First commit for Ender-3V3 SE

First commit for Ender-3V3 SE
This commit is contained in:
CrealityTech
2024-07-10 13:47:44 +08:00
commit e7b2bad8ff
1869 changed files with 1519784 additions and 0 deletions
+819
View File
@@ -0,0 +1,819 @@
#include "AutoOffset.h"
#if ENABLED(USE_AUTOZ_TOOL_2)
/*
* Function Name: getStr(float f)
* Purpose: 将浮点转成字符串(注意:此处不使用ftoa()或%f,是因为部分Marlin版本BUG,会导致浮点转字符失败)
* Params : (float)f 需要转换的浮点值
* Return: (char*) 转换后的字符串
* Attention: 重载调用次数不要超过16
*/
char *getStr(float f)
{
static char str[16][16];
static int index = 0;
memset(str[index % 16], '\0', 16);
sprintf(str[index % 16], (f >= 0 ? "+%d.%03d" : "-%d.%03d"), (int)fabs(f), ((int)(fabs(f) * 1000)) % 1000);
return str[index++ % 16];
}
/*
* Function Name: ckGpioIsInited(int pin)
* Purpose: 检测给定pin是否已经初始化过,避免对clk重复初始化而导致时序错乱
* Params : (int)pin 待检测的pin
* Return: (bool) true=pin已初始化过;false=pin未经过初始化。
*/
bool HX711::ckGpioIsInited(int pin)
{
static int pinList[32] = {0};
FOR_LOOP_TIMES(i, 0, 32, {CHECK_AND_RETURN((pinList[i] == pin), true);CHECK_AND_RUN_AND_RETURN((pinList[i] == 0), {pinList[i] = pin;}, false); });
return true;
}
/*
* Function Name: init(int clkPin, int sdoPin)
* Purpose: HX711驱动初始化(80HZ采样率)
* Params : (int)clkPin HX711对应的时钟信号
* (int)sdoPin HX711对应的数据信号
* Return: 无
*/
void HX711::init(int clkPin, int sdoPin)
{
this->clkPin = clkPin;
this->sdoPin = sdoPin;
CHECK_AND_RUN((!HX711::ckGpioIsInited(sdoPin)), GPIO_SET_MODE(sdoPin, 0));
CHECK_AND_RUN((!HX711::ckGpioIsInited(clkPin)), {GPIO_SET_MODE(clkPin, 1); GPIO_SET_VAL(clkPin, 0); });
}
/*
* Function Name: getVal(bool isShowMsg)
* Purpose: 阻塞并读取压力值,最大阻塞时间20ms
* Params : (bool)isShowMsg 是否打印调试信息
* Return: (int)读取到的压力值
* Attention: 要达到80HZ的采样速率,要保证HX711的频率配置引脚已给对应电平
*/
int HX711::getVal(bool isShowMsg)
{
static unsigned int lastTickMs = 0;
int count = 0;
unsigned int ms = GET_TICK_MS();
GPIO_SET_VAL(clkPin, 0);
while (GPIO_GET_VAL(sdoPin) == 1 && (GET_TICK_MS() - ms <= 20)) //采样率80Hz(12ms周期),这里最大给20ms延时
MARLIN_CORE_IDLE();
DIASBLE_ALL_ISR();
for (int i = 0; i < 24; i++)
{
GPIO_SET_VAL(clkPin, 1);
count = count << 1;
GPIO_SET_VAL(clkPin, 0);
CHECK_AND_RUN((GPIO_GET_VAL(sdoPin) == 1), (count++));
}
GPIO_SET_VAL(clkPin, 1);
count |= ((count & 0x00800000) != 0 ? 0xFF000000 : 0); //24位有符号,转成32位有符号
GPIO_SET_VAL(clkPin, 0);
ENABLE_ALL_ISR();
CHECK_AND_RUN(isShowMsg, {PRINTF("T=%08d, S=%08d\n", (int)(GET_TICK_MS() - lastTickMs), (int)count);lastTickMs = GET_TICK_MS(); });
return count;
}
/*
* Function Name: hFilter(double *vals, int count, double cutFrqHz, double acqFrqHz)
* Purpose: 对数据进行高通滤波
* Params : (double*)vals 待滤波的数据
(int)count 待滤波的数据长度
(double)cutFrqHz 滤波器的截止频率
* (double)acqFrqHz 滤波器的采样频率(等同于HX711的采样频率80HZ)
* Return: 无
*/
void Filters::hFilter(double *vals, int count, double cutFrqHz, double acqFrqHz)
{
double rc = 1.0f / 2.0f / PI / cutFrqHz;
double coff = rc / (rc + 1 / acqFrqHz);
double vi = vals[0], viPrev = vals[0], vo = 0, voPrev = 0;
FOR_LOOP_TIMES(i, 0, count, {
vi = vals[i];
vo = (vi - viPrev + voPrev) * coff;
voPrev = vo;
viPrev = vi;
vals[i] = fabs(vo);
});
}
/**冒泡排序
*升序
*/
static void BubbleSort(double arr[],int len)
{
int i,j;
double tem;
for(i=len-1;i>0;i--)
{
for(j=0;j<i;j++)
{
if(arr[j]>arr[j+1])
{
tem = arr[j];
arr[j] = arr[j+1];
arr[j+1] = tem;
}
}
}
}
/*
* Function Name: tFilter(double *vals, int count)
* Purpose: 对数据进行毛刺滤波
* Params : (double)cutFrqHz 滤波器的截止频率
* (double)acqFrqHz 滤波器的采样频率(等同于HX711的采样频率80HZ)
* Return: 无
*/
void Filters::tFilter(double *vals, int count)
{
// BubbleSort(vals,count);
FOR_LOOP_TIMES(i, 0, count - 3, {
double minVal = (fabs(vals[i]) < fabs(vals[i+1]) ? vals[i] : vals[i+1]);
vals[i] = fabs(minVal) < fabs(vals[i+2]) ? minVal : vals[i+2];});
}
/*
* Function Name: lFilter(double *vals, int count, double k1New)
* Purpose: 对数据进行低通滤波
* Params : (double*)vals 待滤波的数据
(int)count 待滤波的数据长度
(double)k1New 一阶滤波参数
* Return: 无
*/
void Filters::lFilter(double *vals, int count, double k1New)
{
FOR_LOOP_TIMES(i, 1, count, vals[i] = vals[i - 1] * (1 - k1New) + vals[i] * k1New);
}
/*
* Function Name: readBase()
* Purpose: 获取给定数量内(BASE_COUNT/2)的最大、最小、平均压力值。
* Params : 无
* Return: (xyz_long_t) x=MIN; y=AVG; z=MAX;
*/
xyz_long_t ProbeAcq::readBase()
{
static double vals[PI_COUNT / 2] = {0};
double minVal = +0x00FFFFFF, avgVal = 0, maxVal = -0x00FFFFFF; // min avg max
FOR_LOOP_TIMES(i, 0, PI_COUNT / 2, {this->hx711.getVal(false); });
FOR_LOOP_TIMES(i, 0, PI_COUNT / 2, {vals[i] = this->hx711.getVal(false);});
Filters::tFilter(vals, PI_COUNT / 2);
Filters::lFilter(vals, PI_COUNT / 2, LFILTER_K1_NEW);
ARY_MIN(minVal, vals, PI_COUNT / 2);
ARY_MAX(maxVal, vals, PI_COUNT / 2);
ARY_AVG(avgVal, vals, PI_COUNT / 2);
#if ENABLED(SHOW_MSG)
PRINTF("\n***BASE:MIN=%d, AVG=%d, MAX=%d***\n\n", (int)minVal, (int)avgVal, (int)maxVal);
#endif
xyz_long_t xyz = {(int)minVal, (int)avgVal, (int)maxVal};
return xyz;
}
/*
* Function Name: checHx711()
* Purpose: 检测HX711模块是否工作正常
* Params : 无
* Return: true=正常;false=不正常;
* Attention: 理论上,HX711在一定时间内,最大与最值压力差应大于100,且小于MIN_HOLD。
*/
bool ProbeAcq::checHx711()
{
xyz_long_t bv = readBase();
return (abs(bv.x - bv.z) < 100 || abs(bv.x - bv.z) > MIN_HOLD) ? false : true;
}
// probeTimes(0, basePos_mm, 0.02, -10, 0, MIN_HOLD, MAX_HOLD));
float ProbeAcq::probeTimes(int max_times, xyz_float_t rdy_pos, float step_mm, float min_dis_mm, float max_z_err, int min_hold, int max_hold)
{
ProbeAcq pa;
float mm0 = 0, mm1 = 0;
pa.hx711.init(HX711_SCK_PIN, HX711_SDO_PIN);
pa.minZ_mm = min_dis_mm;
pa.basePos_mm = rdy_pos;
pa.baseSpdXY_mm_s = 100;
pa.baseSpdZ_mm_s = 5;
pa.step_mm = step_mm;
pa.minHold = min_hold;
pa.maxHold = max_hold;
FOR_LOOP_TIMES(i, 0, (max_times <= 0 ? 1 : max_times), {
mm0 = pa.probePointByStep()->outVal_mm;
CHECK_AND_RETURN(max_times <= 0, mm0);
mm1 = pa.probePointByStep()->outVal_mm;
CHECK_AND_RETURN(fabs(mm0 - mm1) <= max_z_err, (mm0 + mm1) / 2);
});
return (mm0 + mm1) / 2;
}
/*
* Function Name: shakeZAxis(int times)
* Purpose: 振动Z轴以消除间隙应力
* Params : (int)times 振动的次数
*/
void ProbeAcq::shakeZAxis(int times)
{
float steps[] = STEPS_PRE_UNIT;
int runStep = 0.01* steps[2]; //获取每步进step_mm距离,对应电机的脉冲数量
runStep = runStep <= 0 ? 1 : runStep;
int delayUs = (11.0f * 1000 / runStep) / 2; //保证12ms左右,Z轴电机运动step_mm的距离
delayUs = delayUs <= 10 ? 10 : delayUs;
int dir = AXIS_Z_DIR_GET();
FOR_LOOP_TIMES(i, 0, times, {
AXIS_Z_DIR_SET(Z_DIR_ADD);
FOR_LOOP_TIMES(j, 0, 4 * runStep, AXIS_Z_STEP_PLUS(delayUs / 2));
AXIS_Z_DIR_SET(Z_DIR_DIV);
FOR_LOOP_TIMES(j, 0, 4 * runStep, AXIS_Z_STEP_PLUS(delayUs / 2));
MARLIN_CORE_IDLE();
});
AXIS_Z_DIR_SET(dir);
}
/*
* Function Name: calMinZ()
* Purpose: 根据触发后压力队列中的压力值,计算出对应的z轴高度
* Params : 无
* Return: 无
*/
void ProbeAcq::calMinZ()
{
double* valP_t = &this->valP[PI_COUNT]; //rock_开始没有*2,数组越界使用 20230204
double* posZ_t = &this->posZ[PI_COUNT]; //
// 1、滤波 rock
Filters::tFilter(this->valP, PI_COUNT * 2);
Filters::hFilter(this->valP, PI_COUNT * 2, RC_CUTE_FRQ, 80);
Filters::lFilter(this->valP, PI_COUNT * 2, LFILTER_K1_NEW);
// 2、打印结果
#if ENABLED(SHOW_MSG)
PRINTF("%s", "\nx=[");
FOR_LOOP_TIMES(i, 0, PI_COUNT, PRINTF((i == (PI_COUNT - 1) ? "%s]\n\n" : "%s,"), getStr(posZ_t[i])));
PRINTF("%s", "y=[");
FOR_LOOP_TIMES(i, 0, PI_COUNT, PRINTF((i == (PI_COUNT - 1) ? "%s]\n\n" : "%s,"), getStr(valP_t[i])));
#endif
// 3、对数据进行归一化,方便处理
double valMin = +0x00FFFFFF, valMax = -0x00FFFFFF;
ARY_MIN(valMin, valP_t, PI_COUNT);
ARY_MAX(valMax, valP_t, PI_COUNT);
FOR_LOOP_TIMES(i, 0, PI_COUNT, {valP_t[i] = (valP_t[i] - valMin) / (valMax - valMin);});
// 4、计算并按给定角度翻转数据,以方便计算出最早的触发点
double angle = atan((valP_t[PI_COUNT - 1] - valP_t[0]) / PI_COUNT);
double sinAngle = sin(-angle), cosAngle = cos(-angle);
FOR_LOOP_TIMES(i, 0, PI_COUNT, valP_t[i] = (i - 0) * sinAngle + (valP_t[i] - 0) * cosAngle + 0); //延原点(0,0)顺时针旋转angle度,这里可以不考虑X轴坐标值
// 5、找出翻转后的最小值索引
valMin = +0x00FFFFFF;
ARY_MIN_INDEX(valMin, this->outIndex, valP_t, PI_COUNT);
this->outVal_mm = posZ[this->outIndex + PI_COUNT];
#if ENABLED(SHOW_MSG)
PRINTF("***CalZ Idx=%d, Z=%s***\n", this->outIndex, getStr(this->outVal_mm));
#endif
}
/*
* Function Name: checkTrigger(int fitVal, int unfitDifVal)
* Purpose: 触发状态检测,用于检测喷头是否与压力传感器正常接触
* Params : (int)fitVal RC低通滤波后的压力值,用于特征检测
* (int)unfitDifVal 未滤波但去零后的压力值,用于超压检测
* Return: (bool) true=检测到解发或中止;false=未满足触发条件。
*/
bool ProbeAcq::checkTrigger()
{
static double vp_t[PI_COUNT * 2] = {0};
static double *valP_t = &vp_t[PI_COUNT]; //rock_20230204
#if ENABLED(SHOW_MSG)
//static long long lastTickMs = 0, lastUnfitDifVal = 0;
//PRINTF("T=%08d , S=%08d , U=%08d \n", (int)(GET_TICK_MS() - lastTickMs), fitVal, unfitDifVal);
//lastTickMs = GET_TICK_MS();
#endif
// 0、复制一份用于检测,防止对源数据造成影响
FOR_LOOP_TIMES(i, 0, PI_COUNT * 2, vp_t[i] = this->valP[i]);
// 1、数据滤波 rock
Filters::tFilter(vp_t, PI_COUNT * 2);
Filters::hFilter(vp_t, PI_COUNT * 2, RC_CUTE_FRQ, 80);
Filters::lFilter(vp_t, PI_COUNT * 2, LFILTER_K1_NEW);
// 2、最高优先级,到达最小位置还未触发,则强制停止
CHECK_AND_RETURN((this->posZ[PI_COUNT - 1] <= this->minZ_mm), true);
// 3、最高优先级,压力大于最大压力,则无条件停止。
CHECK_AND_RETURN((abs(valP_t[PI_COUNT - 1]) > this->maxHold && abs(valP_t[PI_COUNT - 2]) > this->maxHold && abs(valP_t[PI_COUNT - 3]) > this->maxHold), true);
// 4、检测点数未满足最小需求
CHECK_AND_RETURN(this->valP[0] == 0, false);
// 5、检测未尾3个点大小的是否有序递增
CHECK_AND_RETURN((!((valP_t[PI_COUNT - 1] > valP_t[PI_COUNT - 2]) && (valP_t[PI_COUNT - 2] > valP_t[PI_COUNT - 3]))), false);
// 6、检测未3个点绝对值是否大于其它任意点
FOR_LOOP_TIMES(i, 0, PI_COUNT - 3, CHECK_AND_RETURN((valP_t[PI_COUNT - 1] < valP_t[i] || valP_t[PI_COUNT - 2] < valP_t[i] || valP_t[PI_COUNT - 3] < valP_t[i]), false));
// 6、对数据进行归一化,方便处理
double valMin = +0x00FFFFFF, valMax = -0x00FFFFFF, valAvg = 0;
float valP_t_f[PI_COUNT] = {0};
ARY_MIN(valMin, valP_t, PI_COUNT);
ARY_MAX(valMax, valP_t, PI_COUNT);
ARY_AVG(valAvg, valP_t, PI_COUNT);
FOR_LOOP_TIMES(i, 0, PI_COUNT, valP_t_f[i] =((double)valP_t[i] - valMin) / (valMax - valMin));
// 7、保证所有点针对最后一个点的斜率均大于40度,可有郊防止过于灵敏而导致的误触发。
FOR_LOOP_TIMES(i, 0, PI_COUNT - 1, CHECK_AND_RETURN(((valP_t_f[PI_COUNT - 1] - valP_t_f[i]) / ((32 - i) * 1.0f / 32) < 0.8), false));
// 8、限制最小值,防止误触发。
CHECK_AND_RETURN(!(valP_t[PI_COUNT - 1] > this->minHold && valP_t[PI_COUNT - 2] > (this->minHold / 2) && valP_t[PI_COUNT - 3] > (this->minHold / 3)), false);
return true;
}
/*
* Function Name: probePointByStep()
* Purpose: 单步进法测量,并返回测量结果。
* Params : 无
* Return: (ProbeAcq) this指针
*/
ProbeAcq* ProbeAcq::probePointByStep()
{
static char msg[128] = {0};
int unfitAvgVal = 0, nowVal = 0, runSteped = 0;
this->outIndex = PI_COUNT - 1;
this->outVal_mm = 0;
#if ENABLED(SHOW_MSG)
PRINTF("\nPROBE: rdyX=%s, rdyY=%s, rdyZ=%s, spdXY_mm_s=%s, spdZ_mm_s=%s",
getStr(this->basePos_mm.x), getStr(this->basePos_mm.y), getStr(this->basePos_mm.z), getStr(this->baseSpdXY_mm_s), getStr(this->baseSpdZ_mm_s));
PRINTF("len_mm=%s, baseCount=%d, minHold=%d, maxHold=%d, step_mm=%s\n\n",
getStr(this->minZ_mm), PI_COUNT, this->minHold, this->maxHold, getStr(this->step_mm));
#endif
memset(this->posZ, 0, sizeof(this->posZ));
memset(this->valP, 0, sizeof(this->valP));
memset(msg, 0, sizeof(msg));
sprintf(msg, "G1 F%s X%s Y%s Z%s", getStr(this->baseSpdXY_mm_s * 60), getStr(this->basePos_mm.x), getStr(this->basePos_mm.y), getStr(this->basePos_mm.z));
RUN_AND_WAIT_GCODE_CMD(msg, true); //运动到等测量点(准备点)
int oldBedTmp = GET_BED_TAR_TEMP();
int oldHotTmp = GET_HOTEND_TAR_TEMP(0);
SET_BED_TEMP(0);
SET_HOTEND_TEMP(0, 0);
unfitAvgVal = readBase().y; //获取干净的数据
float steps[] = STEPS_PRE_UNIT; // { 80, 80, 400, 424.9 }
int runStep = this->step_mm * steps[2]; //获取每步进step_mm距离,对应电机的脉冲数量
runStep = runStep <= 0 ? 1 : runStep;
int delayUs = (12.0f * 1000 / runStep) / 2; //保证12ms左右,Z轴电机运动step_mm的距离
delayUs = delayUs <= 10 ? 10 : delayUs;
this->shakeZAxis(20);
AXIS_Z_ENABLE();
int dir = AXIS_Z_DIR_GET();
AXIS_Z_DIR_SET(Z_DIR_DIV);
do{
FOR_LOOP_TIMES(i, 0, runStep, AXIS_Z_STEP_PLUS(delayUs)); //向给定方向运动给定步进距离
runSteped += runStep;
MARLIN_CORE_IDLE();
nowVal = this->hx711.getVal(0);
FOR_LOOP_TIMES(i, 0, PI_COUNT * 2 - 1, this->valP[i] = this->valP[i + 1]);
FOR_LOOP_TIMES(i, 0, PI_COUNT * 2 - 1, this->posZ[i] = this->posZ[i + 1]);
this->valP[PI_COUNT * 2 - 1] = nowVal - unfitAvgVal; //将压力值放入队列
this->posZ[PI_COUNT * 2 - 1] = current_position[2] - (float)runSteped / steps[2]; //将压力值对应的z位置放入队列
if (checkTrigger() == true) //触发条件检测
{
calMinZ(); //数据整理与计算
AXIS_Z_DIR_SET(Z_DIR_ADD);
FOR_LOOP_TIMES(i, 0, runSteped, AXIS_Z_STEP_PLUS(delayUs / 4)); //返回到触发点或准备点
AXIS_Z_DIR_SET(dir);
break;
}
} while (1);
SET_BED_TEMP(oldBedTmp);
SET_HOTEND_TEMP(oldHotTmp, 0);
return this;
}
/*
* Function Name: clearByBrush(xyz_float_t basePos_mm, float norm, float minTemp, float maxTemp)
* Purpose: 触发状态检测,用于检测喷头是否与压力传感器正常接触
* Params : (xyz_float_t)basePos_mm 喷头擦式过程中,毛刷的坐标
* (float)norm 喷头擦式过程中,喷头前后左右移动的距离,与毛刷的大小有关
* (float)minTemp 在此温度及以下,才可保证耗材不再渗出
* (float)maxTemp 在此温度及以上,才可保证耗材已融化
* Return: (bool) true=擦式成功;false=擦式失败。
* Attention: 由于喷头擦式过程中,需要融化耗材,所在此处的minTemp和maxTemp需与GCODE中的温度相对应,或与上一次使用的耗材类型对应
*/
bool clearByBed(xyz_float_t startPos, xyz_float_t endPos, float minTemp, float maxTemp)
{
ProbeAcq pa;
pa.hx711.init(HX711_SCK_PIN, HX711_SDO_PIN);
DO_BLOCKING_MOVE_TO_Z(startPos.z, 5);
DO_BLOCKING_MOVE_TO_XY(startPos.x, startPos.y-10, 50);
Popup_Window_Height(Nozz_Hot); //刷新对高页面显示_喷嘴加热中
SET_HOTEND_TEMP(maxTemp, 0);
SET_BED_TEMP(65); //暂时取消热床加热
WAIT_HOTEND_TEMP(60 * 5 * 1000, 5);//等待温度达到设定值
WAIT_BED_TEMP(60 * 5 * 1000, 2);
Popup_Window_Height(Nozz_Clear); //刷新对高页面显示_擦喷嘴中
In_out_feedtock_level(LEVEL_DISTANCE,FEEDING_DEF_SPEED,false); //回抽50mm
DO_BLOCKING_MOVE_TO_XY(startPos.x, startPos.y, 50);
float start_mm = ProbeAcq::probeTimes(3, startPos, 0.03, -10, 0.2, MIN_HOLD, MAX_HOLD/2);
PRINT_LOG("clear_nozzle_start_z:",start_mm);
float end_mm= ProbeAcq::probeTimes(3, endPos, 0.03, -10, 0.2, MIN_HOLD, MAX_HOLD/2);
PRINT_LOG("clear_nozzle_end_z:",end_mm);
startPos.z=start_mm;endPos.z=end_mm;
// PRINT_LOG("clear_nozzle_start_z:",start_mm,"clear_nozzle_start_z:",end_mm);
DO_BLOCKING_MOVE_TO_XYZ(startPos.x, startPos.y+3, startPos.z, 50);
// SET_HOTEND_TEMP(maxTemp, 0);
// WAIT_HOTEND_TEMP(60 * 5 * 1000, 5);//等待温度达到设定值
// RUN_AND_WAIT_GCODE_STR("G1 F500 X%s Y%s z%s", true, getStr(startPos.x), getStr(startPos.y),getStr(startPos.z));
// DO_BLOCKING_MOVE_TO_XYZ(endPos.x, endPos.y, endPos.z-0.1, 5); //往前移动3mm,防止上次有耗材。再次粘连
DO_BLOCKING_MOVE_TO_XYZ(endPos.x, endPos.y-3, endPos.z-0.1, 5);
endPos.x-=10;endPos.y-=10;
DO_BLOCKING_MOVE_TO_XYZ(endPos.x, endPos.y, endPos.z-0.1, 5);//往回45°拉一点,撤掉余料
RUN_AND_WAIT_GCODE_CMD("G28 Z", true);
/*
int unfitAvgVal = pa.readBase().y;
// RUN_AND_WAIT_GCODE_STR("G1 F100 X%s Y%s z%s", false, getStr(startPos.x), getStr(startPos.y),getStr(start_mm));
DO_BLOCKING_MOVE_TO_XY(startPos.x, startPos.y, 50);
DO_BLOCKING_MOVE_TO_Z(start_mm+0.2 , 5);
SET_HOTEND_TEMP(minTemp, 0);
// RUN_AND_WAIT_GCODE_STR("G1 F100 X%s Y%s", false, getStr(endPos.x), getStr(endPos.y));
RUN_AND_WAIT_GCODE_STR("G1 F200 X%s Y%s z%s", false, getStr(endPos.x), getStr(endPos.y),getStr(end_mm));
SET_HOTEND_TEMP(minTemp, 0);
SET_FAN_SPD(255);
float steps[] = STEPS_PRE_UNIT;
int runStep = 0.02 * steps[2];
int delayUs = (12.0f * 1000 / runStep) / 2;
int oldDir = AXIS_Z_DIR_GET();
AXIS_Z_ENABLE();
while (AXIS_XYZE_STATUS()){
int nowVal = pa.hx711.getVal(0);
// PRINT_LOG("nowVal:",nowVal,"unfitAvgVal:",unfitAvgVal,"nowVal - unfitAvgVal:",abs(nowVal - unfitAvgVal));
CHECK_AND_RUN_AND_ELSE((abs(nowVal - unfitAvgVal) < (MIN_HOLD)), AXIS_Z_DIR_SET(Z_DIR_DIV), AXIS_Z_DIR_SET(Z_DIR_ADD));
FOR_LOOP_TIMES(i, 0, runStep, AXIS_Z_STEP_PLUS(delayUs));
MARLIN_CORE_IDLE();
}
AXIS_Z_DIR_SET(oldDir);
SET_HOTEND_TEMP(minTemp, 0);
SET_FAN_SPD(255); //打开模型散热风扇,保证更快速度的降温
WAIT_HOTEND_TEMP(60 * 5 * 1000, 5); //等待温度达到设定值
AXIS_Z_DIR_SET(Z_DIR_ADD);
// PRINT_LOG("endPos.x = ", endPos.x + (endPos.x - startPos.x) / 5," endPos.y = ", endPos.y + (endPos.y - startPos.y) / 5," GET_CURRENT_POS().z + 3.5 = ",GET_CURRENT_POS().z + 3.5);
RUN_AND_WAIT_GCODE_STR("G1 F300 X%s Y%s Z%s", true, getStr(endPos.x + (endPos.x - startPos.x) / 5), getStr(endPos.y + (endPos.y - startPos.y) / 5), getStr(GET_CURRENT_POS().z + 3));
pa.shakeZAxis(100);
AXIS_Z_DIR_SET(Z_DIR_ADD);
RUN_AND_WAIT_GCODE_CMD("G28 Z", true);
SET_HOTEND_TEMP(minTemp, 0);
// SET_BED_TEMP(60);
*/
return true;
}
/*
* Function Name: probeByPress(xyz_float_t basePos_mm, float* outZ)
* Purpose: 使用压力传感器对喷头高度测量
* Params : (xyz_float_t)basePos_mm 测量过程中,喷头位于压力传感器正中的坐标
* (float*)outZ 测量结果,共测量两次,取平均值。
* Return: (bool) true=测量成功;false=测量失败。
* Attention: 若喷头未擦式干净并粘有耗材,会导致测量失败。
*/
bool probeByPress(xyz_float_t basePos_mm, float* outZ)
{
/*
float outZ_mm[5] = {0};
//CHECK_AND_RETURN((!(pa.checHx711() || pa.checHx711())), false); //检测模块工作是否正常
FOR_LOOP_TIMES(i, 0, 5, outZ_mm[i] = ProbeAcq::probeTimes(0, basePos_mm, 0.02, -10, 0, MIN_HOLD, MAX_HOLD));
ARY_SORT(outZ_mm, 5);
PRINTF("\n***PROBE BY PRESS: z=%s, zs={%s, %s, %s, %s, %s}***\n", getStr(outZ_mm[2]), getStr(outZ_mm[0]), getStr(outZ_mm[1]), getStr(outZ_mm[2]), getStr(outZ_mm[3]), getStr(outZ_mm[4]));
*outZ = outZ_mm[2];
*/
//为了节约时间,由原来的5次改成3次
float outZ_mm[3] = {0};
//CHECK_AND_RETURN((!(pa.checHx711() || pa.checHx711())), false); //检测模块工作是否正常
FOR_LOOP_TIMES(i, 0, 3, outZ_mm[i] = ProbeAcq::probeTimes(0, basePos_mm, 0.02, -10, 0, MIN_HOLD, MAX_HOLD));
ARY_SORT(outZ_mm, 3);
#if ENABLED(SHOW_MSG)
PRINTF("\n***PROBE BY PRESS: z=%s, zs={%s, %s, %s}***\n", getStr(outZ_mm[1]), getStr(outZ_mm[0]), getStr(outZ_mm[1]), getStr(outZ_mm[2]));
#endif
*outZ = outZ_mm[1];
PRINTF("\n***PROBE BY PRESS: press_z=%s***\n", getStr(*outZ));
return true;
}
/*
* Function Name: probeByTouch(xyz_float_t rdyPos_mm, float* outZ)
* Purpose: 使用CR-TOUCH测量触发高度
* Params : (xyz_float_t)basePos_mm 测量过程中,CR-TOUCH位于压力传感器正中的坐标
* (float*)outZ 测量结果,共测量两次,取第二次。
* Return: (bool) true=测量成功;false=测量失败。
* Attention: CR-TOUCH的测量流程,要与HOME点的测量流程相一致。
*/
bool probeByTouch(xyz_float_t rdyPos_mm, float* outZ)
{
ProbeAcq pa;
pa.shakeZAxis(20);
xyz_float_t touchOftPos = CRTOUCH_OFT_POS;
int oldNozTmp = GET_NOZZLE_TAR_TEMP(0);
int oldBedTmp = GET_BED_TAR_TEMP();
DO_BLOCKING_MOVE_TO_Z(rdyPos_mm.z, 5);
DO_BLOCKING_MOVE_TO_XY(rdyPos_mm.x - touchOftPos.x, rdyPos_mm.y - touchOftPos.y, 100);
*outZ = PROBE_PPINT_BY_TOUCH(rdyPos_mm.x - touchOftPos.x, rdyPos_mm.y - touchOftPos.y); //调用Marlin固有的CR-TOUCH测量接口
PRINTF("\n***PROBE BY TOUCH: touch_z=%s***\n", getStr(*outZ));
SET_HOTEND_TEMP(oldNozTmp, 0);
SET_BED_TEMP(oldBedTmp);
probe.stow(); //rock
return true;
}
/*
* Function Name: printTestResult(float *zTouch, float *zPress)
* Purpose: 打印测试结果
* Params : (float*)zTouch TOUCH传感器的测量结
* (float*)zPress 压力传感器的测量结果
* Return: 无
* Attention: 最大只能打印128组测试结果
*/
void printTestResult(float *zTouch, float *zPress)
{
static float acqVals[128][3] = {0}; //最大保存128组测量数据
static int acqValIndex = 0;
PRINTF("\n***GET Z OFFSET: zTouch={%s, %s, %s}, zPress={%s, %s, %s}, zOffset={%s, %s, %s}***\n",
getStr(zTouch[0]), getStr(zTouch[1]), getStr(zTouch[2]), getStr(zPress[0]), getStr(zPress[1]), getStr(zPress[2]),
getStr(zPress[0] - zTouch[0]), getStr(zPress[1] - zTouch[1]), getStr(zPress[2] - zTouch[2]));
float zt_avg = 0, zp_avg = 0;
ARY_AVG(zt_avg, zTouch, 3);
ARY_AVG(zp_avg, zPress, 3);
acqVals[acqValIndex][0] = zp_avg;
acqVals[acqValIndex][1] = zt_avg;
acqVals[acqValIndex][2] = zp_avg - zt_avg;
acqValIndex = (acqValIndex >= 127 ? 127 : (acqValIndex + 1));
FOR_LOOP_TIMES(i, 0, acqValIndex, PRINTF("%d\t%s\t%s\t%s\n", i, getStr(acqVals[i][0]), getStr(acqVals[i][1]), getStr(acqVals[i][2])));
}
//一次对高
float Hight_One(xyz_float_t pressPos)
{
float temp_value=0,zoffset_avg=0;
float zTouch[1] = {0};
float zPress[1] = {0};
bool isRunProByPress=true, isRunProByTouch=true;
SET_BED_LEVE_ENABLE(false);
// CHECK_AND_RUN(isRunProByTouch, {FOR_LOOP_TIMES(i, 0, 3, {probeByTouch(rdyPos[i], &zTouch[i]); rdyPos[i].z = zTouch[i];})});
CHECK_AND_RUN(isRunProByTouch, {FOR_LOOP_TIMES(i, 0, 1, {probeByTouch(pressPos, &zTouch[0]); pressPos.z = zTouch[0];})});
//3. 使用压力传感器对喷头高度进行测量
SET_BED_LEVE_ENABLE(false);
// CHECK_AND_RUN(isRunProByPress, FOR_LOOP_TIMES(i, 0, 3, {probeByPress(rdyPos[i], &zPress[i]); zPress[i] += NOZ_TEMP_OFT_MM;}));
CHECK_AND_RUN(isRunProByPress, FOR_LOOP_TIMES(i, 0, 1, {probeByPress(pressPos, &zPress[0]); zPress[0] += NOZ_TEMP_OFT_MM;}));
//4. 处理结果
temp_value = (zPress[0] - zTouch[0]);
printTestResult(zTouch, zPress);
DO_BLOCKING_MOVE_TO_Z(5, 5);
return temp_value;
}
//多次对高函数 Multiple 暂时先实现两次对高
float Multiple_Hight(bool isRunProByPress, bool isRunProByTouch)
{
float zoffset_value[3]={0};
uint8_t loop_max=0,loop_num=0;
xyz_float_t pressPos = PRESS_XYZ_POS;
float temp_value=0,temp_zoffset=0,temp_zoffset1=0,zoffset_avg=0;
for(loop_num=0;loop_num<ZOFFSET_REPEAT_NIN;loop_num++)
{
pressPos.y-=(loop_num*5);
zoffset_value[loop_num]=Hight_One(pressPos);
PRINTF("\n***OUTPUT_ZOFFSET: zOffset=%s***\n", getStr(zoffset_value[loop_num]));
RUN_AND_WAIT_GCODE_CMD("G28", true); //测量前先获取一次HOME点
}
temp_zoffset=fabs(zoffset_value[0])-fabs(zoffset_value[1]);
if(fabs(temp_zoffset)<=ZOFFSET_COMPARE) //采集到的值统一
{
ARY_AVG(zoffset_avg, zoffset_value, 2);
SET_BED_LEVE_ENABLE(true); //打开自动调平
In_out_feedtock_level(LEVEL_DISTANCE,FEEDING_DEF_SPEED,true); //进料50mm
SET_HOTEND_TEMP(140, 0);
SET_FAN_SPD(255); //打开模型散热风扇,保证更快速度的降温
WAIT_HOTEND_TEMP(60 * 5 * 1000, 5); //等待温度达到设定值
Popup_Window_Height(Nozz_Finish); //对高完成刷新页面
return zoffset_avg;
}
else //如果不统一就多调试几次
{
for(loop_max=2; loop_max<ZOFFSET_REPEAT_NAX;loop_max++)
{
pressPos.y-=(loop_max-2)*5;
zoffset_value[2]=Hight_One(pressPos);
temp_zoffset=fabs(zoffset_value[2])-fabs(zoffset_value[0]);
temp_zoffset1=fabs(zoffset_value[2])-fabs(zoffset_value[1]);
if((fabs(temp_zoffset)>ZOFFSET_COMPARE)&&(fabs(temp_zoffset1)>ZOFFSET_COMPARE))//两个都不在范围内
{
continue; //返回继续采集
}
else if((fabs(temp_zoffset)<=ZOFFSET_COMPARE)||(fabs(temp_zoffset1)<=ZOFFSET_COMPARE))
{
if((fabs(temp_zoffset)<=ZOFFSET_COMPARE))
{
zoffset_value[1]=zoffset_value[2];
}
else
{
zoffset_value[0]=zoffset_value[2];
}
ARY_AVG(zoffset_avg, zoffset_value, 2);
SET_BED_LEVE_ENABLE(true); //打开自动调平
In_out_feedtock_level(LEVEL_DISTANCE,FEEDING_DEF_SPEED,true); //进料50mm
SET_HOTEND_TEMP(140, 0);
SET_FAN_SPD(255); //打开模型散热风扇,保证更快速度的降温
WAIT_HOTEND_TEMP(60 * 5 * 1000, 5); //等待温度达到设定值
Popup_Window_Height(Nozz_Finish); //对高完成刷新页面
return zoffset_avg;
}
}
//防止Z轴补偿有-0.04的情况
if(ZOFFSET_REPEAT_NAX==loop_max) //防止输出是0,最后直接算一个。
{
/* 有弹窗提示客户调平失败,就取消这段,一直得到最后的值
ARY_AVG(zoffset_avg,zoffset_value,2);
SET_BED_LEVE_ENABLE(true); //打开自动调平
In_out_feedtock_level(LEVEL_DISTANCE,FEEDING_DEF_SPEED,true); //进料50mm
SET_HOTEND_TEMP(140, 0);
SET_FAN_SPD(255); //打开模型散热风扇,保证更快速度的降温
WAIT_HOTEND_TEMP(60 * 5 * 1000, 5); //等待温度达到设定值
Popup_Window_Height(Nozz_Finish); //对高完成刷新页面
*/
return zoffset_avg;
}
return zoffset_avg; //对高失败
}
// CHECK_AND_RUN((isRunProByPress && isRunProByTouch), SET_Z_OFFSET((zPress[0] - zTouch[0]), false));
}
/*
* Function Name: getZOffset(float* outOffset)
* Purpose: 包括喷头擦式、压力传感器测量喷头高度、CR-TOUCH高度测量三个部分,并返回Z-OFFSET
* Params : (float*)outOffset 测量结果
* Return: (bool) true=测量成功,outZ可用于设定系统补偿;false=测量失败。
* Attention: 测量失败,则不要设置系统Z-OFFSET。
*/
bool getZOffset(bool isNozzleClr, bool isRunProByPress, bool isRunProByTouch, float* outOffset)
{
xyz_float_t pressPos = PRESS_XYZ_POS;
xyz_float_t touchOftPos = CRTOUCH_OFT_POS;
xyz_float_t rdyPos[3] = {{0, 0, HIGHT_UPRAISE_Z}, {0, 0, HIGHT_UPRAISE_Z}, {0, 0, HIGHT_UPRAISE_Z}};
rdyPos[0].x = rdyPos[2].x = (pressPos.x < (BED_SIZE_X_MM / 2) ? (touchOftPos.x < 0) : (touchOftPos.x > 0)) ? pressPos.x : touchOftPos.x + 10;
// rdyPos[0].x = ((pressPos.x < (BED_SIZE_X_MM / 2) ? (touchOftPos.x < 0) : (touchOftPos.x > 0)) ? pressPos.x : touchOftPos.x + 10);//-30
rdyPos[0].x -= 9;
rdyPos[0].y = rdyPos[1].y = ((pressPos.y < (BED_SIZE_Y_MM / 2) ? (touchOftPos.y < 0) : (touchOftPos.y > 0)) ? pressPos.y : touchOftPos.y + 10);//-15
rdyPos[0].y = rdyPos[1].y-=17;
rdyPos[1].x = rdyPos[0].x + (pressPos.x < (BED_SIZE_X_MM / 2) ? +1 : -1) * BED_SIZE_X_MM / 5;
rdyPos[2].y = rdyPos[0].y + (pressPos.y < (BED_SIZE_Y_MM / 2) ? +1 : -1) * BED_SIZE_Y_MM / 5;
rdyPos[2].x = (rdyPos[0].x+(rdyPos[1].x-rdyPos[0].x)/2);
// PRINT_LOG("(rdyPos[1].x-rdyPos[0].x)/2:",(rdyPos[1].x-rdyPos[0].x)/2);
// PRINT_LOG("rdyPos[0].x:",rdyPos[0].x,"rdyPos[1].x:",rdyPos[1].x,"rdyPos[2].x:",rdyPos[2].x);
bool SoftEndstopEnable = soft_endstop._enabled;
bool reenable = planner.leveling_active;
//0. 测量前的准备工作
SET_Z_OFFSET(0, false); //先对z-offset清0,防止当z-offset对测量结果造成影响
RUN_AND_WAIT_GCODE_CMD("G28", true); //测量前先获取一次HOME点
//1. 针对PLA耗材进行喷头擦式
srand(millis());
float ret1 = rand() % 15 + 2; //生成1~10的随机数
// SERIAL_ECHOLNPAIR(" ret1=: ",ret1);
xyz_float_t startPos = {rdyPos[0].x + (rdyPos[1].x - rdyPos[0].x) * 1 / 5-10, rdyPos[0].y + (rdyPos[2].y - rdyPos[0].y) * 2 / 5 + random(0, 9) - 4, 6};
// xyz_float_t startPos = {rdyPos[0].x + (rdyPos[1].x - rdyPos[0].x) * 1 / 5-10, rdyPos[0].y + (rdyPos[2].y - rdyPos[0].y) * 2 / 5 + 9 - 4, 6};
xyz_float_t endPos = {rdyPos[0].x + (rdyPos[1].x - rdyPos[0].x) * 3 / 5, startPos.y, 6};
// startPos.x+=(ret1+15);startPos.y+=(ret1+5);
// endPos.x+=(ret1+15);endPos.y=startPos.y;
startPos.x=CLEAR_NOZZL_START_X;startPos.y=CLEAR_NOZZL_START_Y;
endPos.x=CLEAR_NOZZL_END_X;endPos.y=CLEAR_NOZZL_END_Y;
startPos.z=0;
endPos.z=0;
CHECK_AND_RUN(isNozzleClr, clearByBed(startPos, endPos, 140, 200));
Popup_Window_Height(Nozz_Hight); //刷新对高页面显示_对高测量中
//2. 使用CR-TOUCCH测量触发高度
/*
float zTouch[3] = {0};
SET_BED_LEVE_ENABLE(false);
// CHECK_AND_RUN(isRunProByTouch, {FOR_LOOP_TIMES(i, 0, 3, {probeByTouch(rdyPos[i], &zTouch[i]); rdyPos[i].z = zTouch[i];})});
CHECK_AND_RUN(isRunProByTouch, {FOR_LOOP_TIMES(i, 0, 1, {probeByTouch(pressPos, &zTouch[0]); pressPos.z = zTouch[0];})});
//3. 使用压力传感器对喷头高度进行测量
float zPress[3] = {0};
SET_BED_LEVE_ENABLE(false);
// CHECK_AND_RUN(isRunProByPress, FOR_LOOP_TIMES(i, 0, 3, {probeByPress(rdyPos[i], &zPress[i]); zPress[i] += NOZ_TEMP_OFT_MM;}));
CHECK_AND_RUN(isRunProByPress, FOR_LOOP_TIMES(i, 0, 1, {probeByPress(pressPos, &zPress[0]); zPress[0] += NOZ_TEMP_OFT_MM;}));
Popup_Window_Height(Nozz_Finish); //对高完成刷新页面
//4. 处理结果
float zt_avg = 0, zp_avg = 0;
//一次就不用平均
// ARY_AVG(zt_avg, zTouch, 3);
// ARY_AVG(zp_avg, zPress, 3);
ARY_AVG(zt_avg, zTouch, 1);
ARY_AVG(zp_avg, zPress, 1);
printTestResult(zTouch, zPress);
SET_BED_LEVE_ENABLE(true);
DO_BLOCKING_MOVE_TO_Z(5, 5);
// DO_BLOCKING_MOVE_TO_XY(BED_SIZE_X_MM / 2, BED_SIZE_Y_MM / 2, 50); // 取消无用的步骤 rock_20230528
*outOffset = (zp_avg - zt_avg);
*/
*outOffset=Multiple_Hight(isRunProByPress,isRunProByTouch); //测量两次后得到数据
PRINTF("\n***OUTPUT_ZOFFSET: zOffset=%s***\n", getStr(*outOffset));
//LIMIT(*outOffset, ZOFFSET_VALUE_MIN, ZOFFSET_VALUE_MAX);
soft_endstop._enabled = SoftEndstopEnable;
planner.leveling_active = reenable;
if((*outOffset>ZOFFSET_VALUE_MAX)||(*outOffset<ZOFFSET_VALUE_MIN))return false; //如果对高值太离谱直接不要
return (isRunProByPress && isRunProByTouch); //喷头和CR-TOUCH都测量,数据才有效
}
/*
* Function Name: gcodeG212()
* Purpose: 用于上位机发送测试指令,如G212 C128 B P T C128=测量128次;B=执行擦头操作;P=执行压力优传感器测量操作;T=执行CR-TOUCH测量操作
* Params : 无
* Return: 无
* Attention: 需要在gcode.h中添加 #include "../module/AutoOffset.h" 在gcode.cpp的 case 'G':的break前插入case 212:gcodeG212();break;
*/
void gcodeG212()
{
int count = 1;
if(GET_PARSER_SEEN('C')) count = GET_PARSER_INT_VAL();
if(GET_PARSER_SEEN('H'))
{
HX711 hx711;
hx711.init(HX711_SCK_PIN, HX711_SDO_PIN);
FOR_LOOP_TIMES(i, 0, count, hx711.getVal(1));
return;
}
if(GET_PARSER_SEEN('K'))
{
ProbeAcq pa;
xyz_pos_t cp = PRESS_XYZ_POS;
pa.hx711.init(HX711_SCK_PIN, HX711_SDO_PIN);
pa.minZ_mm = -10; //最多下降10mm
pa.basePos_mm.x = cp.x;
pa.basePos_mm.y = cp.y;
pa.basePos_mm.z = 3;
pa.baseSpdXY_mm_s = 100;
pa.baseSpdZ_mm_s = 5;
pa.step_mm = 0.02; //rock
pa.minHold = MIN_HOLD;
pa.maxHold = MAX_HOLD;
pa.probePointByStep();
return;
}
bool isRunClearNozzle = GET_PARSER_SEEN('B'); //是否需要擦喷头
bool isRunTestByPress = GET_PARSER_SEEN('P'); //是否需要使用压力传感器测量喷头高度
bool isRunTestByTouch = GET_PARSER_SEEN('T'); //是否需要使用CT-TOUCH测量
float zOffset = 0;
CHECK_AND_RUN((isRunClearNozzle || isRunTestByPress || isRunTestByTouch), FOR_LOOP_TIMES(i, 0, count, getZOffset(isRunClearNozzle, isRunTestByPress, isRunTestByTouch, &zOffset)));
}
//对高操作再次封装
#endif
+249
View File
@@ -0,0 +1,249 @@
/*
* Assignment: 用于适配CR-TOUCH自动Z-OFFSET获取模块
* Author: 王玉龙107051
* Date: 2022-12-01
* Version: V2.0
* Description: 使用RC低通滤波+特征法触发检测+旋转法结果计算相结合,用于自动获取Z-OFFSET。
* 内容已包括喷头擦式、CR-TOUCH测量、压力传感器测量。
* Attention: 使用者移植过程中,需保证所有的宏定义正确且运行正常(当前宏定义基于Marlin 2.0.8.3)。
*/
#ifndef __AUTO_OFFSET_H__
#define __AUTO_OFFSET_H__
#include "../inc/MarlinConfig.h"
#include "probe.h"
#include "motion.h"
#include "planner.h"
#include "stepper.h"
#include "settings.h"
#include "../gcode/parser.h"
#include "temperature.h"
#include "../HAL/shared/Delay.h"
#include "../lcd/dwin/e3v2/dwin.h"
#include "../../src/feature/bedlevel/bedlevel.h"
#include "../../src/feature/babystep.h"
#include "probe.h"
#include "stdio.h"
#include "string.h"
#include "../../gcode/gcode.h"
#if ENABLED(USE_AUTOZ_TOOL_2)
#define FOR_LOOP_TIMES(lp, sVal, eVal, fun) for(int lp = sVal; lp < eVal; lp++) fun
#define CHECK_RANGE(val, min, max) ((val > min) && (val < max))
#define CHECK_AND_BREAK(bVal) if(bVal) break
#define CHECK_AND_RUN(bVal, fun) if(bVal) fun
#define CHECK_AND_RETURN(bVal, rVal) if(bVal) return rVal
#define CHECK_AND_RUN_AND_RETURN(bVal, fun, rVal) if(bVal) {fun;return rVal;}
#define CHECK_AND_RUN_AND_ELSE(bVal, fun1, fun2); if(bVal) {fun1;} else {fun2;}
#define ARY_MIN(min, ary, count) for(int i = 0; i < count; i++) {CHECK_AND_RUN(min > ary[i], min = ary[i];)}
#define ARY_MAX(max, ary, count) for(int i = 0; i < count; i++) {CHECK_AND_RUN(max < ary[i], max = ary[i];)}
#define ARY_AVG(avg, ary, count) for(int i = 0; i < count; i++) {avg += ary[i];}; avg /= count
#define ARY_MIN_INDEX(min, index, ary, count) for(int i = 0; i < count; i++) {CHECK_AND_RUN(min >= ary[i], {min = ary[i]; index = i;})}
#define ARY_SORT(ary, count) FOR_LOOP_TIMES(i, 0, count, FOR_LOOP_TIMES(j, i, count, { if(ary[i] > ary[j]){float t = ary[i]; ary[i] = ary[j]; ary[j] = t;}}));
#define PRINTF(str, ...) {char strMsg[128] = {0}; sprintf(strMsg, str, __VA_ARGS__); SERIAL_PRINT_MSG(strMsg);}
#define RUN_AND_WAIT_GCODE_STR(gCode, isWait, ...) {char cmd[128] = {0}; sprintf(cmd, gCode, __VA_ARGS__);PRINTF("\n***RUM GCODE CMD: %s***\n", cmd); RUN_AND_WAIT_GCODE_CMD(cmd, isWait);}
#define WAIT_BED_TEMP(maxTickMs, maxErr) { unsigned int tickMs = GET_TICK_MS(); while (((GET_TICK_MS() - tickMs) < maxTickMs) && (abs(GET_BED_TAR_TEMP() - GET_BED_TEMP()) > maxErr)) MARLIN_CORE_IDLE();}
#define WAIT_HOTEND_TEMP(maxTickMs, maxErr) { unsigned int tickMs = GET_TICK_MS(); while (((GET_TICK_MS() - tickMs) < maxTickMs) && (abs(GET_HOTEND_TAR_TEMP(0) - GET_HOTEND_TEMP(0)) > maxErr)) MARLIN_CORE_IDLE();}
#define MIN_HOLD 2000 //触发检测的最小阈值,防止误触发
#define MAX_HOLD 10000 //触发检测的最大阈值,防止过触发
#define RC_CUTE_FRQ 1 //RC滤波器的截止频率0.1~10,值越小=触发越灵敏;值越大=触发越迟钝。
//速度越慢,截止频率越小
/***以下宏定义,需要根据Marlin的不同版本,对应实现***/
#define HX711_SCK_PIN PA4
#define HX711_SDO_PIN PC6
//是否有打印信息
#define SHOW_MSG 0
//压力传感器安装位置(对应螺丝孔的位置)
#define PRESS_XYZ_POS {AUTOZ_TOOL_X, AUTOZ_TOOL_Y, 0}
//喷头的温度膨胀补偿,即26到200度时,喷头伸长的长度
#define NOZ_TEMP_OFT_MM 0.05
#define NOZ_AUTO_OFT_MM 0.02 //0.04
//低通滤波器系数
#define LFILTER_K1_NEW 0.9f
//以喷头为基准0点,CR-TOUCH的安装位置
#define CRTOUCH_OFT_POS NOZZLE_TO_PROBE_OFFSET
//热床的X方向尺寸,单位mm
#define BED_SIZE_X_MM X_BED_SIZE //220
//热床的Y方向尺寸,单位mm
#define BED_SIZE_Y_MM Y_BED_SIZE //220
//对高过程中Z轴抬升的高度,单位mm
#define HIGHT_UPRAISE_Z 4//8
//擦喷嘴的坐标
#define CLEAR_NOZZL_START_X 0
#define CLEAR_NOZZL_START_Y 15
#define CLEAR_NOZZL_END_X 0
#define CLEAR_NOZZL_END_Y 60
//自动对高的次数repeat
#define ZOFFSET_REPEAT_NIN 2
#define ZOFFSET_REPEAT_NAX 5
#define ZOFFSET_COMPARE 0.05
#define ZOFFSET_VALUE_MIN -5
#define ZOFFSET_VALUE_MAX 0
//获取当前喷头的xyz的坐标
#define GET_CURRENT_POS() current_position
//检测GCODE指令是否包含给定参数
#define GET_PARSER_SEEN(c) parser.seen(c)
//获取GCODE指令中给定参数的值int型
#define GET_PARSER_INT_VAL() parser.value_int()
//获取GCODE指令中给定参数的值float
#define GET_PARSER_FLOAT_VAL() parser.value_float()
//通过串口打印调试信息
#define SERIAL_PRINT_MSG(msg) {char* str = msg; while (*str != '\0') MYSERIAL1.write(*str++);}
//获取系统时间戳
#define GET_TICK_MS() millis()
//延时us(微秒)
#define TIME_DELAY_US(dUs) delay_us(dUs)
//Marlin的idle()主循环
#define MARLIN_CORE_IDLE() idle()
//更新看门狗
#define REFRESH_WATCHDOG() {HAL_watchdog_refresh();}
//堵塞执行一条GCODE指令
#define RUN_AND_WAIT_GCODE_CMD(gcode, isWait) planner.synchronize();queue.inject_P(PSTR((gcode))); queue.advance(); if(isWait) {planner.synchronize();}
//设置GPIO工作模式
#define GPIO_SET_MODE(pin, isOut) {if((isOut)>0) SET_OUTPUT((pin)); else SET_INPUT_PULLUP((pin));}
//设置GPIO输出值
#define GPIO_SET_VAL(pin, val) WRITE((pin), (val))
//获取GPIO输入值
#define GPIO_GET_VAL(pin) READ((pin))
//设置喷头温度
#define SET_HOTEND_TEMP(temp, index) thermalManager.setTargetHotend((temp), (index))
//获取喷头当前温度
#define GET_HOTEND_TEMP(index) thermalManager.temp_hotend[(index)].celsius
//获取喷头目标温度
#define GET_HOTEND_TAR_TEMP(index) thermalManager.temp_hotend[(index)].target
//设置热床温度
#define SET_BED_TEMP(temp) thermalManager.setTargetBed(temp)
//获取热床当前温度
#define GET_BED_TEMP() thermalManager.temp_bed.celsius
//获取热床目标温度
#define GET_BED_TAR_TEMP() thermalManager.temp_bed.target
//获取喷头目标温度
#define GET_NOZZLE_TAR_TEMP(index) thermalManager.temp_hotend[(index)].target
//堵塞等待喷头温度到达目标值
#define WAIT_NOZZLE_TEMP(index) thermalManager.wait_for_hotend((index))
//设置热床调平使能状态
#define SET_BED_LEVE_ENABLE(sta) set_bed_leveling_enabled(sta)
//获取模型散热风扇状态
#define GET_FAN_SPD() thermalManager.fan_speed[0]
//设定模型散热风扇状态0~255
#define SET_FAN_SPD(sta) thermalManager.set_fan_speed(0, (sta))
//禁止全局中断,HX711读取数据时需使用
#define DIASBLE_ALL_ISR() DISABLE_ISRS()
//恢复全司中断
#define ENABLE_ALL_ISR() ENABLE_ISRS()
//XYZE电机,每毫米需要给定的步数
#define STEPS_PRE_UNIT DEFAULT_AXIS_STEPS_PER_UNIT //#define DEFAULT_AXIS_STEPS_PER_UNIT { 80, 80, 400, 424.9 }
//Z轴电机前进一步
#define AXIS_Z_STEP_PLUS(dUs) {Z_STEP_WRITE(!INVERT_Z_STEP_PIN);TIME_DELAY_US((dUs));Z_STEP_WRITE(INVERT_Z_STEP_PIN);TIME_DELAY_US((dUs));}
//Z轴高度增加的方向
#define Z_DIR_ADD 0
//Z轴高度减小的方向
#define Z_DIR_DIV (!Z_DIR_ADD)
//Z轴电机方向设置,1为前进,0为后退
#define AXIS_Z_DIR_SET(sta) Z_DIR_WRITE(sta)
//Z轴电机方向读取
#define AXIS_Z_DIR_GET() Z_DIR_READ()
//Z轴电机使能
#define AXIS_Z_ENABLE() ENABLE_AXIS_Z()
//检测电机是否正在运行,返回true为正在运行,返回false为运行完成
#define AXIS_XYZE_STATUS() (planner.has_blocks_queued() || planner.cleaning_buffer_counter)
//设定当前Z轴坐标为home点(0点)
#define SET_NOW_POS_Z_IS_HOME() {set_axis_is_at_home(Z_AXIS);sync_plan_position();}
//使用CR-TOUCH测量给定点的Z值
#define PROBE_PPINT_BY_TOUCH(x, y) probe.probe_at_point(x, y, PROBE_PT_RAISE, 0, false, true)
//设定Z-OFFSET并保存EEPROM
#define SET_Z_OFFSET(zOffset, isSave) {dwin_zoffset = last_zoffset = probe.offset.z = zOffset; HMI_ValueStruct.offset_value = zOffset * 100;DWIN_UpdateLCD(); babystep.add_mm(Z_AXIS, zOffset);}
//堵塞并执行XY轴运动到给定位置
#define DO_BLOCKING_MOVE_TO_XY(x_mm, y_mm, spd_mm_s) do_blocking_move_to_xy((x_mm), (y_mm), (spd_mm_s))
//堵塞并执行Z轴运动到给定位置
#define DO_BLOCKING_MOVE_TO_Z(z_mm, spd_mm_s) do_blocking_move_to_z((z_mm), (spd_mm_s))
#define DO_BLOCKING_MOVE_TO_XYZ(x_mm, y_mm, z_mm,spd_mm_s) do{ \
current_position.set(x_mm, y_mm, z_mm); \
line_to_current_position(spd_mm_s); \
planner.synchronize(); \
}while(0)
/***end***/
//RC高通滤波器,用于滤除如温度变化、导线拉扯等低频干扰。
//毛刺滤波器,用于去除连续数据中的毛刺
//低通滤波器,用于去除连接数据中的超高频噪声
class Filters
{
public:
static void hFilter(double *vals, int count, double cutFrqHz, double acqFrqHz);
static void tFilter(double *vals, int count);
static void lFilter(double *vals, int count, double k1New);
};
//HX711芯片驱动,用于读取压力传感器的数据
class HX711
{
public:
void init(int clkPin, int sdoPin);
int getVal(bool isShowMsg = 0);
static bool ckGpioIsInited(int pin);
private:
int clkPin;
int sdoPin;
};
#define PI_COUNT 32
class ProbeAcq
{
public:
float baseSpdXY_mm_s; //喷头在x和y平面移动的准备速度
float baseSpdZ_mm_s; //喷头在z平面移动的准备速度
float minZ_mm; //向Z轴运动到的停止位置,即到达此位置时还未检测到压力变化,则强制停止。
float step_mm; //每移动此距离,读取一次压力传感器
int minHold; //最小阈值,触发条件的最后一个点需要大于此值
int maxHold; //最大阈值,触发条件的最后一个点大于此值则强制触发
float outVal_mm; //输出,触发时对应的轴坐标
int outIndex; //输出,触发时对应的序列索引,如果值不位于(PI_COUNT*2/3, PI_COUNT-1)区间,则测量错误,需要重新测量。
xyz_float_t basePos_mm; //即开始测量此点前,喷头需要达到的准备位置坐标
HX711 hx711; //指向CS123x或HX711的采集函数
ProbeAcq* probePointByStep(); //根据此类的参数配置测试此点
xyz_long_t readBase(); //获取干净的数据
bool checHx711(); //检测压力传感器是否工作正常
void shakeZAxis(int times); //振动Z轴以消除间隙应力
static float probeTimes(int max_times, xyz_float_t rdy_pos, float step_mm, float min_dis_mm, float max_z_err, int min_hold, int max_hold);
private:
double valP[PI_COUNT * 2]; //压力保存序列的压力值
double posZ[PI_COUNT * 2]; //压力保存序列的对应坐标值
void calMinZ(); //根据压力保存序列计算测量结果
bool checkTrigger(); //检测压力保存序列中的数据是否满足触发条件
};
char *getStr(float f);
void gcodeG212();
bool clearByBed(xyz_float_t rdyPos_mm, float norm, float minTemp, float maxTemp);
bool probeByPress(xyz_float_t rdyPos_mm, float* outZ);
bool probeByTouch(xyz_float_t rdyPos_mm, float* outZ);
bool getZOffset(bool nozzleClr, bool runProByPress, bool runProByTouch, float* outOffset);
#endif
#endif
+858
View File
@@ -0,0 +1,858 @@
#include "PressLeveled.h"
#include "stdio.h"
#include "string.h"
#if ENABLED(USE_AUTOZ_TOOL) //一键对高第一种方式
#define FOR_LOOP_TIMES(lp, sVal, eVal, fun) for(int lp = sVal; lp < eVal; lp++) fun
#define CHECK_RANGE(val, min, max) ((val > min) && (val < max))
#define CHECK_AND_BREAK(bVal) if(bVal) break
#define CHECK_AND_RUN(bVal, fun) if(bVal) fun
#define CHECK_AND_RETURN(bVal, rVal) if(bVal) return rVal
#define CHECK_AND_RUN_AND_RETURN(bVal, fun, rVal) if(bVal) {fun;return rVal;}
#define CHECK_AND_RUN_AND_ELSE(bVal, fun1, fun2); if(bVal) {fun1;} else {fun2;}
#define ARY_MIN(min, ary, count) for(int i = 0; i < count; i++) {CHECK_AND_RUN(min > ary[i], min = ary[i];)}
#define ARY_MAX(max, ary, count) for(int i = 0; i < count; i++) {CHECK_AND_RUN(max < ary[i], max = ary[i];)}
#define ARY_AVG(avg, ary, count) for(int i = 0; i < count; i++) {avg += ary[i];}; avg /= count
#define ARY_MIN_INDEX(min, index, ary, count) for(int i = 0; i < count; i++) {CHECK_AND_RUN(min >= ary[i], {min = ary[i]; index = i;})}
#define ARY_MAX_INDEX(max, index, ary, count) for(int i = 0; i < count; i++) {CHECK_AND_RUN(max <= ary[i], {max = ary[i]; index = i;})}
#define WAIT_BED_TEMP(maxTickMs, maxErr) { unsigned int tickMs = GET_TICK_MS();\
while (((GET_TICK_MS() - tickMs) < maxTickMs) && (abs(GET_BED_TAR_TEMP() - GET_BED_TEMP()) > maxErr))\
MARLIN_CORE_IDLE();}
#define WAIT_HOTEND_TEMP(maxTickMs, maxErr) { unsigned int tickMs = GET_TICK_MS();\
while (((GET_TICK_MS() - tickMs) < maxTickMs) && (abs(GET_HOTEND_TAR_TEMP(0) - GET_HOTEND_TEMP(0)) > maxErr))\
MARLIN_CORE_IDLE();}
#define RUN_AND_WAIT_GCODE_STR(gCode, isWait, ...) {char cmd[128] = {0}; sprintf(cmd, gCode, __VA_ARGS__);PRINTF("\n***RUM GCODE CMD: %s***\n", cmd); RUN_AND_WAIT_GCODE_CMD(cmd, isWait);}
int g29ReprobeCount = 0; //有于统计重次测量次数,可用来判断调平时喷头是否粘有耗材
// 保存擦拭参数
float pl_minHotendTemp = 0;
float pl_maxHotendTemp = 200;
float pl_bedTemp = 60;
xyz_float_t g29BasePos[] = {{BED_PROBE_EDGE - 2, BED_PROBE_EDGE - 2, 0},
{BED_PROBE_EDGE - 2, BED_SIZE_Y_MM - BED_PROBE_EDGE + 2, 0},
{BED_SIZE_X_MM - BED_PROBE_EDGE + 2, BED_SIZE_Y_MM - BED_PROBE_EDGE + 2, 0},
{BED_SIZE_X_MM - BED_PROBE_EDGE + 2, BED_PROBE_EDGE - 2, 0}};
xyz_float_t bedMesh[BED_MESH_X_PT + 2][BED_MESH_Y_PT + 2];
/**
* @brief 将浮点转成字符串(注意:此处不使用ftoa()或%f,是因为部分Marlin版本BUG,会导致浮点转字符失败)
* @param f 需要转换的浮点值
* @return char* 转换后的字符串
* @attention 重载调用次数不要超过16
*/
char *getStr(float f)
{
static char str[16][16];
static int index = 0;
memset(str[index % 16], '\0', 16);
sprintf(str[index % 16], (f >= 0 ? "+%d.%03d" : "-%d.%03d"), (int)fabs(f), ((int)(fabs(f) * 1000)) % 1000);
return str[index++ % 16];
}
/**
* @brief 检测给定pin是否已经初始化过,避免对clk重复初始化而导致时序错乱
* @param pin 待检测的pin
* @return true=pin已初始化过;false=pin未经过初始化。
*/
bool HX711::ckGpioIsInited(int pin)
{
static int pinList[32] = {0};
FOR_LOOP_TIMES(i, 0, 32, {CHECK_AND_RETURN((pinList[i] == pin), true);CHECK_AND_RUN_AND_RETURN((pinList[i] == 0), {pinList[i] = pin;}, false); });
return true;
}
/**
* @brief HX711驱动初始化(80HZ采样率)
* @param clkPin HX711对应的时钟信号
* @param sdoPin HX711对应的数据信号
*/
void HX711::init(int clkPin, int sdoPin)
{
this->clkPin = clkPin;
this->sdoPin = sdoPin;
CHECK_AND_RUN((!HX711::ckGpioIsInited(sdoPin)), GPIO_SET_MODE(sdoPin, 0));
CHECK_AND_RUN((!HX711::ckGpioIsInited(clkPin)), {GPIO_SET_MODE(clkPin, 1); GPIO_SET_VAL(clkPin, 0); });
}
/**
* @brief 阻塞并读取压力值,最大阻塞时间20ms
* @param isShowMsg isShowMsg 是否打印调试信息
* @return int 读取到的压力值
* @attention 要达到80HZ的采样速率,要保证HX711的频率配置引脚已给对应电平
*/
int HX711::getVal(bool isShowMsg)
{
static unsigned int lastTickMs = 0;
int count = 0;
unsigned int ms = GET_TICK_MS();
GPIO_SET_VAL(clkPin, 0);
while (GPIO_GET_VAL(sdoPin) == 1 && (GET_TICK_MS() - ms <= 20)) //采样率80Hz(12ms周期),这里最大给20ms延时
MARLIN_CORE_IDLE();
DIASBLE_ALL_ISR();
for (int i = 0; i < 24; i++)
{
GPIO_SET_VAL(clkPin, 1);
count = count << 1;
GPIO_SET_VAL(clkPin, 0);
CHECK_AND_RUN((GPIO_GET_VAL(sdoPin) == 1), (count++));
}
ENABLE_ALL_ISR();
GPIO_SET_VAL(clkPin, 1);
count |= ((count & 0x00800000) != 0 ? 0xFF000000 : 0); //24位有符号,转成32位有符号
GPIO_SET_VAL(clkPin, 0);
CHECK_AND_RUN(isShowMsg, {PRINTF("T=%08d, S=%08d\n", (int)(GET_TICK_MS() - lastTickMs), (int)count);lastTickMs = GET_TICK_MS(); });
return count;
}
/**
* @brief RC高通滤波器初始化
* @param cutFrqHz 滤波器的截止频率
* @param acqFrqHz 滤波器的采样频率(等同于HX711的采样频率80HZ)
* @param baseVal 滤波器的初始值(方便滤波器快速进入稳定状态)
*/
void RCLFilter::init(double cutFrqHz, double acqFrqHz, double baseVal)
{
this->vi = this->viPrev = baseVal;
this->voPrev = this->vo = 0;
this->cutoffFrqHz = cutFrqHz; // high pass filter @cutoff frequency = XX Hz
this->acqFrqHz = acqFrqHz; // execute XX every second
}
/**
* @brief 对一个值使用RC滤波器进行滤波,并返回滤波后的值
* @param newVal 未滤波前的值
* @return double 滤波后的植
*/
double RCLFilter::filter(double newVal)
{
double rc, coff;
this->vi = newVal;
rc = 1.0f / 2.0f / PI / this->cutoffFrqHz;
coff = rc / (rc + 1 / this->acqFrqHz);
this->vo = (this->vi - this->viPrev + this->voPrev) * coff;
this->voPrev = this->vo; // update
this->viPrev = this->vi;
return fabs(this->vo);
}
/**
* @brief 获取给定数量内(BASE_COUNT/2)的最大、最小、平均压力值。
* @return x=MIN; y=AVG; z=MAX;
*/
xyz_long_t ProbeAcq::readBase()
{
xyz_long_t xyz = {+0x00FFFFFF, 0, -0x00FFFFFF}; // min avg max
long avg = 0, v = 0;
FOR_LOOP_TIMES(i, 0, BASE_COUNT / 2, { v = this->hx711.getVal(false); });
FOR_LOOP_TIMES(i, 0, BASE_COUNT / 2, {
v = this->hx711.getVal(0);
xyz.x = xyz.x > v ? v : xyz.x;
xyz.z = xyz.z < v ? v : xyz.z;
avg += v; });
xyz.y = (int)(avg / (BASE_COUNT / 2));
this->rcFilter.init(this->rcFilter.cutoffFrqHz, this->rcFilter.acqFrqHz, v);
PRINTF("\n***BASE:MIN=%d, AVG=%d, MAX=%d***\n\n", (int)xyz.x, (int)xyz.y, (int)xyz.z);
return xyz;
}
/**
* @brief 检测HX711模块是否工作正常
* @return true:正常,false 不正常
* @attention 理论上,HX711在一定时间内,最大与最值压力差应大于100,且小于MIN_HOLD。
*/
bool ProbeAcq::checHx711()
{
xyz_long_t bv = readBase();
return (abs(bv.x - bv.z) < 100 || abs(bv.x - bv.z) > 2 * MIN_HOLD) ? false : true;
}
/**
* @brief 根据触发后压力队列中的压力值,计算出对应的z轴高度
* @param
* @return
*/
void ProbeAcq::calMinZ()
{
double valMin = +0x00FFFFFF, valMax = -0x00FFFFFF, bCs[PI_COUNT] = {0}, maxE = 0;
// 1、一阶互补滤波
#define CAL_K1 0.5f
FOR_LOOP_TIMES(i, 1, PI_COUNT, valP[i] = valP[i] * CAL_K1 + valP[i - 1] * (1 - CAL_K1));
#ifdef SHOW_MSG
// 2、打印结果
PRINTF("%s", "\nx=[");
FOR_LOOP_TIMES(i, 0, PI_COUNT, PRINTF((i == (PI_COUNT - 1) ? "%s]\n\n" : "%s,"), getStr(posZ[i])));
PRINTF("%s", "y=[");
FOR_LOOP_TIMES(i, 0, PI_COUNT, PRINTF((i == (PI_COUNT - 1) ? "%s]\n\n" : "%s,"), getStr(valP[i])));
#endif
// 3、对数据进行归一化,方便处理
ARY_MIN(valMin, valP, PI_COUNT);
ARY_MAX(valMax, valP, PI_COUNT);
FOR_LOOP_TIMES(i, 0, PI_COUNT, {valP[i] = (valP[i] - valMin) / (valMax - valMin); bCs[i] = valP[i]; });
// 4、计算并按给定角度翻转数据,以方便计算出最早的触发点
double angle = atan((valP[PI_COUNT - 1] - valP[0]) / PI_COUNT);
double sinAngle = sin(-angle), cosAngle = cos(-angle);
FOR_LOOP_TIMES(i, 0, PI_COUNT, valP[i] = (i - 0) * sinAngle + (valP[i] - 0) * cosAngle + 0); //延原点(0,0)顺时针旋转angle度,这里可以不考虑X轴坐标值
// 5、找出翻转后的最小值索引
valMin = +0x00FFFFFF;
ARY_MIN_INDEX(valMin, this->outIndex, valP, PI_COUNT);
ARY_MAX(maxE, bCs, this->outIndex);
this->outVal_mm = posZ[this->outIndex];
this->outIndex = (((maxE > 0.2) || (posZ[PI_COUNT - 1] <= minZ_mm)) ? (PI_COUNT - 1) : this->outIndex); //对计算结果进行验证
PRINTF("\n***CalZ Idx=%d, Z=%s***\n\n", this->outIndex, getStr(this->outVal_mm));
}
/**
* @brief 触发状态检测,用于检测喷头是否与压力传感器正常接触
* @param fitVal RC低通滤波后的压力值,用于特征检测
* @param unfitDifVal 未滤波但去零后的压力值,用于超压检测
* @return true=检测到解发或中止;false=未满足触发条件。
*/
bool ProbeAcq::checkTrigger(int fitVal, int unfitDifVal)
{
double valMin = +0x00FFFFFF, valMax = -0x00FFFFFF, valAvg = 0, valP_t[PI_COUNT] = {0}, valP_n[PI_COUNT] = {0};
static long long lastTickMs = 0, lastUnfitDifVal = 0;
#ifdef SHOW_MSG
if(isShowMsg)
{
PRINTF("T=%08d , S=%08d , U=%08d \n", (int)(GET_TICK_MS() - lastTickMs), fitVal, unfitDifVal);
lastTickMs = GET_TICK_MS();
}
#endif
// 0、复制一份用于检测,防止对源数据造成影响
FOR_LOOP_TIMES(i, 0, PI_COUNT, valP_t[i] = this->valP[i]);
// 1、最高优先级,到达最小位置还未触发,则强制停止
CHECK_AND_RETURN((this->posZ[PI_COUNT - 1] <= this->minZ_mm), true);
// 2、最高优先级,压力大于最大压力,则无条件停止。
CHECK_AND_RUN_AND_RETURN((abs(unfitDifVal) >= this->maxHold && abs(lastUnfitDifVal) >= this->maxHold), this->outIndex = PI_COUNT - 1, true);
lastUnfitDifVal = unfitDifVal;
// 3、检测点数未满足最小需求
CHECK_AND_RETURN(IS_ZERO(this->valP[0]), false);
// 4、剔除错误的数据
FOR_LOOP_TIMES(i, 1, PI_COUNT - 1, CHECK_AND_RUN((abs(valP_t[i]) >= this->maxHold && abs(valP_t[i - 1]) < (this->maxHold / 2) && abs(valP_t[i + 1]) < (this->maxHold / 2)), valP_t[i] = valP_t[i - 1]));
// 5、检测未尾3个点大小的是否有序递增
CHECK_AND_RETURN((!((valP_t[PI_COUNT - 1] > valP_t[PI_COUNT - 2]) && (valP_t[PI_COUNT - 2] > valP_t[PI_COUNT - 3]))), false);
// 6、检测未3个点绝对值是否大于其它任意点
FOR_LOOP_TIMES(i, 0, PI_COUNT - 3, CHECK_AND_RETURN((valP_t[PI_COUNT - 1] < valP_t[i] || valP_t[PI_COUNT - 2] < valP_t[i] || valP_t[PI_COUNT - 3] < valP_t[i]), false));
// 6、对数据进行归一化,方便处理
ARY_MIN(valMin, valP_t, PI_COUNT);
ARY_MAX(valMax, valP_t, PI_COUNT);
ARY_AVG(valAvg, valP_t, PI_COUNT);
FOR_LOOP_TIMES(i, 0, PI_COUNT, valP_n[i] = (float)(((double)valP_t[i] - valMin) / (valMax - valMin)));
// 7、保证所有点针对最后一个点的斜率均大于40度,可有郊防止过于灵敏而导致的误触发。
FOR_LOOP_TIMES(i, 0, PI_COUNT - 1, CHECK_AND_RETURN(((valP_n[PI_COUNT - 1] - valP_n[i]) / ((32 - i) * 1.0f / 32) < 0.8), false));
// 8、限制最小值,防止误触发。
CHECK_AND_RETURN((valP_t[PI_COUNT - 1] < this->minHold), false);
return true;
}
/**
* @brief 单步进法测量,并返回测量结果。
* @return ProbeAcq* this指针
*/
ProbeAcq* ProbeAcq::probePointByStep()
{
int unfitAvgVal = 0, unfitNowVal = 0, fitNowVal = 0, runSteped = 0;
#ifdef SHOW_MSG
PRINTF("\nPROBE: rdyX=%s, rdyY=%s, rdyZ=%s, spdXY_mm_s=%s, spdZ_mm_s=%s",
getStr(this->basePos_mm.x), getStr(this->basePos_mm.y), getStr(this->basePos_mm.z), getStr(this->baseSpdXY_mm_s), getStr(this->baseSpdZ_mm_s));
PRINTF("len_mm=%s, baseCount=%d, minHold=%d, maxHold=%d, step_mm=%s\n\n",
getStr(this->minZ_mm), BASE_COUNT, this->minHold, this->maxHold, getStr(this->step_mm));
#endif
memset(this->posZ, 0, sizeof(this->posZ));
memset(this->valP, 0, sizeof(this->valP));
//运动到等测量点(准备点)
RUN_AND_WAIT_GCODE_STR("G1 F%s X%s Y%s Z%s", true, getStr(this->baseSpdXY_mm_s * 60), getStr(this->basePos_mm.x), getStr(this->basePos_mm.y), getStr(this->basePos_mm.z));
SET_HOTEND_TEMP(0, 0);
unfitAvgVal = readBase().y; //获取干净的数据
float steps[] = STEPS_PRE_UNIT; // { 80, 80, 400, 424.9 }
int runStep = this->step_mm * steps[2]; //获取每步进step_mm距离,对应电机的脉冲数量
runStep = runStep <= 0 ? 1 : runStep;
int delayUs = (11.0f * 1000 / runStep) / 2; //保证12ms左右,Z轴电机运动step_mm的距离
delayUs = delayUs <= 10 ? 10 : delayUs;
int oldDir = AXIS_Z_DIR_GET();
AXIS_Z_ENABLE();
AXIS_Z_DIR_DIV();
do{
FOR_LOOP_TIMES(i, 0, runStep, AXIS_Z_STEP_PLUS(delayUs)); //向给定方向运动给定步进距离
runSteped += runStep;
MARLIN_CORE_IDLE();
unfitNowVal = this->hx711.getVal(0); //获取压力值
fitNowVal = this->rcFilter.filter(unfitNowVal); //对压力值进行高通滤波
FOR_LOOP_TIMES(i, 0, PI_COUNT - 1, this->valP[i] = this->valP[i + 1]);
FOR_LOOP_TIMES(i, 0, PI_COUNT - 1, this->posZ[i] = this->posZ[i + 1]);
this->valP[PI_COUNT - 1] = fitNowVal; //将压力值放入队列
this->posZ[PI_COUNT - 1] = GET_CURRENT_POS().z - (float)runSteped / steps[2]; //将压力值对应的z位置放入队列
// if((checkTrigger(fitNowVal, abs(unfitNowVal - unfitAvgVal)) == true) && (0 == READ(PROBE_ACTIVATION_SWITCH_PIN))) //触发条件检测
if(checkTrigger(fitNowVal, abs(unfitNowVal - unfitAvgVal)) == true)
{
if(thermalManager.temp_hotend[0].target < pl_minHotendTemp)
{
SET_HOTEND_TEMP(pl_minHotendTemp, 0);
}
calMinZ(); //数据整理与计算
runSteped = ((this->isUpAfter == false) ? (PI_COUNT - this->outIndex - 1) * runStep : runSteped);
AXIS_Z_DIR_ADD();
FOR_LOOP_TIMES(i, 0, runSteped, AXIS_Z_STEP_PLUS(delayUs / 4)); //返回到触发点或准备点
AXIS_Z_DIR_SET(oldDir);
break;
}
} while (1);
return this;
}
/**
* @brief 对p1和p2两点进行线性拟合,并计算po点在此直线上的位置
* @param p1 待拟合的第一个点
* @param p2 待拟合的第二个点
* @param po 待计算的点
* @param isBaseX 是否将三维直线投影到x平面
* @return po点在拟合后直线上的位置
*/
float getLinear2(xyz_float_t *p1, xyz_float_t *p2, xyz_float_t *po, int isBaseX)
{
if ((IS_ZERO(p1->x - p2->x) && isBaseX > 0) || (IS_ZERO(p1->y - p2->y) && isBaseX == 0))
return 0;
// 线性方式 z=ax+b或z=ay+b,以下是计算a和b
float a = (p2->z - p1->z) / (isBaseX > 0 ? (p2->x - p1->x) : (p2->y - p1->y));
float b = p1->z - (isBaseX > 0 ? p1->x : p1->y) * a;
po->z = a * (isBaseX > 0 ? po->x : po->y) + b;
return po->z;
}
/**
* @brief 在调平测试单点时,为提高效率和安全性,这里获取最佳的Z轴准备高度
* @param x 等检测点的x坐标
* @param y 待检测点的y坐标
* @return float 最佳准备点坐标
*/
float getBestProbeZ(float x, float y)
{
if(IS_ZERO(g29BasePos[0].z) && IS_ZERO(g29BasePos[1].z) && IS_ZERO(g29BasePos[2].z) && IS_ZERO(g29BasePos[3].z))
return BED_MAX_ERR;
xyz_float_t pLeft = {g29BasePos[0].x, y, 0}, pRight = {g29BasePos[2].x, y, 0}, pMid = {x, y, 0};
pLeft.z = getLinear2(&g29BasePos[0], &g29BasePos[1], &pLeft, 0);
pRight.z = getLinear2(&g29BasePos[2], &g29BasePos[3], &pRight, 0);
pMid.z = getLinear2(&pLeft, &pRight, &pMid, 1);
return pMid.z;
}
/**
* @brief 打印调平数据矩阵信息,可用于热床平面3D图绘制
*/
void printBedMesh(void)
{
//测量数据,输出坐标+测量值方式
FOR_LOOP_TIMES(i, 0, BED_MESH_X_PT + 2, {
PRINTF("%s", "\n");
FOR_LOOP_TIMES(j, 0, BED_MESH_Y_PT + 2, PRINTF("(%s, %s, %s), ", getStr(bedMesh[i][j].x), getStr(bedMesh[i][j].y), getStr(bedMesh[i][j].z)););
});
PRINTF("%s", "\n");
//测量数据,输出Excel表格格式,
FOR_LOOP_TIMES(j, 1, BED_MESH_Y_PT + 1, {
PRINTF("%s", "\n");
FOR_LOOP_TIMES(i, 1, BED_MESH_X_PT + 1, PRINTF(((i == BED_MESH_X_PT + 1 - 1) ? "%s" : "%s\t"), getStr(bedMesh[i][j].z)))
});
PRINTF("%s", "\n\n");
//测量数据,输出PYTHON格式
FOR_LOOP_TIMES(j, 1, BED_MESH_Y_PT + 1, {
PRINTF("%s", "[");
FOR_LOOP_TIMES(i, 1, BED_MESH_X_PT + 1, PRINTF("%s%s", getStr(bedMesh[i][j].z), ((i == BED_MESH_X_PT + 1 - 1) ? "],\n" : ",")));
});
PRINTF("%s", "\n\n");
//测量数据+扩充数据,输出PYTHON格式
FOR_LOOP_TIMES(i, 0, BED_MESH_X_PT + 2, {
PRINTF("%s", "[");
FOR_LOOP_TIMES(j, 0, BED_MESH_Y_PT + 2, PRINTF("%s%s", getStr(bedMesh[i][j].z), (j == BED_MESH_Y_PT + 1 ? "],\n" : ",")));
});
PRINTF("%s", "\n\n");
}
/**
* @brief 初始化调平数据矩阵
*/
void initBedMesh(void)
{
xyz_float_t t = {0, 0, 0};
g29ReprobeCount = 0;
FOR_LOOP_TIMES(i, 0, BED_MESH_X_PT + 2, FOR_LOOP_TIMES(j, 0, BED_MESH_Y_PT + 2, {bedMesh[i][j]= t;}));
// SET_Z_OFFSET(0);
// probe.offset.z Parameters must be saved
// probe.offset.z = 0;
}
/**
* @brief 在热床是进行喷头擦拭操作
* @param minTemp 喷头耗材不再渗出时的温度
* @param maxTemp 喷头耗材可以挤出并正常打印时的温度
* @param doExFil 擦拭过程中挤出耗材的长度,等于0表明不挤出
* @return true:擦拭成功;false:擦拭失败
* @attention 喷头擦拭需要较长时间,如有优化或更合适的擦拭方式,可以改写此功能
*/
bool clearNozzle(float minHotendTemp, float maxHotendTemp, float bedTemp, int doExFil_mm)
{
xyz_float_t srcPos = {BED_PROBE_EDGE / 2, BED_PROBE_EDGE, BED_MAX_ERR + 1};
ProbeAcq pa;
pa.hx711.init(HX711_SCK_PIN, HX711_SDO_PIN);
pa.rcFilter.init(RC_CUTE_FRQ, 80, 0);
srand(millis()); //随机取热床上的一段距离用于擦拭,防止频繁使用同一处而对热床产生磨损
srcPos.y = rand() % (BED_SIZE_Y_MM - 6 * BED_PROBE_EDGE - PA_CLR_DIS_MM) + 4 * BED_PROBE_EDGE;
SET_FAN_SPD(0);
pl_minHotendTemp = minHotendTemp;
pl_maxHotendTemp = maxHotendTemp;
pl_bedTemp = bedTemp;
pa.minZ_mm = -5;
pa.basePos_mm = srcPos;
pa.basePos_mm.y = srcPos.y - PA_FIL_DIS_MM;
pa.baseSpdXY_mm_s = 100;
pa.baseSpdZ_mm_s = 5;
pa.step_mm = 0.025;
pa.isUpAfter = true;
pa.isShowMsg = false;
pa.minHold = MAX_HOLD / 3;
pa.maxHold = MAX_HOLD;
SET_BED_TEMP(bedTemp); //热床加热后有形变,因此应在60度左右时测量误差最小
SET_HOTEND_TEMP(maxHotendTemp, 0);
DO_BLOCKING_MOVE_TO_Z(srcPos.z, pa.baseSpdZ_mm_s);
DO_BLOCKING_MOVE_TO_XY(0, 0, pa.baseSpdXY_mm_s);
WAIT_HOTEND_TEMP((3*60*1000), 5);
pa.probePointByStep();
int unFitVal = pa.readBase().y;
if(doExFil_mm > 0)//喷头擦拭过程中,是否挤出耗材
{
DO_BLOCKING_MOVE_TO_XY(srcPos.x, srcPos.y - PA_FIL_DIS_MM, pa.baseSpdXY_mm_s);
DO_BLOCKING_MOVE_TO_Z(pa.outVal_mm + 0.2, 5);
RUN_AND_WAIT_GCODE_CMD("G92 E0", true);
RUN_AND_WAIT_GCODE_STR("G1 F100 Y%s Z%s E%s", true, getStr(srcPos.y - 5), getStr(pa.outVal_mm + 0.1), getStr(doExFil_mm));
RUN_AND_WAIT_GCODE_STR("G1 F100 Y%s Z%s E%s", true, getStr(srcPos.y), getStr(pa.outVal_mm + 0.1), getStr(doExFil_mm - 2));
}
DO_BLOCKING_MOVE_TO_XY(srcPos.x, srcPos.y, pa.baseSpdXY_mm_s);
DO_BLOCKING_MOVE_TO_Z(pa.outVal_mm + 0.1, 5);
RUN_AND_WAIT_GCODE_STR("G1 F100 Y%s", false, getStr(srcPos.y + PA_CLR_DIS_MM));
SET_HOTEND_TEMP(minHotendTemp, 0);
SET_FAN_SPD(255);
float steps[] = STEPS_PRE_UNIT;
int runStep = 0.02 * steps[2];
int delayUs = (12.0f * 1000 / runStep) / 2;
AXIS_Z_ENABLE();
while (AXIS_XYZE_STATUS()){
int nowVal = pa.hx711.getVal(0);
CHECK_AND_RUN_AND_ELSE((abs(nowVal - unFitVal) < pa.minHold), AXIS_Z_DIR_DIV(), AXIS_Z_DIR_ADD());
FOR_LOOP_TIMES(i, 0, runStep, AXIS_Z_STEP_PLUS(delayUs));
MARLIN_CORE_IDLE();
}
AXIS_Z_DIR_ADD();
WAIT_HOTEND_TEMP((3 * 60 * 1000), 5);
SET_FAN_SPD(0);
RUN_AND_WAIT_GCODE_STR("G1 F100 Y%s Z%s", true, getStr(GET_CURRENT_POS().y + 5), getStr(GET_CURRENT_POS().z + 1));
DO_BLOCKING_MOVE_TO_Z(GET_CURRENT_POS().z + BED_MAX_ERR + 1, 5);
WAIT_BED_TEMP((3 * 60 * 1000), 5);
RUN_AND_WAIT_GCODE_CMD("G28 Z C0", true);
return true;
}
/**
* @brief 在进行16个点的调平点高度测量前,可以先调用此函数,获取热床大致平面,可以缩短后期16个点的测量时间
* @param rdyZ_mm 准备点测量时的准备高度,即等于 热床平面最高点高度(Z+1)mm,如产品允许热床最大倾斜偏差为正负5mm,则此值取6mm
* @return true:准备点测量完成;false:准备点测量失败
*/
bool probeReady(void)
{
ProbeAcq pa;
pa.hx711.init(HX711_SCK_PIN, HX711_SDO_PIN);
pa.rcFilter.init(RC_CUTE_FRQ, 80, 0);
pa.minZ_mm = -10;
pa.baseSpdXY_mm_s = 200;
pa.baseSpdZ_mm_s = 5;
pa.step_mm = 0.025;
pa.isUpAfter = true;
pa.isShowMsg = false;
pa.minHold = MIN_HOLD;
pa.maxHold = MAX_HOLD;
FOR_LOOP_TIMES(i, 0, 4, g29BasePos[i].z = BED_MAX_ERR + 1);
FOR_LOOP_TIMES(i, 0, 4, {
float z1 = 0;
float z2 = 0;
pa.basePos_mm = g29BasePos[i];
FOR_LOOP_TIMES(j, 0, 3, {
z1 = pa.probePointByStep()->outVal_mm;
z2 = pa.probePointByStep()->outVal_mm;
CHECK_AND_BREAK((fabs(z1 - z2) <= 0.2));
});
g29BasePos[i].z = (z1 + z1) / 2;
});
PRINTF("***G29 Ready={%s, %s, %s, %s}***\n", getStr(g29BasePos[0].z), getStr(g29BasePos[1].z), getStr(g29BasePos[2].z), getStr(g29BasePos[3].z));
return true;
}
/**
* @brief 设定调平数据矩阵给定点的坐标及测量结果,在G29调平过程中,每测量完一个点,均需要更新测量结果到mesh内
* @param xIndex 沿X轴方向的点索引
* @param yIndex 沿X轴方向的点索引
* @param xPos_mm 测量点的x坐标
* @param yPos_mm 测量点的y坐标
* @param zPos_mm 测量点测量出的热床高度z值
* @return true:添加成功;false:添加失败
*/
bool setBedMesh(int xIndex, int yIndex, float xPos_mm, float yPos_mm, float zPos_mm)
{
xyz_float_t t = {xPos_mm,yPos_mm,zPos_mm};
CHECK_AND_RETURN((xIndex >= BED_MESH_X_PT || yIndex >= BED_MESH_Y_PT), false);
bedMesh[xIndex + 1][yIndex + 1] = t;
return true;
}
/**
* @brief 更新并扩充调平数据矩阵测量点外的区域点
*/
void updataBedMesh(void)
{
//1、扩展x轴左右两侧估计点的x、y坐标
for (int xi = 1; xi < BED_MESH_X_PT + 1; xi++)
{
bedMesh[xi][0].x = bedMesh[xi][1].x;
bedMesh[xi][BED_MESH_Y_PT + 1].x = bedMesh[xi][BED_MESH_Y_PT].x;
bedMesh[xi][0].y = 2 * bedMesh[xi][1].y - bedMesh[xi][2].y;
bedMesh[xi][BED_MESH_Y_PT + 1].y = 2 * bedMesh[xi][BED_MESH_Y_PT].y - bedMesh[xi][BED_MESH_Y_PT - 1].y;
}
//2、扩展y轴上下两侧估计点的x、y坐标
for (int yj = 0; yj < BED_MESH_Y_PT + 2; yj++)
{
bedMesh[0][yj].x = 2 * bedMesh[1][yj].x - bedMesh[2][yj].x;
bedMesh[BED_MESH_X_PT + 1][yj].x = 2 * bedMesh[BED_MESH_X_PT][yj].x - bedMesh[BED_MESH_X_PT - 1][yj].x;
bedMesh[0][yj].y = bedMesh[1][yj].y;
bedMesh[BED_MESH_X_PT + 1][yj].y = bedMesh[BED_MESH_X_PT][yj].y;
}
//3、拟合计算x轴左右两侧估计点的z坐标
for (int xi = 1; xi < BED_MESH_X_PT + 1; xi++)
{
bedMesh[xi][0].z = getLinear2(&bedMesh[xi][2], &bedMesh[xi][1], &bedMesh[xi][0], 0);
bedMesh[xi][BED_MESH_Y_PT + 1].z = getLinear2(&bedMesh[xi][BED_MESH_Y_PT - 1], &bedMesh[xi][BED_MESH_Y_PT], &bedMesh[xi][BED_MESH_Y_PT + 1], 0);
}
//4、拟合计算y轴上下两侧估计点的z坐标
for (int yj = 1; yj < BED_MESH_Y_PT + 1; yj++)
{
bedMesh[0][yj].z = getLinear2(&bedMesh[2][yj], &bedMesh[1][yj], &bedMesh[0][yj], 1);
bedMesh[BED_MESH_X_PT + 1][yj].z = getLinear2(&bedMesh[BED_MESH_X_PT - 1][yj], &bedMesh[BED_MESH_X_PT][yj], &bedMesh[BED_MESH_X_PT + 1][yj], 1);
}
//5、拟合计算四个角的z坐标
bedMesh[0][0].z = getLinear2(&bedMesh[2][2], &bedMesh[1][1], &bedMesh[0][0], 0);
bedMesh[0][BED_MESH_Y_PT + 1].z = getLinear2(&bedMesh[2][BED_MESH_Y_PT - 1], &bedMesh[1][BED_MESH_Y_PT], &bedMesh[0][BED_MESH_Y_PT + 1], 0);
bedMesh[BED_MESH_X_PT + 1][0].z = getLinear2(&bedMesh[BED_MESH_X_PT - 1][2], &bedMesh[BED_MESH_X_PT][1], &bedMesh[BED_MESH_X_PT + 1][0], 0);
bedMesh[BED_MESH_X_PT + 1][BED_MESH_Y_PT + 1].z = getLinear2(&bedMesh[BED_MESH_X_PT - 1][BED_MESH_Y_PT - 1], &bedMesh[BED_MESH_X_PT][BED_MESH_Y_PT], &bedMesh[BED_MESH_X_PT + 1][BED_MESH_Y_PT + 1], 0);
}
/**
* @brief 热床平整度检查,同时对问题点进行重新测量
*/
void checkAndReProbe(void)
{
float bzs[] = {g29BasePos[0].z, g29BasePos[1].z, g29BasePos[2].z, g29BasePos[3].z};
float minBz = 0, maxBz = 0;
//1、找出准备点的最大最小z值
ARY_MIN(minBz, bzs, 4);
ARY_MAX(maxBz, bzs, 4);
//2、计算热床当前的最大倾角(未测量过准备点,则取产品允许热床最大高低差)
float norm = (BED_SIZE_X_MM < BED_SIZE_Y_MM ? BED_SIZE_X_MM : BED_SIZE_Y_MM);
float heigh = (IS_ZERO(minBz) && IS_ZERO(maxBz)) ? (2 * BED_MAX_ERR) : (maxBz - minBz);
float maxArcTan = (heigh < 6 ? 6 : heigh) / norm;
maxArcTan = (maxArcTan <= (4.0f / BED_SIZE_X_MM) ? (4.0f / BED_SIZE_X_MM) : maxArcTan);
if(g29ReprobeCount >= MAX_REPROBE_CNT) // 如果重复测量点过多,表明喷头可能粘有耗材,此时要进行喷头擦拭后再重新测量
{
maxArcTan = 0;
clearNozzle(pl_minHotendTemp, pl_maxHotendTemp + 20, pl_bedTemp, PA_FIL_LEN_MM);
}
PRINTF("\n***CHECK POINTS: minZ=%s, maxZ=%s, norm=%s, heigh=%s, maxArcTan=%s***\n", getStr(minBz), getStr(maxBz), getStr(norm), getStr(heigh), getStr(maxArcTan));
//3、循环遍历每个点,并与其周围点做比较,以难斜率是否在给定的范围内
for (int i = 1; i < BED_MESH_X_PT + 1; i++)
{
for (int j = 1; j < BED_MESH_X_PT + 1; j++)
{
float rd[4] = {0}, xIntval = bedMesh[2][2].x - bedMesh[1][1].x, yIntval = bedMesh[2][2].y - bedMesh[1][1].y;
rd[0] = (i <= 1 ? (maxArcTan + 1) : (bedMesh[i - 1][j].z - bedMesh[i][j].z) / xIntval);
rd[1] = (i >= BED_MESH_X_PT - 1 ? (maxArcTan + 1) : (bedMesh[i + 1][j].z - bedMesh[i][j].z) / xIntval);
rd[2] = (j <= 0 ? (maxArcTan + 1) : (bedMesh[i][j - 1].z - bedMesh[i][j].z) / yIntval);
rd[3] = (j >= BED_MESH_Y_PT - 1 ? (maxArcTan + 1) : (bedMesh[i][j + 1].z - bedMesh[i][j].z) / yIntval);
if ((fabsf(rd[0]) < maxArcTan) || (fabsf(rd[1]) < maxArcTan) || (fabsf(rd[2]) < maxArcTan) || (fabsf(rd[3]) < maxArcTan))
continue;
PRINTF("\n***MUST RE PROBE: (z=%s, z0=%s, z1=%s, z2=%s, z3=%s), (rd=%s, rd0=%s, rd1=%s, rd2=%s, rd3=%s)***\n",
getStr(bedMesh[i][j].z), getStr(bedMesh[i - 1][j].z), getStr(bedMesh[i + 1][j].z), getStr(bedMesh[i][j - 1].z), getStr(bedMesh[i][j + 1].z),
getStr(maxArcTan), getStr(rd[0]),getStr(rd[1]),getStr(rd[2]),getStr(rd[3]));
bedMesh[i][j].z = doG29Probe(bedMesh[i][j].x, bedMesh[i][j].y);//重新测量
}
}
}
/**
* @brief 根据测量及扩充后的数据矩阵,进行补偿值获取
* @param xPos 待获取位置的x坐标
* @param yPos 待获取位置的y坐标
* @return outZ_mm 计算出的Z补偿值
*/
float getMeshZ(float xPos, float yPos)
{
int xS = 0, yS = 0;
while (xS <= BED_MESH_X_PT && !(xPos >= bedMesh[xS][0].x && xPos < bedMesh[xS + 1][0].x))
xS++;
while (yS <= BED_MESH_Y_PT && !(yPos >= bedMesh[0][yS].y && yPos < bedMesh[0][yS + 1].y))
yS++;
if (xS >= BED_MESH_X_PT + 1 || yS >= BED_MESH_Y_PT + 1)
return 0;
xyz_float_t pLeft = {xPos, bedMesh[xS][yS].y, 0}, pRight = {xPos, bedMesh[xS][yS + 1].y, 0}, pMid = {xPos, yPos, 0};
pLeft.z = getLinear2(&bedMesh[xS][yS], &bedMesh[xS + 1][yS], &pLeft, 1);
pRight.z = getLinear2(&bedMesh[xS][yS + 1], &bedMesh[xS + 1][yS + 1], &pRight, 1);
pMid.z = getLinear2(&pLeft, &pRight, &pMid, 0);
#if 0 //SHOW_MSG //Z轴补偿值的获取比较频繁,调试完成后应该关闭此处,以免影响打印质量。
PRINTF("\nMeshCell: Point = (%s, %s, %s)\n", getStr(pMid.x), getStr(pMid.y), getStr(pMid.z));
/*
memset(msg, 0, sizeof(msg));
sprintf(msg, "pLeft=(%.2f, %.2f, %.2f)\tpRight=(%.2f, %.2f, %.2f)\n", pLeft.x, pLeft.y, pLeft.z, pRight.x, pRight.y, pRight.z);
serialprintPGM(msg);
memset(msg, 0, sizeof(msg));
sprintf(msg, "(%d, %d)=(%.2f, %.2f, %.2f)\t(%d, %d)=(%.2f, %.2f, %.2f)\n", xS, yS, bedMesh[xS][yS].x, bedMesh[xS][yS].y, bedMesh[xS][yS].z, xS, yS + 1, bedMesh[xS][yS + 1].x, bedMesh[xS][yS + 1].y, bedMesh[xS][yS + 1].z);
serialprintPGM(msg);
memset(msg, 0, sizeof(msg));
sprintf(msg, "(%d, %d)=(%.2f, %.2f, %.2f)\t(%d, %d)=(%.2f, %.2f, %.2f)\n", xS + 1, yS, bedMesh[xS + 1][yS].x, bedMesh[xS + 1][yS].y, bedMesh[xS + 1][yS].z, xS + 1, yS + 1, bedMesh[xS + 1][yS + 1].x, bedMesh[xS + 1][yS + 1].y, bedMesh[xS + 1][yS + 1].z);
serialprintPGM(msg);
serialprintPGM("\n");
*/
#endif
return pMid.z;
}
/**
* @brief 使用压力传感器测量并获取给定点的热床高度
* @param xPos 需要获取点的x坐标
* @param yPos 需要获取点的y坐标
* @attention 先执行probeReady(),有利于减小调平时间,调平点数越多,效果越明显
* @return 测量完成后,输出的结果
*/
float doG29Probe(float xPos, float yPos)
{
ProbeAcq pa;
pa.hx711.init(HX711_SCK_PIN, HX711_SDO_PIN);
pa.rcFilter.init(RC_CUTE_FRQ, 80, 0);
pa.minZ_mm = -20;
pa.basePos_mm.x = xPos + (random(0, 3) - 1);
pa.basePos_mm.y = yPos;
pa.basePos_mm.z = getBestProbeZ(xPos, yPos);
pa.basePos_mm.z = (IS_ZERO(pa.basePos_mm.z) ? (BED_MAX_ERR + 1) : pa.basePos_mm.z);
pa.baseSpdXY_mm_s = 200;
pa.baseSpdZ_mm_s = 5;
pa.step_mm = 0.0125; // 测量精度
pa.isUpAfter = true;
pa.isShowMsg = false;
pa.minHold = MIN_HOLD;
pa.maxHold = MAX_HOLD;
// CHECK_AND_RETURN((!(pa.checHx711() || pa.checHx711())), 0); // 检测模块工作是否正常
int i = 0;
for (i = 0; i < 5; i++)
{
pa.probePointByStep()->outIndex;
CHECK_AND_BREAK(CHECK_RANGE(pa.outIndex, 3 * PI_COUNT / 4, PI_COUNT - 1)); //验证检测结果是否正确
pa.basePos_mm.z = getBestProbeZ(xPos, yPos); //检测失败,则将开始测量时的Z轴高度抬升一段
g29ReprobeCount++;
}
PRINTF("\n***PROBE BY PRESS: z=%s***\n", getStr(pa.outVal_mm));
return ((i >= 3) ? 0 : pa.outVal_mm);
}
/**
* @brief 使用压力传感器获取Z轴HOME点
* @param isPrecision true:为精确测量(比如喷头擦拭后);false:为粗略测量(比如喷头擦拭前);
*/
void doG28ZProbe(bool isPrecision)
{
ProbeAcq pa;
pa.hx711.init(HX711_SCK_PIN, HX711_SDO_PIN);
pa.rcFilter.init(RC_CUTE_FRQ, 80, 0);
pa.minZ_mm = -BED_SIZE_Y_MM * 1.5;
// pa.basePos_mm.x = BED_SIZE_X_MM / 2 + (isPrecision ? 0 : 5); // 如果不是精确测量,为防止喷头上的耗材污染中心点,这里给于微小偏移
// pa.basePos_mm.y = BED_SIZE_Y_MM / 2 + (isPrecision ? 0 : 5);
pa.basePos_mm.x = AUTOZ_TOOL_X + (isPrecision ? 0 : 5); // 如果不是精确测量,为防止喷头上的耗材污染中心点,这里给于微小偏移
pa.basePos_mm.y = AUTOZ_TOOL_Y + (isPrecision ? 0 : 5);
pa.basePos_mm.z = GET_CURRENT_POS().z;
pa.baseSpdXY_mm_s = 200;
pa.baseSpdZ_mm_s = 5;
pa.step_mm = 0.03;
pa.isUpAfter = false;
pa.isShowMsg = false;
pa.minHold = (isPrecision ? MIN_HOLD : (MAX_HOLD / 5));
pa.maxHold = MAX_HOLD;
//CHECK_AND_RUN((!(pa.checHx711() || pa.checHx711())), PRINTF("%s\n", "***G28 HX711 CHECK FAILE!!!***")); //检测模块工作是否正常
int nowVal = 0, unFitVal = pa.readBase().y;
do{
pa.probePointByStep();
nowVal = pa.readBase().y;
SET_NOW_POS_Z_IS_HOME();
pa.basePos_mm.z = GET_CURRENT_POS().z + 3;
} while (abs(nowVal - unFitVal) < (pa.minHold / 2)); //使用压力大小来验证喷头是否压到热床,此方法可以排除干扰影响的误触发
if (isPrecision) //如果是高精度测量
{
int m = 0;
float tmp1 = 0, tmp2 = 0;
pa.minHold = MIN_HOLD;
pa.step_mm = 0.01; //精度修改成0.01mm
pa.isUpAfter = true; //测量完后抬升Z轴
pa.basePos_mm.z = 2; //开始测量时的高度为2mm
do{
pa.basePos_mm.x = BED_SIZE_X_MM / 2 + (random(0, 5) - 2);//如果不是精确测量,为防止喷头上的耗材污染中心点,这里给于微小偏移
pa.basePos_mm.y = BED_SIZE_Y_MM / 2 + (random(0, 5) - 2);
tmp1 = pa.probePointByStep()->outVal_mm;
tmp2 = pa.probePointByStep()->outVal_mm;
} while (m++ < 2 && (fabsf(tmp1 - tmp2) >= 0.05)); //测量两次,并对比两者之差
DO_BLOCKING_MOVE_TO_Z((tmp1 + tmp2) / 2, pa.baseSpdZ_mm_s);//设定HOME点
SET_NOW_POS_Z_IS_HOME();
}
DO_BLOCKING_MOVE_TO_XY(Z_SAFE_HOMING_X_POINT, Z_SAFE_HOMING_Y_POINT, pa.baseSpdXY_mm_s);
DO_BLOCKING_MOVE_TO_Z(5, 10);
}
/**
* @brief 用于相关内容验证,常用于功能调试
*/
void doG212ExCmd(void)
{
float cnt = GET_PARSER_SEEN('C') ? GET_PARSER_INT_VAL() : 1;
if(GET_PARSER_SEEN('H'))
{
HX711 hx711;
hx711.init(HX711_SCK_PIN, HX711_SDO_PIN);
FOR_LOOP_TIMES(i, 0, cnt, hx711.getVal(1));
return;
}
if(GET_PARSER_SEEN('T'))
{
ProbeAcq pa;
pa.hx711.init(HX711_SCK_PIN, HX711_SDO_PIN);
pa.rcFilter.init(RC_CUTE_FRQ, 80, 0);
pa.minZ_mm = -BED_SIZE_Y_MM * 1.5;
pa.basePos_mm.x = GET_CURRENT_POS().x;
pa.basePos_mm.y = GET_CURRENT_POS().y;
pa.basePos_mm.z = GET_CURRENT_POS().z;
pa.baseSpdXY_mm_s = 100;
pa.baseSpdZ_mm_s = 5;
pa.step_mm = 0.0125;
pa.isUpAfter = true;
pa.isShowMsg = true;
pa.minHold = MIN_HOLD;
pa.maxHold = MAX_HOLD;
pa.probePointByStep();
return;
}
if(GET_PARSER_SEEN('M'))
{
printBedMesh();
}
if(GET_PARSER_SEEN('L'))
{
clearNozzle(120, 180, 60, 0);
}
if(GET_PARSER_SEEN('E'))
{
clearNozzle(120, 200, 60, PA_FIL_LEN_MM);
}
}
#endif
+223
View File
@@ -0,0 +1,223 @@
/**
* @file 文件名(PressLeveled.h/PressLeveled.c
* @brief 使用应变片进行喷头擦拭、高度测量、数据校验、Z轴补偿相关接口
* @details
* @attention 使用者移植过程中,需保证所有的宏定义正确且运行正常(当前宏定义基于Marlin 2.0.8.3)。
* @author 王玉龙107051
* @date 2022-06-20
* @version 文件当前的版本号(V1.0.0)。
* @copyright
*/
#ifndef __PRESS_LEVELED_H__
#define __PRESS_LEVELED_H__
#include "../inc/MarlinConfig.h"
#include "probe.h"
#include "motion.h"
#include "planner.h"
#include "stepper.h"
#include "../gcode/parser.h"
#include "temperature.h"
#include "../HAL/shared/Delay.h"
//#include "../lcd/dwin/lcd_rts.h"
#if ENABLED(USE_AUTOZ_TOOL) //一键对高第一种方式
//设置GPIO工作模式
#define GPIO_SET_MODE(pin, isOut) {if((isOut)>0) SET_OUTPUT((pin)); else SET_INPUT_PULLUP((pin));}
//设置GPIO输出值
#define GPIO_SET_VAL(pin, val) WRITE((pin), (val))
//获取GPIO输入值
#define GPIO_GET_VAL(pin) READ((pin))
//禁止全局中断,HX711读取数据时需使用
#define DIASBLE_ALL_ISR() DISABLE_ISRS()
//恢复全司中断
#define ENABLE_ALL_ISR() ENABLE_ISRS()
//热床的X方向尺寸,单位mm
#define BED_SIZE_X_MM X_BED_SIZE
//热床的Y方向尺寸,单位mm
#define BED_SIZE_Y_MM Y_BED_SIZE
#define BED_SIZE_Z_MM Z_MAX_POS
//自动调平X方向上的点数量
#define BED_MESH_X_PT GRID_MAX_POINTS_X
//自动调平Y方向上的点数量
#define BED_MESH_Y_PT GRID_MAX_POINTS_Y
//自动调平,边沿上的调平检测点距离热床边沿的距离
#define BED_PROBE_EDGE PROBING_MARGIN
//通过串口打印调试信息
#define SERIAL_PRINT_MSG(msg) {char* str = msg; while (*str != '\0') MYSERIAL1.write(*str++);}
//获取系统时间戳
#define GET_TICK_MS() millis()
//延时us(微秒)
#define TIME_DELAY_US(dUs) DELAY_US(dUs)
//Marlin的idle()主循环
#define MARLIN_CORE_IDLE() idle()
//更新看门狗
#define REFRESH_WATCHDOG() {HAL_watchdog_refresh();}
//堵塞执行一条GCODE指令
#define RUN_AND_WAIT_GCODE_CMD(gcode, isWait) planner.synchronize();queue.inject_P(PSTR((gcode))); queue.advance(); if(isWait) {planner.synchronize();}
//设置热床温度
#define SET_BED_TEMP(temp) thermalManager.setTargetBed(temp)
//获取热床当前温度
#define GET_BED_TEMP() thermalManager.temp_bed.celsius
//获取热床目标温度
#define GET_BED_TAR_TEMP() thermalManager.temp_bed.target
//设置喷头温度
#define SET_HOTEND_TEMP(temp, index) thermalManager.setTargetHotend((temp), (index))
//获取喷头当前温度
#define GET_HOTEND_TEMP(index) thermalManager.temp_hotend[(index)].celsius
//获取喷头目标温度
#define GET_HOTEND_TAR_TEMP(index) thermalManager.temp_hotend[(index)].target
//设定模型散热风扇状态0~255
#define SET_FAN_SPD(sta) thermalManager.fan_speed[0] = (sta)
//XYZE电机,每毫米需要给定的步数
#define STEPS_PRE_UNIT DEFAULT_AXIS_STEPS_PER_UNIT //#define DEFAULT_AXIS_STEPS_PER_UNIT { 80, 80, 400, 424.9 }
//Z轴电机前进一步
#define AXIS_Z_STEP_PLUS(dUs) {Z_STEP_WRITE(!INVERT_Z_STEP_PIN);TIME_DELAY_US((dUs));Z_STEP_WRITE(INVERT_Z_STEP_PIN);TIME_DELAY_US((dUs));}
//Z轴电机方向读取
#define AXIS_Z_DIR_GET() Z_DIR_READ()
//Z轴电机方向设置
#define AXIS_Z_DIR_SET(dir) Z_DIR_WRITE(dir)
//Z轴电机方向设置,向Z+方向运动
#define AXIS_Z_DIR_ADD() Z_DIR_WRITE(0)
//Z轴电机方向设置,向Z-方向运动
#define AXIS_Z_DIR_DIV() Z_DIR_WRITE(1)
//Z轴电机使能
#define AXIS_Z_ENABLE() ENABLE_AXIS_Z()
//检测电机是否正在运行,返回true为正在运行,返回false为运行完成
#define AXIS_XYZE_STATUS() (planner.has_blocks_queued() || planner.cleaning_buffer_counter)
//设定Z-OFFSET并保存EEPROM
#define SET_Z_OFFSET(zOffset) {last_zoffset = probe.offset.z = zOffset; RTSUpdate();}
//设定当前Z轴坐标为home点(0点)
#define SET_NOW_POS_Z_IS_HOME() {set_axis_is_at_home(Z_AXIS);sync_plan_position();}
//获取当前喷头的xyz的坐标
#define GET_CURRENT_POS() current_position
//检测GCODE指令是否包含给定参数
#define GET_PARSER_SEEN(c) parser.seen(c)
//获取GCODE指令中给定参数的值int型
#define GET_PARSER_INT_VAL() parser.value_int()
//获取GCODE指令中给定参数的值float
#define GET_PARSER_FLOAT_VAL() parser.value_float()
//堵塞并执行XY轴运动到给定位置
#define DO_BLOCKING_MOVE_TO_XY(x_mm, y_mm, spd_mm_s) do_blocking_move_to_xy((x_mm), (y_mm), (spd_mm_s))
//堵塞并执行Z轴运动到给定位置
#define DO_BLOCKING_MOVE_TO_Z(z_mm, spd_mm_s) do_blocking_move_to_z((z_mm), (spd_mm_s))
/***end***/
/***以下宏定义,为系统配置参数,可根据实际需求进行修改,一般保持默认即可***/
#define SHOW_MSG 1 //!< 测量过程中,是否打印调试信息
#define BASE_COUNT 40 //!< 测量过程中,在正常使用HX711的数据前,先读取一定次数据的数据以保证HX711工作稳定
#define MIN_HOLD 1000 //!< 触发检测的最小阈值,防止误触发
#define MAX_HOLD 20000 //!< 触发检测的最大阈值,防止过触发
#define RC_CUTE_FRQ 1 //!< RC滤波器的截止频率0.1~10,值越小=触发越灵敏;值越大=触发越迟钝。
#define PA_FIL_LEN_MM 20 //!< 挤出喷头擦拭过程中,耗材的长度,
#define PA_FIL_DIS_MM 30 //!< 挤出喷头擦拭过程中,擦拭的距离,
#define PA_CLR_DIS_MM 20 //!< 不挤出喷头擦拭过程中,擦拭的距离,越大擦拭成功率越高,但要小于热床Y_SIZE/2
#define BED_MAX_ERR 5 //!< 产品所允许的,热床平面高度值的绝对值。如取值为5,则表明热床中心点Z高度为0,产品热床其它任意点的高度Z相对于中心点的差的绝对值最大不超过5mm
#define MAX_REPROBE_CNT ((BED_MESH_X_PT * BED_MESH_X_PT) / 2) //!< 如果调平点的总重复测量次数超过此值,则可认为喷头上粘有耗材,要进行喷头擦拭后再次测量
#define DEFORMATION_SIZE 0.00 // The size of the deformation when the sensor is triggered, in mm, is related to the sensitivity of the sensor itself
// The sensitivity should be significantly modified or a different strain gauge should be replaced
/***end***/
/***以下宏定义,为系统调用,保持默认***/
#define IS_ZERO(val) (fabs(val) < 0.00001 ? true : false) //!< 浮点型变量是否为0的判断
#define PRINTF(str, ...) {char strMsg[128] = {0}; sprintf(strMsg, str, __VA_ARGS__); SERIAL_PRINT_MSG(strMsg);} //替换sprintf和printf的接口
/***end***/
//HX711芯片驱动,用于读取压力传感器的数据
class HX711
{
public:
void init(int clkPin, int sdoPin);
int getVal(bool isShowMsg = 0);
static bool ckGpioIsInited(int pin);
private:
int clkPin;
int sdoPin;
};
// RC高通滤波器,用于滤除如温度变化、导线拉扯等低频干扰。
class RCLFilter
{
private:
double vi;
double viPrev;
double voPrev;
double vo;
public:
double cutoffFrqHz;
double acqFrqHz;
void init(double cutFrqHz, double acqFrqHz, double baseVal);
double filter(double newVal);
};
//使用压力传感器探测单点高度类
#define PI_COUNT 32
class ProbeAcq
{
public:
xyz_float_t basePos_mm; //即开始测量此点前,喷头需要达到的准备位置坐标
float baseSpdXY_mm_s; //喷头在x和y平面移动的准备速度
float baseSpdZ_mm_s; //喷头在z平面移动的准备速度
float minZ_mm; //向Z轴运动到的停止位置,即到达此位置时还未检测到压力变化,则强制停止。
bool isUpAfter; //测量完成后,是否复位Z轴到准备位置
bool isShowMsg;
float step_mm; //每移动此距离,读取一次压力传感器
int minHold; //最小阈值,触发条件的最后一个点需要大于此值
int maxHold; //最大阈值,触发条件的最后一个点大于此值则强制触发
float outVal_mm; //输出,触发时对应的轴坐标
int outIndex; //输出,触发时对应的序列索引,如果值不位于(PI_COUNT*2/3, PI_COUNT-1)区间,则测量错误,需要重新测量。
HX711 hx711; //指向CS123x或HX711的采集函数
RCLFilter rcFilter; //高通滤波器
ProbeAcq* probePointByStep(); //根据此类的参数配置测试此点
xyz_long_t readBase(); //获取干净的数据
bool checHx711(); //检测压力传感器是否工作正常
private:
double valP[PI_COUNT]; //压力保存序列的压力值
double posZ[PI_COUNT]; //压力保存序列的对应坐标值
void calMinZ(); //根据压力保存序列计算测量结果
bool checkTrigger(int fitVal, int unfitDifVal); //检测压力保存序列中的数据是否满足触发条件
};
/* 1、调试指令相关内容 */
void doG212ExCmd(void);
/* 2、G28 HOME点获取相关*/
void doG28ZProbe(bool isPrecision);
/* 3、G29 多点测量前的准备相关*/
void initBedMesh(void);
bool clearNozzle(float minHotendTemp, float maxHotendTemp, float bedTemp, int doExFil_mm);
bool probeReady(void);
/* 4、G29 单点测量相关*/
float doG29Probe(float xPos, float yPos);
bool setBedMesh(int xIndex, int yIndex, float xPos_mm, float yPos_mm, float zPos_mm);
/* 5、G29 测量完成后续操作*/
void checkAndReProbe(void);
void updataBedMesh(void);
void printBedMesh(void);
/* 6、打印时Z轴补偿值获取相关*/
float getMeshZ(float xPos, float yPos);
#endif
#endif
+180
View File
@@ -0,0 +1,180 @@
/* This is a public domain base64 implementation written by WEI Zhicheng. */
#include "base64.h"
#define BASE64_PAD '='
#define BASE64DE_FIRST '+'
#define BASE64DE_LAST 'z'
/* BASE 64 encode table */
static const char base64en[] = {
'A', 'B', 'C', 'D', 'E', 'F', 'G', 'H',
'I', 'J', 'K', 'L', 'M', 'N', 'O', 'P',
'Q', 'R', 'S', 'T', 'U', 'V', 'W', 'X',
'Y', 'Z', 'a', 'b', 'c', 'd', 'e', 'f',
'g', 'h', 'i', 'j', 'k', 'l', 'm', 'n',
'o', 'p', 'q', 'r', 's', 't', 'u', 'v',
'w', 'x', 'y', 'z', '0', '1', '2', '3',
'4', '5', '6', '7', '8', '9', '+', '/',
};
/* ASCII order for BASE 64 decode, 255 in unused character */
static const unsigned char base64de[] = {
/* nul, soh, stx, etx, eot, enq, ack, bel, */
255, 255, 255, 255, 255, 255, 255, 255,
/* bs, ht, nl, vt, np, cr, so, si, */
255, 255, 255, 255, 255, 255, 255, 255,
/* dle, dc1, dc2, dc3, dc4, nak, syn, etb, */
255, 255, 255, 255, 255, 255, 255, 255,
/* can, em, sub, esc, fs, gs, rs, us, */
255, 255, 255, 255, 255, 255, 255, 255,
/* sp, '!', '"', '#', '$', '%', '&', ''', */
255, 255, 255, 255, 255, 255, 255, 255,
/* '(', ')', '*', '+', ',', '-', '.', '/', */
255, 255, 255, 62, 255, 255, 255, 63,
/* '0', '1', '2', '3', '4', '5', '6', '7', */
52, 53, 54, 55, 56, 57, 58, 59,
/* '8', '9', ':', ';', '<', '=', '>', '?', */
60, 61, 255, 255, 255, 255, 255, 255,
/* '@', 'A', 'B', 'C', 'D', 'E', 'F', 'G', */
255, 0, 1, 2, 3, 4, 5, 6,
/* 'H', 'I', 'J', 'K', 'L', 'M', 'N', 'O', */
7, 8, 9, 10, 11, 12, 13, 14,
/* 'P', 'Q', 'R', 'S', 'T', 'U', 'V', 'W', */
15, 16, 17, 18, 19, 20, 21, 22,
/* 'X', 'Y', 'Z', '[', '\', ']', '^', '_', */
23, 24, 25, 255, 255, 255, 255, 255,
/* '`', 'a', 'b', 'c', 'd', 'e', 'f', 'g', */
255, 26, 27, 28, 29, 30, 31, 32,
/* 'h', 'i', 'j', 'k', 'l', 'm', 'n', 'o', */
33, 34, 35, 36, 37, 38, 39, 40,
/* 'p', 'q', 'r', 's', 't', 'u', 'v', 'w', */
41, 42, 43, 44, 45, 46, 47, 48,
/* 'x', 'y', 'z', '{', '|', '}', '~', del, */
49, 50, 51, 255, 255, 255, 255, 255
};
unsigned int
base64_encode(const unsigned char *in, unsigned int inlen, char *out)
{
int s;
unsigned int i;
unsigned int j;
unsigned char c;
unsigned char l;
s = 0;
l = 0;
for (i = j = 0; i < inlen; i++)
{
c = in[i];
switch (s)
{
case 0:
s = 1;
out[j++] = base64en[(c >> 2) & 0x3F];
break;
case 1:
s = 2;
out[j++] = base64en[((l & 0x3) << 4) | ((c >> 4) & 0xF)];
break;
case 2:
s = 0;
out[j++] = base64en[((l & 0xF) << 2) | ((c >> 6) & 0x3)];
out[j++] = base64en[c & 0x3F];
break;
}
l = c;
}
switch (s)
{
case 1:
out[j++] = base64en[(l & 0x3) << 4];
out[j++] = BASE64_PAD;
out[j++] = BASE64_PAD;
break;
case 2:
out[j++] = base64en[(l & 0xF) << 2];
out[j++] = BASE64_PAD;
break;
}
out[j] = 0;
return j;
}
/**
* @功能 Base64 解码
* *in 指向待解码的数据的指针
* inlen 待解码数据长度
* *out 指向解码完成的数据的指针
* return : 解码完成的数据长度
*/
unsigned int
base64_decode(const char *in, unsigned int inlen, unsigned char *out)
{
unsigned int i;
unsigned int j;
unsigned char c;
if (inlen & 0x3)
{
return 0;
}
for (i = j = 0; i < inlen; i++)
{
if (in[i] == BASE64_PAD)
{
break;
}
if (in[i] < BASE64DE_FIRST || in[i] > BASE64DE_LAST)
{
return 0;
}
c = base64de[(unsigned char)in[i]];
if (c == 255)
{
return 0;
}
switch (i & 0x3)
{
case 0:
out[j] = (c << 2) & 0xFF;
break;
case 1:
out[j++] |= (c >> 4) & 0x3;
out[j] = (c & 0xF) << 4;
break;
case 2:
out[j++] |= (c >> 2) & 0xF;
out[j] = (c & 0x3) << 6;
break;
case 3:
out[j++] |= c;
break;
}
}
return j;
}
+20
View File
@@ -0,0 +1,20 @@
#ifndef BASE64_H
#define BASE64_H
#define BASE64_ENCODE_OUT_SIZE(s) ((unsigned int)((((s) + 2) / 3) * 4 + 1))
#define BASE64_DECODE_OUT_SIZE(s) ((unsigned int)(((s) / 4) * 3))
/*
* out is null-terminated encode string.
* return values is out length, exclusive terminating `\0'
*/
unsigned int
base64_encode(const unsigned char *in, unsigned int inlen, char *out);
/*
* return values is out length
*/
unsigned int
base64_decode(const char *in, unsigned int inlen, unsigned char *out);
#endif /* BASE64_H */
+287
View File
@@ -0,0 +1,287 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
/**
* delta.cpp
*/
#include "../inc/MarlinConfig.h"
#if ENABLED(DELTA)
#include "delta.h"
#include "motion.h"
// For homing:
#include "planner.h"
#include "endstops.h"
#include "../lcd/marlinui.h"
#include "../MarlinCore.h"
#if HAS_BED_PROBE
#include "probe.h"
#endif
#if ENABLED(SENSORLESS_HOMING)
#include "../feature/tmc_util.h"
#include "stepper/indirection.h"
#endif
#define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE)
#include "../core/debug_out.h"
// Initialized by settings.load()
float delta_height;
abc_float_t delta_endstop_adj{0};
float delta_radius,
delta_diagonal_rod,
segments_per_second;
abc_float_t delta_tower_angle_trim;
xy_float_t delta_tower[ABC];
abc_float_t delta_diagonal_rod_2_tower;
float delta_clip_start_height = Z_MAX_POS;
abc_float_t delta_diagonal_rod_trim;
float delta_safe_distance_from_top();
/**
* Recalculate factors used for delta kinematics whenever
* settings have been changed (e.g., by M665).
*/
void recalc_delta_settings() {
constexpr abc_float_t trt = DELTA_RADIUS_TRIM_TOWER;
delta_tower[A_AXIS].set(cos(RADIANS(210 + delta_tower_angle_trim.a)) * (delta_radius + trt.a), // front left tower
sin(RADIANS(210 + delta_tower_angle_trim.a)) * (delta_radius + trt.a));
delta_tower[B_AXIS].set(cos(RADIANS(330 + delta_tower_angle_trim.b)) * (delta_radius + trt.b), // front right tower
sin(RADIANS(330 + delta_tower_angle_trim.b)) * (delta_radius + trt.b));
delta_tower[C_AXIS].set(cos(RADIANS( 90 + delta_tower_angle_trim.c)) * (delta_radius + trt.c), // back middle tower
sin(RADIANS( 90 + delta_tower_angle_trim.c)) * (delta_radius + trt.c));
delta_diagonal_rod_2_tower.set(sq(delta_diagonal_rod + delta_diagonal_rod_trim.a),
sq(delta_diagonal_rod + delta_diagonal_rod_trim.b),
sq(delta_diagonal_rod + delta_diagonal_rod_trim.c));
update_software_endstops(Z_AXIS);
set_all_unhomed();
}
/**
* Get a safe radius for calibration
*/
#if EITHER(DELTA_AUTO_CALIBRATION, DELTA_CALIBRATION_MENU)
#if ENABLED(DELTA_AUTO_CALIBRATION)
float calibration_radius_factor = 1;
#endif
float delta_calibration_radius() {
return calibration_radius_factor * (
#if HAS_BED_PROBE
FLOOR((DELTA_PRINTABLE_RADIUS) - _MAX(HYPOT(probe.offset_xy.x, probe.offset_xy.y), PROBING_MARGIN))
#else
DELTA_PRINTABLE_RADIUS
#endif
);
}
#endif
/**
* Delta Inverse Kinematics
*
* Calculate the tower positions for a given machine
* position, storing the result in the delta[] array.
*
* This is an expensive calculation, requiring 3 square
* roots per segmented linear move, and strains the limits
* of a Mega2560 with a Graphical Display.
*
* Suggested optimizations include:
*
* - Disable the home_offset (M206) and/or position_shift (G92)
* features to remove up to 12 float additions.
*/
#define DELTA_DEBUG(VAR) do { \
SERIAL_ECHOLNPAIR_P(PSTR("Cartesian X"), VAR.x, SP_Y_STR, VAR.y, SP_Z_STR, VAR.z); \
SERIAL_ECHOLNPAIR_P(PSTR("Delta A"), delta.a, SP_B_STR, delta.b, SP_C_STR, delta.c); \
}while(0)
void inverse_kinematics(const xyz_pos_t &raw) {
#if HAS_HOTEND_OFFSET
// Delta hotend offsets must be applied in Cartesian space with no "spoofing"
xyz_pos_t pos = { raw.x - hotend_offset[active_extruder].x,
raw.y - hotend_offset[active_extruder].y,
raw.z };
DELTA_IK(pos);
//DELTA_DEBUG(pos);
#else
DELTA_IK(raw);
//DELTA_DEBUG(raw);
#endif
}
/**
* Calculate the highest Z position where the
* effector has the full range of XY motion.
*/
float delta_safe_distance_from_top() {
xyz_pos_t cartesian{0};
inverse_kinematics(cartesian);
const float centered_extent = delta.a;
cartesian.y = DELTA_PRINTABLE_RADIUS;
inverse_kinematics(cartesian);
return ABS(centered_extent - delta.a);
}
/**
* Delta Forward Kinematics
*
* See the Wikipedia article "Trilateration"
* https://en.wikipedia.org/wiki/Trilateration
*
* Establish a new coordinate system in the plane of the
* three carriage points. This system has its origin at
* tower1, with tower2 on the X axis. Tower3 is in the X-Y
* plane with a Z component of zero.
* We will define unit vectors in this coordinate system
* in our original coordinate system. Then when we calculate
* the Xnew, Ynew and Znew values, we can translate back into
* the original system by moving along those unit vectors
* by the corresponding values.
*
* Variable names matched to Marlin, c-version, and avoid the
* use of any vector library.
*
* by Andreas Hardtung 2016-06-07
* based on a Java function from "Delta Robot Kinematics V3"
* by Steve Graves
*
* The result is stored in the cartes[] array.
*/
void forward_kinematics(const_float_t z1, const_float_t z2, const_float_t z3) {
// Create a vector in old coordinates along x axis of new coordinate
const float p12[3] = { delta_tower[B_AXIS].x - delta_tower[A_AXIS].x, delta_tower[B_AXIS].y - delta_tower[A_AXIS].y, z2 - z1 },
// Get the reciprocal of Magnitude of vector.
d2 = sq(p12[0]) + sq(p12[1]) + sq(p12[2]), inv_d = RSQRT(d2),
// Create unit vector by multiplying by the inverse of the magnitude.
ex[3] = { p12[0] * inv_d, p12[1] * inv_d, p12[2] * inv_d },
// Get the vector from the origin of the new system to the third point.
p13[3] = { delta_tower[C_AXIS].x - delta_tower[A_AXIS].x, delta_tower[C_AXIS].y - delta_tower[A_AXIS].y, z3 - z1 },
// Use the dot product to find the component of this vector on the X axis.
i = ex[0] * p13[0] + ex[1] * p13[1] + ex[2] * p13[2],
// Create a vector along the x axis that represents the x component of p13.
iex[3] = { ex[0] * i, ex[1] * i, ex[2] * i };
// Subtract the X component from the original vector leaving only Y. We use the
// variable that will be the unit vector after we scale it.
float ey[3] = { p13[0] - iex[0], p13[1] - iex[1], p13[2] - iex[2] };
// The magnitude and the inverse of the magnitude of Y component
const float j2 = sq(ey[0]) + sq(ey[1]) + sq(ey[2]), inv_j = RSQRT(j2);
// Convert to a unit vector
ey[0] *= inv_j; ey[1] *= inv_j; ey[2] *= inv_j;
// The cross product of the unit x and y is the unit z
// float[] ez = vectorCrossProd(ex, ey);
const float ez[3] = {
ex[1] * ey[2] - ex[2] * ey[1],
ex[2] * ey[0] - ex[0] * ey[2],
ex[0] * ey[1] - ex[1] * ey[0]
},
// We now have the d, i and j values defined in Wikipedia.
// Plug them into the equations defined in Wikipedia for Xnew, Ynew and Znew
Xnew = (delta_diagonal_rod_2_tower.a - delta_diagonal_rod_2_tower.b + d2) * inv_d * 0.5,
Ynew = ((delta_diagonal_rod_2_tower.a - delta_diagonal_rod_2_tower.c + sq(i) + j2) * 0.5 - i * Xnew) * inv_j,
Znew = SQRT(delta_diagonal_rod_2_tower.a - HYPOT2(Xnew, Ynew));
// Start from the origin of the old coordinates and add vectors in the
// old coords that represent the Xnew, Ynew and Znew to find the point
// in the old system.
cartes.set(delta_tower[A_AXIS].x + ex[0] * Xnew + ey[0] * Ynew - ez[0] * Znew,
delta_tower[A_AXIS].y + ex[1] * Xnew + ey[1] * Ynew - ez[1] * Znew,
z1 + ex[2] * Xnew + ey[2] * Ynew - ez[2] * Znew);
}
/**
* A delta can only safely home all axes at the same time
* This is like quick_home_xy() but for 3 towers.
*/
void home_delta() {
DEBUG_SECTION(log_home_delta, "home_delta", DEBUGGING(LEVELING));
// Init the current position of all carriages to 0,0,0
current_position.reset();
destination.reset();
sync_plan_position();
// Disable stealthChop if used. Enable diag1 pin on driver.
#if ENABLED(SENSORLESS_HOMING)
TERN_(X_SENSORLESS, sensorless_t stealth_states_x = start_sensorless_homing_per_axis(X_AXIS));
TERN_(Y_SENSORLESS, sensorless_t stealth_states_y = start_sensorless_homing_per_axis(Y_AXIS));
TERN_(Z_SENSORLESS, sensorless_t stealth_states_z = start_sensorless_homing_per_axis(Z_AXIS));
#endif
// Move all carriages together linearly until an endstop is hit.
current_position.z = DIFF_TERN(HAS_BED_PROBE, delta_height + 10, probe.offset.z);
line_to_current_position(homing_feedrate(Z_AXIS));
planner.synchronize();
// Re-enable stealthChop if used. Disable diag1 pin on driver.
#if ENABLED(SENSORLESS_HOMING) && DISABLED(ENDSTOPS_ALWAYS_ON_DEFAULT)
TERN_(X_SENSORLESS, end_sensorless_homing_per_axis(X_AXIS, stealth_states_x));
TERN_(Y_SENSORLESS, end_sensorless_homing_per_axis(Y_AXIS, stealth_states_y));
TERN_(Z_SENSORLESS, end_sensorless_homing_per_axis(Z_AXIS, stealth_states_z));
#endif
endstops.validate_homing_move();
// At least one carriage has reached the top.
// Now re-home each carriage separately.
homeaxis(A_AXIS);
homeaxis(B_AXIS);
homeaxis(C_AXIS);
// Set all carriages to their home positions
// Do this here all at once for Delta, because
// XYZ isn't ABC. Applying this per-tower would
// give the impression that they are the same.
LOOP_ABC(i) set_axis_is_at_home((AxisEnum)i);
sync_plan_position();
#if DISABLED(DELTA_HOME_TO_SAFE_ZONE) && defined(HOMING_BACKOFF_POST_MM)
constexpr xyz_float_t endstop_backoff = HOMING_BACKOFF_POST_MM;
if (endstop_backoff.z) {
current_position.z -= ABS(endstop_backoff.z) * Z_HOME_DIR;
line_to_current_position(homing_feedrate(Z_AXIS));
}
#endif
}
#endif // DELTA
+129
View File
@@ -0,0 +1,129 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* delta.h - Delta-specific functions
*/
#include "../core/types.h"
#include "../core/macros.h"
extern float delta_height;
extern abc_float_t delta_endstop_adj;
extern float delta_radius,
delta_diagonal_rod,
segments_per_second;
extern abc_float_t delta_tower_angle_trim;
extern xy_float_t delta_tower[ABC];
extern abc_float_t delta_diagonal_rod_2_tower;
extern float delta_clip_start_height;
extern abc_float_t delta_diagonal_rod_trim;
/**
* Recalculate factors used for delta kinematics whenever
* settings have been changed (e.g., by M665).
*/
void recalc_delta_settings();
/**
* Get a safe radius for calibration
*/
#if ENABLED(DELTA_AUTO_CALIBRATION)
extern float calibration_radius_factor;
#else
constexpr float calibration_radius_factor = 1;
#endif
#if EITHER(DELTA_AUTO_CALIBRATION, DELTA_CALIBRATION_MENU)
float delta_calibration_radius();
#endif
/**
* Delta Inverse Kinematics
*
* Calculate the tower positions for a given machine
* position, storing the result in the delta[] array.
*
* This is an expensive calculation, requiring 3 square
* roots per segmented linear move, and strains the limits
* of a Mega2560 with a Graphical Display.
*
* Suggested optimizations include:
*
* - Disable the home_offset (M206) and/or position_shift (G92)
* features to remove up to 12 float additions.
*
* - Use a fast-inverse-sqrt function and add the reciprocal.
* (see above)
*/
// Macro to obtain the Z position of an individual tower
#define DELTA_Z(V,T) V.z + SQRT( \
delta_diagonal_rod_2_tower[T] - HYPOT2( \
delta_tower[T].x - V.x, \
delta_tower[T].y - V.y \
) \
)
#define DELTA_IK(V) delta.set(DELTA_Z(V, A_AXIS), DELTA_Z(V, B_AXIS), DELTA_Z(V, C_AXIS))
void inverse_kinematics(const xyz_pos_t &raw);
/**
* Calculate the highest Z position where the
* effector has the full range of XY motion.
*/
float delta_safe_distance_from_top();
/**
* Delta Forward Kinematics
*
* See the Wikipedia article "Trilateration"
* https://en.wikipedia.org/wiki/Trilateration
*
* Establish a new coordinate system in the plane of the
* three carriage points. This system has its origin at
* tower1, with tower2 on the X axis. Tower3 is in the X-Y
* plane with a Z component of zero.
* We will define unit vectors in this coordinate system
* in our original coordinate system. Then when we calculate
* the Xnew, Ynew and Znew values, we can translate back into
* the original system by moving along those unit vectors
* by the corresponding values.
*
* Variable names matched to Marlin, c-version, and avoid the
* use of any vector library.
*
* by Andreas Hardtung 2016-06-07
* based on a Java function from "Delta Robot Kinematics V3"
* by Steve Graves
*
* The result is stored in the cartes[] array.
*/
void forward_kinematics(const_float_t z1, const_float_t z2, const_float_t z3);
FORCE_INLINE void forward_kinematics(const abc_float_t &point) {
forward_kinematics(point.a, point.b, point.c);
}
void home_delta();
File diff suppressed because it is too large Load Diff
+244
View File
@@ -0,0 +1,244 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* endstops.h - manages endstops
*/
#include "../inc/MarlinConfig.h"
#include <stdint.h>
#define __ES_ITEM(N) N,
#define _ES_ITEM(K,N) TERN_(K,DEFER4(__ES_ITEM)(N))
enum EndstopEnum : char {
// Common XYZ (ABC) endstops. Defined according to USE_[XYZ](MIN|MAX)_PLUG settings.
_ES_ITEM(HAS_X_MIN, X_MIN)
_ES_ITEM(HAS_X_MAX, X_MAX)
_ES_ITEM(HAS_Y_MIN, Y_MIN)
_ES_ITEM(HAS_Y_MAX, Y_MAX)
_ES_ITEM(HAS_Z_MIN, Z_MIN)
_ES_ITEM(HAS_Z_MAX, Z_MAX)
// Extra Endstops for XYZ
#if ENABLED(X_DUAL_ENDSTOPS)
_ES_ITEM(HAS_X_MIN, X2_MIN)
_ES_ITEM(HAS_X_MAX, X2_MAX)
#endif
#if ENABLED(Y_DUAL_ENDSTOPS)
_ES_ITEM(HAS_Y_MIN, Y2_MIN)
_ES_ITEM(HAS_Y_MAX, Y2_MAX)
#endif
#if ENABLED(Z_MULTI_ENDSTOPS)
_ES_ITEM(HAS_Z_MIN, Z2_MIN)
_ES_ITEM(HAS_Z_MAX, Z2_MAX)
#if NUM_Z_STEPPER_DRIVERS >= 3
_ES_ITEM(HAS_Z_MIN, Z3_MIN)
_ES_ITEM(HAS_Z_MAX, Z3_MAX)
#endif
#if NUM_Z_STEPPER_DRIVERS >= 4
_ES_ITEM(HAS_Z_MIN, Z4_MIN)
_ES_ITEM(HAS_Z_MAX, Z4_MAX)
#endif
#endif
// Bed Probe state is distinct or shared with Z_MIN (i.e., when the probe is the only Z endstop)
_ES_ITEM(HAS_BED_PROBE, Z_MIN_PROBE IF_DISABLED(HAS_CUSTOM_PROBE_PIN, = Z_MIN))
// The total number of states
NUM_ENDSTOP_STATES
// Endstops can be either MIN or MAX but not both
#if HAS_X_MIN || HAS_X_MAX
, X_ENDSTOP = TERN(X_HOME_TO_MAX, X_MAX, X_MIN)
#endif
#if HAS_Y_MIN || HAS_Y_MAX
, Y_ENDSTOP = TERN(Y_HOME_TO_MAX, Y_MAX, Y_MIN)
#endif
#if HAS_Z_MIN || HAS_Z_MAX
, Z_ENDSTOP = TERN(Z_HOME_TO_MAX, Z_MAX, TERN(HOMING_Z_WITH_PROBE, Z_MIN_PROBE, Z_MIN))
#endif
};
#undef __ES_ITEM
#undef _ES_ITEM
class Endstops {
public:
typedef IF<(NUM_ENDSTOP_STATES > 8), uint16_t, uint8_t>::type endstop_mask_t;
#if ENABLED(X_DUAL_ENDSTOPS)
static float x2_endstop_adj;
#endif
#if ENABLED(Y_DUAL_ENDSTOPS)
static float y2_endstop_adj;
#endif
#if ENABLED(Z_MULTI_ENDSTOPS)
static float z2_endstop_adj;
#endif
#if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 3
static float z3_endstop_adj;
#endif
#if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 4
static float z4_endstop_adj;
#endif
private:
static bool enabled, enabled_globally;
static endstop_mask_t live_state;
static volatile endstop_mask_t hit_state; // Use X_MIN, Y_MIN, Z_MIN and Z_MIN_PROBE as BIT index
#if ENDSTOP_NOISE_THRESHOLD
static endstop_mask_t validated_live_state;
static uint8_t endstop_poll_count; // Countdown from threshold for polling
#endif
public:
Endstops() {};
/**
* Initialize the endstop pins
*/
static void init();
/**
* Are endstops or the probe set to abort the move?
*/
FORCE_INLINE static bool abort_enabled() {
return enabled || TERN0(HAS_BED_PROBE, z_probe_enabled);
}
static inline bool global_enabled() { return enabled_globally; }
/**
* Periodic call to poll endstops if required. Called from temperature ISR
*/
static void poll();
/**
* Update endstops bits from the pins. Apply filtering to get a verified state.
* If abort_enabled() and moving towards a triggered switch, abort the current move.
* Called from ISR contexts.
*/
static void update();
/**
* Get Endstop hit state.
*/
FORCE_INLINE static endstop_mask_t trigger_state() { return hit_state; }
/**
* Get current endstops state
*/
FORCE_INLINE static endstop_mask_t state() {
return
#if ENDSTOP_NOISE_THRESHOLD
validated_live_state
#else
live_state
#endif
;
}
static inline bool probe_switch_activated()
{
return (true
#if ENABLED(PROBE_ACTIVATION_SWITCH)
&& READ(PROBE_ACTIVATION_SWITCH_PIN) == PROBE_ACTIVATION_SWITCH_STATE
#endif
);
}
/**
* Report endstop hits to serial. Called from loop().
*/
static void event_handler();
/**
* Report endstop states in response to M119
*/
static void report_states();
// Enable / disable endstop checking globally
static void enable_globally(const bool onoff=true);
// Enable / disable endstop checking
static void enable(const bool onoff=true);
// Disable / Enable endstops based on ENSTOPS_ONLY_FOR_HOMING and global enable
static void not_homing();
#if ENABLED(VALIDATE_HOMING_ENDSTOPS)
// If the last move failed to trigger an endstop, call kill
static void validate_homing_move();
#else
FORCE_INLINE static void validate_homing_move() { hit_on_purpose(); }
#endif
// Clear endstops (i.e., they were hit intentionally) to suppress the report
FORCE_INLINE static void hit_on_purpose() { hit_state = 0; }
// Enable / disable endstop z-probe checking
#if HAS_BED_PROBE
static volatile bool z_probe_enabled;
static void enable_z_probe(const bool onoff=true);
#endif
static void resync();
// Debugging of endstops
#if ENABLED(PINS_DEBUGGING)
static bool monitor_flag;
static void monitor();
static void run_monitor();
#endif
#if ENABLED(SPI_ENDSTOPS)
typedef struct {
union {
bool any;
struct { bool x:1, y:1, z:1; };
};
} tmc_spi_homing_t;
static tmc_spi_homing_t tmc_spi_homing;
static void clear_endstop_state();
static bool tmc_spi_homing_check();
#endif
};
extern Endstops endstops;
/**
* A class to save and change the endstop state,
* then restore it when it goes out of scope.
*/
class TemporaryGlobalEndstopsState {
bool saved;
public:
TemporaryGlobalEndstopsState(const bool enable) : saved(endstops.global_enabled()) {
endstops.enable_globally(enable);
}
~TemporaryGlobalEndstopsState() { endstops.enable_globally(saved); }
};
File diff suppressed because it is too large Load Diff
+542
View File
@@ -0,0 +1,542 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* motion.h
*
* High-level motion commands to feed the planner
* Some of these methods may migrate to the planner class.
*/
#include "../inc/MarlinConfig.h"
#if IS_SCARA
#include "scara.h"
#endif
// Error margin to work around float imprecision
constexpr float fslop = 0.0001;
extern bool relative_mode;
extern xyze_pos_t current_position, // High-level current tool position
destination; // Destination for a move
// G60/G61 Position Save and Return
#if SAVED_POSITIONS
extern uint8_t saved_slots[(SAVED_POSITIONS + 7) >> 3];
extern xyze_pos_t stored_position[SAVED_POSITIONS];
#endif
// Scratch space for a cartesian result
extern xyz_pos_t cartes;
// Until kinematics.cpp is created, declare this here
#if IS_KINEMATIC
extern abc_pos_t delta;
#endif
#if HAS_ABL_NOT_UBL
extern feedRate_t xy_probe_feedrate_mm_s;
#define XY_PROBE_FEEDRATE_MM_S xy_probe_feedrate_mm_s
#elif defined(XY_PROBE_FEEDRATE)
#define XY_PROBE_FEEDRATE_MM_S MMM_TO_MMS(XY_PROBE_FEEDRATE)
#else
#define XY_PROBE_FEEDRATE_MM_S PLANNER_XY_FEEDRATE()
#endif
#if HAS_BED_PROBE
constexpr feedRate_t z_probe_fast_mm_s = MMM_TO_MMS(Z_PROBE_FEEDRATE_FAST);
#endif
/**
* Feed rates are often configured with mm/m
* but the planner and stepper like mm/s units.
*/
constexpr xyz_feedrate_t homing_feedrate_mm_m = HOMING_FEEDRATE_MM_M;
FORCE_INLINE feedRate_t homing_feedrate(const AxisEnum a) {
float v;
#if ENABLED(DELTA)
v = homing_feedrate_mm_m.z;
#else
switch (a) {
case X_AXIS: v = homing_feedrate_mm_m.x; break;
case Y_AXIS: v = homing_feedrate_mm_m.y; break;
case Z_AXIS:
default: v = homing_feedrate_mm_m.z;
}
#endif
return MMM_TO_MMS(v);
}
feedRate_t get_homing_bump_feedrate(const AxisEnum axis);
/**
* The default feedrate for many moves, set by the most recent move
*/
extern feedRate_t feedrate_mm_s;
/**
* Feedrate scaling is applied to all G0/G1, G2/G3, and G5 moves
*/
extern int16_t feedrate_percentage;
#define MMS_SCALED(V) ((V) * 0.01f * feedrate_percentage)
// The active extruder (tool). Set with T<extruder> command.
#if HAS_MULTI_EXTRUDER
extern uint8_t active_extruder;
#else
constexpr uint8_t active_extruder = 0;
#endif
#if ENABLED(LCD_SHOW_E_TOTAL)
extern float e_move_accumulator;
#endif
#ifdef __IMXRT1062__
#define DEFS_PROGMEM
#else
#define DEFS_PROGMEM PROGMEM
#endif
inline float pgm_read_any(const float *p) { return TERN(__IMXRT1062__, *p, pgm_read_float(p)); }
inline int8_t pgm_read_any(const int8_t *p) { return TERN(__IMXRT1062__, *p, pgm_read_byte(p)); }
#define XYZ_DEFS(T, NAME, OPT) \
inline T NAME(const AxisEnum axis) { \
static const XYZval<T> NAME##_P DEFS_PROGMEM = { X_##OPT, Y_##OPT, Z_##OPT }; \
return pgm_read_any(&NAME##_P[axis]); \
}
XYZ_DEFS(float, base_min_pos, MIN_POS);
XYZ_DEFS(float, base_max_pos, MAX_POS);
XYZ_DEFS(float, base_home_pos, HOME_POS);
XYZ_DEFS(float, max_length, MAX_LENGTH);
XYZ_DEFS(int8_t, home_dir, HOME_DIR);
inline float home_bump_mm(const AxisEnum axis) {
static const xyz_pos_t home_bump_mm_P DEFS_PROGMEM = HOMING_BUMP_MM;
return pgm_read_any(&home_bump_mm_P[axis]);
}
#if HAS_WORKSPACE_OFFSET
void update_workspace_offset(const AxisEnum axis);
#else
inline void update_workspace_offset(const AxisEnum) {}
#endif
#if HAS_HOTEND_OFFSET
extern xyz_pos_t hotend_offset[HOTENDS];
void reset_hotend_offsets();
#elif HOTENDS
constexpr xyz_pos_t hotend_offset[HOTENDS] = { { 0 } };
#else
constexpr xyz_pos_t hotend_offset[1] = { { 0 } };
#endif
#if HAS_SOFTWARE_ENDSTOPS
typedef struct {
bool _enabled, _loose;
bool enabled() { return _enabled && !_loose; }
xyz_pos_t min, max;
void get_manual_axis_limits(const AxisEnum axis, float &amin, float &amax) {
amin = -100000; amax = 100000; // "No limits"
#if HAS_SOFTWARE_ENDSTOPS
if (enabled()) switch (axis) {
case X_AXIS:
TERN_(MIN_SOFTWARE_ENDSTOP_X, amin = min.x);
TERN_(MAX_SOFTWARE_ENDSTOP_X, amax = max.x);
break;
case Y_AXIS:
TERN_(MIN_SOFTWARE_ENDSTOP_Y, amin = min.y);
TERN_(MAX_SOFTWARE_ENDSTOP_Y, amax = max.y);
break;
case Z_AXIS:
TERN_(MIN_SOFTWARE_ENDSTOP_Z, amin = min.z);
TERN_(MAX_SOFTWARE_ENDSTOP_Z, amax = max.z);
default: break;
}
#endif
}
} soft_endstops_t;
extern soft_endstops_t soft_endstop;
void apply_motion_limits(xyz_pos_t &target);
void update_software_endstops(const AxisEnum axis
#if HAS_HOTEND_OFFSET
, const uint8_t old_tool_index=0, const uint8_t new_tool_index=0
#endif
);
#define SET_SOFT_ENDSTOP_LOOSE(loose) (soft_endstop._loose = loose)
#else // !HAS_SOFTWARE_ENDSTOPS
typedef struct {
bool enabled() { return false; }
void get_manual_axis_limits(const AxisEnum axis, float &amin, float &amax) {
// No limits
amin = current_position[axis] - 1000;
amax = current_position[axis] + 1000;
}
} soft_endstops_t;
extern soft_endstops_t soft_endstop;
#define apply_motion_limits(V) NOOP
#define update_software_endstops(...) NOOP
#define SET_SOFT_ENDSTOP_LOOSE(V) NOOP
#endif // !HAS_SOFTWARE_ENDSTOPS
void report_real_position();
void report_current_position();
void report_current_position_projected();
#if ENABLED(AUTO_REPORT_POSITION)
#include "../libs/autoreport.h"
struct PositionReport { static void report() { report_current_position_projected(); } };
extern AutoReporter<PositionReport> position_auto_reporter;
#endif
#if EITHER(FULL_REPORT_TO_HOST_FEATURE, REALTIME_REPORTING_COMMANDS)
#define HAS_GRBL_STATE 1
/**
* Machine states for GRBL or TinyG
*/
enum M_StateEnum : uint8_t {
M_INIT = 0, // 0 machine is initializing
M_RESET, // 1 machine is ready for use
M_ALARM, // 2 machine is in alarm state (soft shut down)
M_IDLE, // 3 program stop or no more blocks (M0, M1, M60)
M_END, // 4 program end via M2, M30
M_RUNNING, // 5 motion is running
M_HOLD, // 6 motion is holding
M_PROBE, // 7 probe cycle active
M_CYCLING, // 8 machine is running (cycling)
M_HOMING, // 9 machine is homing
M_JOGGING, // 10 machine is jogging
M_ERROR // 11 machine is in hard alarm state (shut down)
};
extern M_StateEnum M_State_grbl;
M_StateEnum grbl_state_for_marlin_state();
void report_current_grblstate_moving();
void report_current_position_moving();
#if ENABLED(FULL_REPORT_TO_HOST_FEATURE)
inline void set_and_report_grblstate(const M_StateEnum state) {
M_State_grbl = state;
report_current_grblstate_moving();
}
#endif
#if ENABLED(REALTIME_REPORTING_COMMANDS)
void quickpause_stepper();
void quickresume_stepper();
#endif
#endif
void get_cartesian_from_steppers();
void set_current_from_steppers_for_axis(const AxisEnum axis);
void quickstop_stepper();
/**
* Set the planner/stepper positions directly from current_position with
* no kinematic translation. Used for homing axes and cartesian/core syncing.
*/
void sync_plan_position();
void sync_plan_position_e();
/**
* Move the planner to the current position from wherever it last moved
* (or from wherever it has been told it is located).
*/
void line_to_current_position(const_feedRate_t fr_mm_s=feedrate_mm_s);
#if HAS_EXTRUDERS
void unscaled_e_move(const_float_t length, const_feedRate_t fr_mm_s);
#endif
void prepare_line_to_destination();
void _internal_move_to_destination(const_feedRate_t fr_mm_s=0.0f OPTARG(IS_KINEMATIC, const bool is_fast=false));
inline void prepare_internal_move_to_destination(const_feedRate_t fr_mm_s=0.0f) {
_internal_move_to_destination(fr_mm_s);
}
#if IS_KINEMATIC
void prepare_fast_move_to_destination(const_feedRate_t scaled_fr_mm_s=MMS_SCALED(feedrate_mm_s));
inline void prepare_internal_fast_move_to_destination(const_feedRate_t fr_mm_s=0.0f) {
_internal_move_to_destination(fr_mm_s, true);
}
#endif
/**
* Blocking movement and shorthand functions
*/
void do_blocking_move_to(const float rx, const float ry, const float rz, const_feedRate_t fr_mm_s=0.0f);
void do_blocking_move_to(const xy_pos_t &raw, const_feedRate_t fr_mm_s=0.0f);
void do_blocking_move_to(const xyz_pos_t &raw, const_feedRate_t fr_mm_s=0.0f);
void do_blocking_move_to(const xyze_pos_t &raw, const_feedRate_t fr_mm_s=0.0f);
void do_blocking_move_to_x(const_float_t rx, const_feedRate_t fr_mm_s=0.0f);
void do_blocking_move_to_y(const_float_t ry, const_feedRate_t fr_mm_s=0.0f);
void do_blocking_move_to_z(const_float_t rz, const_feedRate_t fr_mm_s=0.0f);
void do_blocking_move_to_xy(const_float_t rx, const_float_t ry, const_feedRate_t fr_mm_s=0.0f);
void do_blocking_move_to_xy(const xy_pos_t &raw, const_feedRate_t fr_mm_s=0.0f);
FORCE_INLINE void do_blocking_move_to_xy(const xyz_pos_t &raw, const_feedRate_t fr_mm_s=0.0f) { do_blocking_move_to_xy(xy_pos_t(raw), fr_mm_s); }
FORCE_INLINE void do_blocking_move_to_xy(const xyze_pos_t &raw, const_feedRate_t fr_mm_s=0.0f) { do_blocking_move_to_xy(xy_pos_t(raw), fr_mm_s); }
void do_blocking_move_to_xy_z(const xy_pos_t &raw, const_float_t z, const_feedRate_t fr_mm_s=0.0f);
FORCE_INLINE void do_blocking_move_to_xy_z(const xyz_pos_t &raw, const_float_t z, const_feedRate_t fr_mm_s=0.0f) { do_blocking_move_to_xy_z(xy_pos_t(raw), z, fr_mm_s); }
FORCE_INLINE void do_blocking_move_to_xy_z(const xyze_pos_t &raw, const_float_t z, const_feedRate_t fr_mm_s=0.0f) { do_blocking_move_to_xy_z(xy_pos_t(raw), z, fr_mm_s); }
void remember_feedrate_and_scaling();
void remember_feedrate_scaling_off();
void restore_feedrate_and_scaling();
void do_z_clearance(const_float_t zclear, const bool lower_allowed=false);
/**
* Homing and Trusted Axes
*/
typedef IF<(LINEAR_AXES>8), uint16_t, uint8_t>::type linear_axis_bits_t;
constexpr linear_axis_bits_t linear_bits = _BV(LINEAR_AXES) - 1;
void set_axis_is_at_home(const AxisEnum axis);
#if HAS_ENDSTOPS
/**
* axis_homed
* Flags that each linear axis was homed.
* XYZ on cartesian, ABC on delta, ABZ on SCARA.
*
* axis_trusted
* Flags that the position is trusted in each linear axis. Set when homed.
* Cleared whenever a stepper powers off, potentially losing its position.
*/
extern linear_axis_bits_t axis_homed, axis_trusted;
void homeaxis(const AxisEnum axis);
void set_axis_never_homed(const AxisEnum axis);
linear_axis_bits_t axes_should_home(linear_axis_bits_t axis_bits=linear_bits);
bool homing_needed_error(linear_axis_bits_t axis_bits=linear_bits);
FORCE_INLINE void set_axis_unhomed(const AxisEnum axis) { CBI(axis_homed, axis); }
FORCE_INLINE void set_axis_untrusted(const AxisEnum axis) { CBI(axis_trusted, axis); }
FORCE_INLINE void set_all_unhomed() { axis_homed = axis_trusted = 0; }
FORCE_INLINE void set_axis_homed(const AxisEnum axis) { SBI(axis_homed, axis); }
FORCE_INLINE void set_axis_trusted(const AxisEnum axis) { SBI(axis_trusted, axis); }
FORCE_INLINE void set_all_homed() { axis_homed = axis_trusted = linear_bits; }
#else
constexpr linear_axis_bits_t axis_homed = linear_bits, axis_trusted = linear_bits; // Zero-endstop machines are always homed and trusted
FORCE_INLINE void homeaxis(const AxisEnum axis) {}
FORCE_INLINE void set_axis_never_homed(const AxisEnum) {}
FORCE_INLINE linear_axis_bits_t axes_should_home(linear_axis_bits_t=linear_bits) { return false; }
FORCE_INLINE bool homing_needed_error(linear_axis_bits_t=linear_bits) { return false; }
FORCE_INLINE void set_axis_unhomed(const AxisEnum axis) {}
FORCE_INLINE void set_axis_untrusted(const AxisEnum axis) {}
FORCE_INLINE void set_all_unhomed() {}
FORCE_INLINE void set_axis_homed(const AxisEnum axis) {}
FORCE_INLINE void set_axis_trusted(const AxisEnum axis) {}
FORCE_INLINE void set_all_homed() {}
#endif
FORCE_INLINE bool axis_was_homed(const AxisEnum axis) { return TEST(axis_homed, axis); }
FORCE_INLINE bool axis_is_trusted(const AxisEnum axis) { return TEST(axis_trusted, axis); }
FORCE_INLINE bool axis_should_home(const AxisEnum axis) { return (axes_should_home() & _BV(axis)) != 0; }
FORCE_INLINE bool no_axes_homed() { return !axis_homed; }
FORCE_INLINE bool all_axes_homed() { return linear_bits == (axis_homed & linear_bits); }
FORCE_INLINE bool homing_needed() { return !all_axes_homed(); }
FORCE_INLINE bool all_axes_trusted() { return linear_bits == (axis_trusted & linear_bits); }
#if ENABLED(NO_MOTION_BEFORE_HOMING)
#define MOTION_CONDITIONS (IsRunning() && !homing_needed_error())
#else
#define MOTION_CONDITIONS IsRunning()
#endif
#define BABYSTEP_ALLOWED() ((ENABLED(BABYSTEP_WITHOUT_HOMING) || all_axes_trusted()) && (ENABLED(BABYSTEP_ALWAYS_AVAILABLE) || printer_busy()))
/**
* Workspace offsets
*/
#if HAS_HOME_OFFSET || HAS_POSITION_SHIFT
#if HAS_HOME_OFFSET
extern xyz_pos_t home_offset;
#endif
#if HAS_POSITION_SHIFT
extern xyz_pos_t position_shift;
#endif
#if HAS_HOME_OFFSET && HAS_POSITION_SHIFT
extern xyz_pos_t workspace_offset;
#define _WS workspace_offset
#elif HAS_HOME_OFFSET
#define _WS home_offset
#else
#define _WS position_shift
#endif
#define NATIVE_TO_LOGICAL(POS, AXIS) ((POS) + _WS[AXIS])
#define LOGICAL_TO_NATIVE(POS, AXIS) ((POS) - _WS[AXIS])
FORCE_INLINE void toLogical(xy_pos_t &raw) { raw += _WS; }
FORCE_INLINE void toLogical(xyz_pos_t &raw) { raw += _WS; }
FORCE_INLINE void toLogical(xyze_pos_t &raw) { raw += _WS; }
FORCE_INLINE void toNative(xy_pos_t &raw) { raw -= _WS; }
FORCE_INLINE void toNative(xyz_pos_t &raw) { raw -= _WS; }
FORCE_INLINE void toNative(xyze_pos_t &raw) { raw -= _WS; }
#else
#define NATIVE_TO_LOGICAL(POS, AXIS) (POS)
#define LOGICAL_TO_NATIVE(POS, AXIS) (POS)
FORCE_INLINE void toLogical(xy_pos_t&) {}
FORCE_INLINE void toLogical(xyz_pos_t&) {}
FORCE_INLINE void toLogical(xyze_pos_t&) {}
FORCE_INLINE void toNative(xy_pos_t&) {}
FORCE_INLINE void toNative(xyz_pos_t&) {}
FORCE_INLINE void toNative(xyze_pos_t&) {}
#endif
#define LOGICAL_X_POSITION(POS) NATIVE_TO_LOGICAL(POS, X_AXIS)
#define LOGICAL_Y_POSITION(POS) NATIVE_TO_LOGICAL(POS, Y_AXIS)
#define LOGICAL_Z_POSITION(POS) NATIVE_TO_LOGICAL(POS, Z_AXIS)
#define RAW_X_POSITION(POS) LOGICAL_TO_NATIVE(POS, X_AXIS)
#define RAW_Y_POSITION(POS) LOGICAL_TO_NATIVE(POS, Y_AXIS)
#define RAW_Z_POSITION(POS) LOGICAL_TO_NATIVE(POS, Z_AXIS)
/**
* position_is_reachable family of functions
*/
#if IS_KINEMATIC // (DELTA or SCARA)
#if HAS_SCARA_OFFSET
extern abc_pos_t scara_home_offset; // A and B angular offsets, Z mm offset
#endif
// Return true if the given point is within the printable area
inline bool position_is_reachable(const_float_t rx, const_float_t ry, const float inset=0) {
#if ENABLED(DELTA)
return HYPOT2(rx, ry) <= sq(DELTA_PRINTABLE_RADIUS - inset + fslop);
#elif ENABLED(AXEL_TPARA)
const float R2 = HYPOT2(rx - TPARA_OFFSET_X, ry - TPARA_OFFSET_Y);
return (
R2 <= sq(L1 + L2) - inset
#if MIDDLE_DEAD_ZONE_R > 0
&& R2 >= sq(float(MIDDLE_DEAD_ZONE_R))
#endif
);
#elif IS_SCARA
const float R2 = HYPOT2(rx - SCARA_OFFSET_X, ry - SCARA_OFFSET_Y);
return (
R2 <= sq(L1 + L2) - inset
#if MIDDLE_DEAD_ZONE_R > 0
&& R2 >= sq(float(MIDDLE_DEAD_ZONE_R))
#endif
);
#endif
}
inline bool position_is_reachable(const xy_pos_t &pos, const float inset=0) {
return position_is_reachable(pos.x, pos.y, inset);
}
#else // CARTESIAN
// Return true if the given position is within the machine bounds.
inline bool position_is_reachable(const_float_t rx, const_float_t ry) {
if (!COORDINATE_OKAY(ry, Y_MIN_POS - fslop, Y_MAX_POS + fslop)) return false;
#if ENABLED(DUAL_X_CARRIAGE)
if (active_extruder)
return COORDINATE_OKAY(rx, X2_MIN_POS - fslop, X2_MAX_POS + fslop);
else
return COORDINATE_OKAY(rx, X1_MIN_POS - fslop, X1_MAX_POS + fslop);
#else
return COORDINATE_OKAY(rx, X_MIN_POS - fslop, X_MAX_POS + fslop);
#endif
}
inline bool position_is_reachable(const xy_pos_t &pos) { return position_is_reachable(pos.x, pos.y); }
#endif // CARTESIAN
/**
* Duplication mode
*/
#if HAS_DUPLICATION_MODE
extern bool extruder_duplication_enabled; // Used in Dual X mode 2
#endif
/**
* Dual X Carriage
*/
#if ENABLED(DUAL_X_CARRIAGE)
enum DualXMode : char {
DXC_FULL_CONTROL_MODE,
DXC_AUTO_PARK_MODE,
DXC_DUPLICATION_MODE,
DXC_MIRRORED_MODE
};
extern DualXMode dual_x_carriage_mode;
extern float inactive_extruder_x, // Used in mode 0 & 1
duplicate_extruder_x_offset; // Used in mode 2 & 3
extern xyz_pos_t raised_parked_position; // Used in mode 1
extern bool active_extruder_parked; // Used in mode 1, 2 & 3
extern millis_t delayed_move_time; // Used in mode 1
extern celsius_t duplicate_extruder_temp_offset; // Used in mode 2 & 3
extern bool idex_mirrored_mode; // Used in mode 3
FORCE_INLINE bool idex_is_duplicating() { return dual_x_carriage_mode >= DXC_DUPLICATION_MODE; }
float x_home_pos(const uint8_t extruder);
#define TOOL_X_HOME_DIR(T) ((T) ? X2_HOME_DIR : X_HOME_DIR)
void set_duplication_enabled(const bool dupe, const int8_t tool_index=-1);
void idex_set_mirrored_mode(const bool mirr);
void idex_set_parked(const bool park=true);
#else
#if ENABLED(MULTI_NOZZLE_DUPLICATION)
extern uint8_t duplication_e_mask;
enum DualXMode : char { DXC_DUPLICATION_MODE = 2 };
FORCE_INLINE void set_duplication_enabled(const bool dupe) { extruder_duplication_enabled = dupe; }
#endif
#define TOOL_X_HOME_DIR(T) X_HOME_DIR
#endif
#if HAS_M206_COMMAND
void set_home_offset(const AxisEnum axis, const float v);
#endif
#if USE_SENSORLESS
struct sensorless_t;
sensorless_t start_sensorless_homing_per_axis(const AxisEnum axis);
void end_sensorless_homing_per_axis(const AxisEnum axis, sensorless_t enable_stealth);
#endif
File diff suppressed because it is too large Load Diff
File diff suppressed because it is too large Load Diff
+204
View File
@@ -0,0 +1,204 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
/**
* planner_bezier.cpp
*
* Compute and buffer movement commands for bezier curves
*/
#include "../inc/MarlinConfig.h"
#if ENABLED(BEZIER_CURVE_SUPPORT)
#include "planner.h"
#include "motion.h"
#include "temperature.h"
#include "../MarlinCore.h"
#include "../gcode/queue.h"
// See the meaning in the documentation of cubic_b_spline().
#define MIN_STEP 0.002f
#define MAX_STEP 0.1f
#define SIGMA 0.1f
// Compute the linear interpolation between two real numbers.
static inline float interp(const_float_t a, const_float_t b, const_float_t t) { return (1 - t) * a + t * b; }
/**
* Compute a Bézier curve using the De Casteljau's algorithm (see
* https://en.wikipedia.org/wiki/De_Casteljau%27s_algorithm), which is
* easy to code and has good numerical stability (very important,
* since Arudino works with limited precision real numbers).
*/
static inline float eval_bezier(const_float_t a, const_float_t b, const_float_t c, const_float_t d, const_float_t t) {
const float iab = interp(a, b, t),
ibc = interp(b, c, t),
icd = interp(c, d, t),
iabc = interp(iab, ibc, t),
ibcd = interp(ibc, icd, t);
return interp(iabc, ibcd, t);
}
/**
* We approximate Euclidean distance with the sum of the coordinates
* offset (so-called "norm 1"), which is quicker to compute.
*/
static inline float dist1(const_float_t x1, const_float_t y1, const_float_t x2, const_float_t y2) { return ABS(x1 - x2) + ABS(y1 - y2); }
/**
* The algorithm for computing the step is loosely based on the one in Kig
* (See https://sources.debian.net/src/kig/4:15.08.3-1/misc/kigpainter.cpp/#L759)
* However, we do not use the stack.
*
* The algorithm goes as it follows: the parameters t runs from 0.0 to
* 1.0 describing the curve, which is evaluated by eval_bezier(). At
* each iteration we have to choose a step, i.e., the increment of the
* t variable. By default the step of the previous iteration is taken,
* and then it is enlarged or reduced depending on how straight the
* curve locally is. The step is always clamped between MIN_STEP/2 and
* 2*MAX_STEP. MAX_STEP is taken at the first iteration.
*
* For some t, the step value is considered acceptable if the curve in
* the interval [t, t+step] is sufficiently straight, i.e.,
* sufficiently close to linear interpolation. In practice the
* following test is performed: the distance between eval_bezier(...,
* t+step/2) is evaluated and compared with 0.5*(eval_bezier(...,
* t)+eval_bezier(..., t+step)). If it is smaller than SIGMA, then the
* step value is considered acceptable, otherwise it is not. The code
* seeks to find the larger step value which is considered acceptable.
*
* At every iteration the recorded step value is considered and then
* iteratively halved until it becomes acceptable. If it was already
* acceptable in the beginning (i.e., no halving were done), then
* maybe it was necessary to enlarge it; then it is iteratively
* doubled while it remains acceptable. The last acceptable value
* found is taken, provided that it is between MIN_STEP and MAX_STEP
* and does not bring t over 1.0.
*
* Caveat: this algorithm is not perfect, since it can happen that a
* step is considered acceptable even when the curve is not linear at
* all in the interval [t, t+step] (but its mid point coincides "by
* chance" with the midpoint according to the parametrization). This
* kind of glitches can be eliminated with proper first derivative
* estimates; however, given the improbability of such configurations,
* the mitigation offered by MIN_STEP and the small computational
* power available on Arduino, I think it is not wise to implement it.
*/
void cubic_b_spline(
const xyze_pos_t &position, // current position
const xyze_pos_t &target, // target position
const xy_pos_t (&offsets)[2], // a pair of offsets
const_feedRate_t scaled_fr_mm_s, // mm/s scaled by feedrate %
const uint8_t extruder
) {
// Absolute first and second control points are recovered.
const xy_pos_t first = position + offsets[0], second = target + offsets[1];
xyze_pos_t bez_target;
bez_target.set(position.x, position.y);
float step = MAX_STEP;
millis_t next_idle_ms = millis() + 200UL;
for (float t = 0; t < 1;) {
thermalManager.manage_heater();
millis_t now = millis();
if (ELAPSED(now, next_idle_ms)) {
next_idle_ms = now + 200UL;
idle();
}
// First try to reduce the step in order to make it sufficiently
// close to a linear interpolation.
bool did_reduce = false;
float new_t = t + step;
NOMORE(new_t, 1);
float new_pos0 = eval_bezier(position.x, first.x, second.x, target.x, new_t),
new_pos1 = eval_bezier(position.y, first.y, second.y, target.y, new_t);
for (;;) {
if (new_t - t < (MIN_STEP)) break;
const float candidate_t = 0.5f * (t + new_t),
candidate_pos0 = eval_bezier(position.x, first.x, second.x, target.x, candidate_t),
candidate_pos1 = eval_bezier(position.y, first.y, second.y, target.y, candidate_t),
interp_pos0 = 0.5f * (bez_target.x + new_pos0),
interp_pos1 = 0.5f * (bez_target.y + new_pos1);
if (dist1(candidate_pos0, candidate_pos1, interp_pos0, interp_pos1) <= (SIGMA)) break;
new_t = candidate_t;
new_pos0 = candidate_pos0;
new_pos1 = candidate_pos1;
did_reduce = true;
}
// If we did not reduce the step, maybe we should enlarge it.
if (!did_reduce) for (;;) {
if (new_t - t > MAX_STEP) break;
const float candidate_t = t + 2 * (new_t - t);
if (candidate_t >= 1) break;
const float candidate_pos0 = eval_bezier(position.x, first.x, second.x, target.x, candidate_t),
candidate_pos1 = eval_bezier(position.y, first.y, second.y, target.y, candidate_t),
interp_pos0 = 0.5f * (bez_target.x + candidate_pos0),
interp_pos1 = 0.5f * (bez_target.y + candidate_pos1);
if (dist1(new_pos0, new_pos1, interp_pos0, interp_pos1) > (SIGMA)) break;
new_t = candidate_t;
new_pos0 = candidate_pos0;
new_pos1 = candidate_pos1;
}
// Check some postcondition; they are disabled in the actual
// Marlin build, but if you test the same code on a computer you
// may want to check they are respect.
/*
assert(new_t <= 1.0);
if (new_t < 1.0) {
assert(new_t - t >= (MIN_STEP) / 2.0);
assert(new_t - t <= (MAX_STEP) * 2.0);
}
*/
step = new_t - t;
t = new_t;
// Compute and send new position
xyze_pos_t new_bez = {
new_pos0, new_pos1,
interp(position.z, target.z, t), // FIXME. These two are wrong, since the parameter t is
interp(position.e, target.e, t) // not linear in the distance.
};
apply_motion_limits(new_bez);
bez_target = new_bez;
#if HAS_LEVELING && !PLANNER_LEVELING
xyze_pos_t pos = bez_target;
planner.apply_leveling(pos);
#else
const xyze_pos_t &pos = bez_target;
#endif
if (!planner.buffer_line(pos, scaled_fr_mm_s, active_extruder, step))
break;
}
}
#endif // BEZIER_CURVE_SUPPORT
+38
View File
@@ -0,0 +1,38 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* planner_bezier.h
*
* Compute and buffer movement commands for Bézier curves
*/
#include "../core/types.h"
void cubic_b_spline(
const xyze_pos_t &position, // current position
const xyze_pos_t &target, // target position
const xy_pos_t (&offsets)[2], // a pair of offsets
const_feedRate_t scaled_fr_mm_s, // mm/s scaled by feedrate %
const uint8_t extruder
);
+351
View File
@@ -0,0 +1,351 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#include "../inc/MarlinConfig.h"
#if DISABLED(PRINTCOUNTER)
#include "../libs/stopwatch.h"
Stopwatch print_job_timer; // Global Print Job Timer instance
#else // PRINTCOUNTER
#if ENABLED(EXTENSIBLE_UI)
#include "../lcd/extui/ui_api.h"
#endif
#include "printcounter.h"
#include "../MarlinCore.h"
#include "../HAL/shared/eeprom_api.h"
#if HAS_BUZZER && SERVICE_WARNING_BUZZES > 0
#include "../libs/buzzer.h"
#endif
#if PRINTCOUNTER_SYNC
#include "../module/planner.h"
#warning "To prevent step loss, motion will pause for PRINTCOUNTER auto-save."
#endif
// Service intervals
#if HAS_SERVICE_INTERVALS
#if SERVICE_INTERVAL_1 > 0
#define SERVICE_INTERVAL_SEC_1 (3600UL * SERVICE_INTERVAL_1)
#else
#define SERVICE_INTERVAL_SEC_1 (3600UL * 100)
#endif
#if SERVICE_INTERVAL_2 > 0
#define SERVICE_INTERVAL_SEC_2 (3600UL * SERVICE_INTERVAL_2)
#else
#define SERVICE_INTERVAL_SEC_2 (3600UL * 100)
#endif
#if SERVICE_INTERVAL_3 > 0
#define SERVICE_INTERVAL_SEC_3 (3600UL * SERVICE_INTERVAL_3)
#else
#define SERVICE_INTERVAL_SEC_3 (3600UL * 100)
#endif
#endif
PrintCounter print_job_timer; // Global Print Job Timer instance
printStatistics PrintCounter::data;
const PrintCounter::eeprom_address_t PrintCounter::address = STATS_EEPROM_ADDRESS;
millis_t PrintCounter::lastDuration;
bool PrintCounter::loaded = false;
millis_t PrintCounter::deltaDuration() {
TERN_(DEBUG_PRINTCOUNTER, debug(PSTR("deltaDuration")));
millis_t tmp = lastDuration;
lastDuration = duration();
return lastDuration - tmp;
}
void PrintCounter::incFilamentUsed(float const &amount) {
TERN_(DEBUG_PRINTCOUNTER, debug(PSTR("incFilamentUsed")));
// Refuses to update data if object is not loaded
if (!isLoaded()) return;
data.filamentUsed += amount; // mm
}
void PrintCounter::initStats() {
TERN_(DEBUG_PRINTCOUNTER, debug(PSTR("initStats")));
loaded = true;
data = { 0, 0, 0, 0, 0.0
#if HAS_SERVICE_INTERVALS
#if SERVICE_INTERVAL_1 > 0
, SERVICE_INTERVAL_SEC_1
#endif
#if SERVICE_INTERVAL_2 > 0
, SERVICE_INTERVAL_SEC_2
#endif
#if SERVICE_INTERVAL_3 > 0
, SERVICE_INTERVAL_SEC_3
#endif
#endif
};
saveStats();
persistentStore.access_start();
persistentStore.write_data(address, (uint8_t)0x16);
persistentStore.access_finish();
}
#if HAS_SERVICE_INTERVALS
inline void _print_divider() { SERIAL_ECHO_MSG("============================================="); }
inline bool _service_warn(const char * const msg) {
_print_divider();
SERIAL_ECHO_START();
SERIAL_ECHOPGM_P(msg);
SERIAL_ECHOLNPGM("!");
_print_divider();
return true;
}
#endif
void PrintCounter::loadStats() {
TERN_(DEBUG_PRINTCOUNTER, debug(PSTR("loadStats")));
// Check if the EEPROM block is initialized
uint8_t value = 0;
persistentStore.access_start();
persistentStore.read_data(address, &value, sizeof(uint8_t));
if (value != 0x16)
initStats();
else
persistentStore.read_data(address + sizeof(uint8_t), (uint8_t*)&data, sizeof(printStatistics));
persistentStore.access_finish();
loaded = true;
#if HAS_SERVICE_INTERVALS
bool doBuzz = false;
#if SERVICE_INTERVAL_1 > 0
if (data.nextService1 == 0) doBuzz = _service_warn(PSTR(" " SERVICE_NAME_1));
#endif
#if SERVICE_INTERVAL_2 > 0
if (data.nextService2 == 0) doBuzz = _service_warn(PSTR(" " SERVICE_NAME_2));
#endif
#if SERVICE_INTERVAL_3 > 0
if (data.nextService3 == 0) doBuzz = _service_warn(PSTR(" " SERVICE_NAME_3));
#endif
#if HAS_BUZZER && SERVICE_WARNING_BUZZES > 0
if (doBuzz) for (int i = 0; i < SERVICE_WARNING_BUZZES; i++) BUZZ(200, 404);
#else
UNUSED(doBuzz);
#endif
#endif // HAS_SERVICE_INTERVALS
}
void PrintCounter::saveStats() {
TERN_(DEBUG_PRINTCOUNTER, debug(PSTR("saveStats")));
// Refuses to save data if object is not loaded
if (!isLoaded()) return;
TERN_(PRINTCOUNTER_SYNC, planner.synchronize());
// Saves the struct to EEPROM
persistentStore.access_start();
persistentStore.write_data(address + sizeof(uint8_t), (uint8_t*)&data, sizeof(printStatistics));
persistentStore.access_finish();
TERN_(EXTENSIBLE_UI, ExtUI::onConfigurationStoreWritten(true));
}
#if HAS_SERVICE_INTERVALS
inline void _service_when(char buffer[], const char * const msg, const uint32_t when) {
SERIAL_ECHOPGM(STR_STATS);
SERIAL_ECHOPGM_P(msg);
SERIAL_ECHOLNPAIR(" in ", duration_t(when).toString(buffer));
}
#endif
void PrintCounter::showStats() {
char buffer[22];
SERIAL_ECHOPGM(STR_STATS);
SERIAL_ECHOLNPAIR(
"Prints: ", data.totalPrints,
", Finished: ", data.finishedPrints,
", Failed: ", data.totalPrints - data.finishedPrints
- ((isRunning() || isPaused()) ? 1 : 0) // Remove 1 from failures with an active counter
);
SERIAL_ECHOPGM(STR_STATS);
duration_t elapsed = data.printTime;
elapsed.toString(buffer);
SERIAL_ECHOPAIR("Total time: ", buffer);
#if ENABLED(DEBUG_PRINTCOUNTER)
SERIAL_ECHOPAIR(" (", data.printTime);
SERIAL_CHAR(')');
#endif
elapsed = data.longestPrint;
elapsed.toString(buffer);
SERIAL_ECHOPAIR(", Longest job: ", buffer);
#if ENABLED(DEBUG_PRINTCOUNTER)
SERIAL_ECHOPAIR(" (", data.longestPrint);
SERIAL_CHAR(')');
#endif
SERIAL_ECHOPAIR("\n" STR_STATS "Filament used: ", data.filamentUsed / 1000);
SERIAL_CHAR('m');
SERIAL_EOL();
#if SERVICE_INTERVAL_1 > 0
_service_when(buffer, PSTR(SERVICE_NAME_1), data.nextService1);
#endif
#if SERVICE_INTERVAL_2 > 0
_service_when(buffer, PSTR(SERVICE_NAME_2), data.nextService2);
#endif
#if SERVICE_INTERVAL_3 > 0
_service_when(buffer, PSTR(SERVICE_NAME_3), data.nextService3);
#endif
}
void PrintCounter::tick() {
if (!isRunning()) return;
millis_t now = millis();
static millis_t update_next; // = 0
if (ELAPSED(now, update_next)) {
update_next = now + updateInterval;
TERN_(DEBUG_PRINTCOUNTER, debug(PSTR("tick")));
millis_t delta = deltaDuration();
data.printTime += delta;
#if SERVICE_INTERVAL_1 > 0
data.nextService1 -= _MIN(delta, data.nextService1);
#endif
#if SERVICE_INTERVAL_2 > 0
data.nextService2 -= _MIN(delta, data.nextService2);
#endif
#if SERVICE_INTERVAL_3 > 0
data.nextService3 -= _MIN(delta, data.nextService3);
#endif
}
#if PRINTCOUNTER_SAVE_INTERVAL > 0
static millis_t eeprom_next; // = 0
if (ELAPSED(now, eeprom_next)) {
eeprom_next = now + saveInterval;
saveStats();
}
#endif
}
// @Override
bool PrintCounter::start() {
TERN_(DEBUG_PRINTCOUNTER, debug(PSTR("start")));
bool paused = isPaused();
if (super::start()) {
if (!paused) {
data.totalPrints++;
lastDuration = 0;
}
return true;
}
return false;
}
bool PrintCounter::_stop(const bool completed) {
TERN_(DEBUG_PRINTCOUNTER, debug(PSTR("stop")));
const bool did_stop = super::stop();
if (did_stop) {
data.printTime += deltaDuration();
if (completed) {
data.finishedPrints++;
if (duration() > data.longestPrint)
data.longestPrint = duration();
}
}
saveStats();
return did_stop;
}
// @Override
void PrintCounter::reset() {
TERN_(DEBUG_PRINTCOUNTER, debug(PSTR("stop")));
super::reset();
lastDuration = 0;
}
#if HAS_SERVICE_INTERVALS
void PrintCounter::resetServiceInterval(const int index) {
switch (index) {
#if SERVICE_INTERVAL_1 > 0
case 1: data.nextService1 = SERVICE_INTERVAL_SEC_1;
#endif
#if SERVICE_INTERVAL_2 > 0
case 2: data.nextService2 = SERVICE_INTERVAL_SEC_2;
#endif
#if SERVICE_INTERVAL_3 > 0
case 3: data.nextService3 = SERVICE_INTERVAL_SEC_3;
#endif
}
saveStats();
}
bool PrintCounter::needsService(const int index) {
if (!loaded) loadStats();
switch (index) {
#if SERVICE_INTERVAL_1 > 0
case 1: return data.nextService1 == 0;
#endif
#if SERVICE_INTERVAL_2 > 0
case 2: return data.nextService2 == 0;
#endif
#if SERVICE_INTERVAL_3 > 0
case 3: return data.nextService3 == 0;
#endif
default: return false;
}
}
#endif // HAS_SERVICE_INTERVALS
#if ENABLED(DEBUG_PRINTCOUNTER)
void PrintCounter::debug(const char func[]) {
if (DEBUGGING(INFO)) {
SERIAL_ECHOPGM("PrintCounter::");
SERIAL_ECHOPGM_P(func);
SERIAL_ECHOLNPGM("()");
}
}
#endif
#endif // PRINTCOUNTER
+205
View File
@@ -0,0 +1,205 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
#include "../libs/stopwatch.h"
#include "../libs/duration_t.h"
#include "../inc/MarlinConfig.h"
// Print debug messages with M111 S2
//#define DEBUG_PRINTCOUNTER
// Round up I2C / SPI address to next page boundary (assuming 32 byte pages)
#define STATS_EEPROM_ADDRESS TERN(USE_WIRED_EEPROM, 0x40, 0x32)
struct printStatistics { // 16 bytes
//const uint8_t magic; // Magic header, it will always be 0x16
uint16_t totalPrints; // Number of prints
uint16_t finishedPrints; // Number of complete prints
uint32_t printTime; // Accumulated printing time
uint32_t longestPrint; // Longest successful print job
float filamentUsed; // Accumulated filament consumed in mm
#if SERVICE_INTERVAL_1 > 0
uint32_t nextService1; // Service intervals (or placeholders)
#endif
#if SERVICE_INTERVAL_2 > 0
uint32_t nextService2;
#endif
#if SERVICE_INTERVAL_3 > 0
uint32_t nextService3;
#endif
};
class PrintCounter: public Stopwatch {
private:
typedef Stopwatch super;
#if EITHER(USE_WIRED_EEPROM, CPU_32_BIT)
typedef uint32_t eeprom_address_t;
#else
typedef uint16_t eeprom_address_t;
#endif
static printStatistics data;
/**
* @brief EEPROM address
* @details Defines the start offset address where the data is stored.
*/
static const eeprom_address_t address;
/**
* @brief Interval in seconds between counter updates
* @details This const value defines what will be the time between each
* accumulator update. This is different from the EEPROM save interval.
*/
static constexpr millis_t updateInterval = SEC_TO_MS(10);
#if PRINTCOUNTER_SAVE_INTERVAL > 0
/**
* @brief Interval in seconds between EEPROM saves
* @details This const value defines what will be the time between each
* EEPROM save cycle, the development team recommends to set this value
* no lower than 3600 secs (1 hour).
*/
static constexpr millis_t saveInterval = MIN_TO_MS(PRINTCOUNTER_SAVE_INTERVAL);
#endif
/**
* @brief Timestamp of the last call to deltaDuration()
* @details Store the timestamp of the last deltaDuration(), this is
* required due to the updateInterval cycle.
*/
static millis_t lastDuration;
/**
* @brief Stats were loaded from EEPROM
* @details If set to true it indicates if the statistical data was already
* loaded from the EEPROM.
*/
static bool loaded;
protected:
/**
* @brief dT since the last call
* @details Return the elapsed time in seconds since the last call, this is
* used internally for print statistics accounting is not intended to be a
* user callable function.
*/
static millis_t deltaDuration();
public:
/**
* @brief Initialize the print counter
*/
static inline void init() {
super::init();
loadStats();
}
/**
* @brief Check if Print Statistics has been loaded
* @details Return true if the statistical data has been loaded.
* @return bool
*/
FORCE_INLINE static bool isLoaded() { return loaded; }
/**
* @brief Increment the total filament used
* @details The total filament used counter will be incremented by "amount".
*
* @param amount The amount of filament used in mm
*/
static void incFilamentUsed(float const &amount);
/**
* @brief Reset the Print Statistics
* @details Reset the statistics to zero and saves them to EEPROM creating
* also the magic header.
*/
static void initStats();
/**
* @brief Load the Print Statistics
* @details Load the statistics from EEPROM
*/
static void loadStats();
/**
* @brief Save the Print Statistics
* @details Save the statistics to EEPROM
*/
static void saveStats();
/**
* @brief Serial output the Print Statistics
* @details This function may change in the future, for now it directly
* prints the statistical data to serial.
*/
static void showStats();
/**
* @brief Return the currently loaded statistics
* @details Return the raw data, in the same structure used internally
*/
static printStatistics getStats() { return data; }
/**
* @brief Loop function
* @details This function should be called at loop, it will take care of
* periodically save the statistical data to EEPROM and do time keeping.
*/
static void tick();
/**
* The following functions are being overridden
*/
static bool start();
static bool _stop(const bool completed);
static inline bool stop() { return _stop(true); }
static inline bool abort() { return _stop(false); }
static void reset();
#if HAS_SERVICE_INTERVALS
static void resetServiceInterval(const int index);
static bool needsService(const int index);
#endif
#if ENABLED(DEBUG_PRINTCOUNTER)
/**
* @brief Print a debug message
* @details Print a simple debug message
*/
static void debug(const char func[]);
#endif
};
// Global Print Job Timer instance
#if ENABLED(PRINTCOUNTER)
extern PrintCounter print_job_timer;
#else
extern Stopwatch print_job_timer;
#endif
File diff suppressed because it is too large Load Diff
+275
View File
@@ -0,0 +1,275 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* module/probe.h - Move, deploy, enable, etc.
*/
#include "../inc/MarlinConfig.h"
#include "motion.h"
#if ENABLED(USE_AUTOZ_TOOL)
#include "PressLeveled.h"
#endif
#if HAS_BED_PROBE
enum ProbePtRaise : uint8_t {
PROBE_PT_NONE, // No raise or stow after run_z_probe
PROBE_PT_STOW, // Do a complete stow after run_z_probe
PROBE_PT_RAISE, // Raise to "between" clearance after run_z_probe
PROBE_PT_BIG_RAISE // Raise to big clearance after run_z_probe
};
#endif
#if HAS_CUSTOM_PROBE_PIN
#define PROBE_TRIGGERED() (READ(Z_MIN_PROBE_PIN) != Z_MIN_PROBE_ENDSTOP_INVERTING)
#else
#define PROBE_TRIGGERED() (READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING)
#endif
#if ENABLED(PREHEAT_BEFORE_LEVELING)
#ifndef LEVELING_NOZZLE_TEMP
#define LEVELING_NOZZLE_TEMP 0
#endif
#ifndef LEVELING_BED_TEMP
#define LEVELING_BED_TEMP 0
#endif
#endif
class Probe {
public:
#if ENABLED(USE_AUTOZ_TOOL)
bool isNeedAutoOffset = false;
void probe_clean_hotend(void);
float probe_at_point_by_crtouch(float x, float y, float rdyZ, float minZ, int tSpdMM_MIN);
float probe_at_point_by_sensor(float x, float y, float rdyZ, float minZ, int tSpdMM_MIN);
void auto_get_offset();
#endif
#if HAS_BED_PROBE
static xyz_pos_t offset;
#if EITHER(PREHEAT_BEFORE_PROBING, PREHEAT_BEFORE_LEVELING)
static void preheat_for_probing(const celsius_t hotend_temp, const celsius_t bed_temp);
#endif
static bool set_deployed(const bool deploy);
#if IS_KINEMATIC
#if HAS_PROBE_XY_OFFSET
// Return true if the both nozzle and the probe can reach the given point.
// Note: This won't work on SCARA since the probe offset rotates with the arm.
static bool can_reach(const_float_t rx, const_float_t ry) {
return position_is_reachable(rx - offset_xy.x, ry - offset_xy.y) // The nozzle can go where it needs to go?
&& position_is_reachable(rx, ry, ABS(PROBING_MARGIN)); // Can the nozzle also go near there?
}
#else
static bool can_reach(const_float_t rx, const_float_t ry) {
return position_is_reachable(rx, ry, PROBING_MARGIN);
}
#endif
#else
/**
* Return whether the given position is within the bed, and whether the nozzle
* can reach the position required to put the probe at the given position.
*
* Example: For a probe offset of -10,+10, then for the probe to reach 0,0 the
* nozzle must be be able to reach +10,-10.
*/
static bool can_reach(const_float_t rx, const_float_t ry) {
return position_is_reachable(rx - offset_xy.x, ry - offset_xy.y)
&& COORDINATE_OKAY(rx, min_x() - fslop, max_x() + fslop)
&& COORDINATE_OKAY(ry, min_y() - fslop, max_y() + fslop);
}
#endif
static void move_z_after_probing() {
#ifdef Z_AFTER_PROBING
do_z_clearance(Z_AFTER_PROBING, true); // Move down still permitted
#endif
}
static float probe_at_point(const_float_t rx, const_float_t ry, const ProbePtRaise raise_after=PROBE_PT_NONE, const uint8_t verbose_level=0, const bool probe_relative=true, const bool sanity_check=true);
static float probe_at_point(const xy_pos_t &pos, const ProbePtRaise raise_after=PROBE_PT_NONE, const uint8_t verbose_level=0, const bool probe_relative=true, const bool sanity_check=true) {
return probe_at_point(pos.x, pos.y, raise_after, verbose_level, probe_relative, sanity_check);
}
#else
static constexpr xyz_pos_t offset = xyz_pos_t({ 0, 0, 0 }); // See #16767
static bool set_deployed(const bool) { return false; }
static bool can_reach(const_float_t rx, const_float_t ry) { return position_is_reachable(rx, ry); }
#endif
static void move_z_after_homing() {
#ifdef Z_AFTER_HOMING
do_z_clearance(Z_AFTER_HOMING, true);
#elif BOTH(Z_AFTER_PROBING, HAS_BED_PROBE)
move_z_after_probing();
#endif
}
static bool can_reach(const xy_pos_t &pos) { return can_reach(pos.x, pos.y); }
static bool good_bounds(const xy_pos_t &lf, const xy_pos_t &rb) {
return (
#if IS_KINEMATIC
can_reach(lf.x, 0) && can_reach(rb.x, 0) && can_reach(0, lf.y) && can_reach(0, rb.y)
#else
can_reach(lf) && can_reach(rb)
#endif
);
}
// Use offset_xy for read only access
// More optimal the XY offset is known to always be zero.
#if HAS_PROBE_XY_OFFSET
static const xy_pos_t &offset_xy;
#else
static constexpr xy_pos_t offset_xy = xy_pos_t({ 0, 0 }); // See #16767
#endif
static bool deploy() { return set_deployed(true); }
static bool stow() { return set_deployed(false); }
#if HAS_BED_PROBE || HAS_LEVELING
#if IS_KINEMATIC
static constexpr float printable_radius = (
TERN_(DELTA, DELTA_PRINTABLE_RADIUS)
TERN_(IS_SCARA, SCARA_PRINTABLE_RADIUS)
);
static constexpr float probe_radius(const xy_pos_t &probe_offset_xy = offset_xy) {
return printable_radius - _MAX(PROBING_MARGIN, HYPOT(probe_offset_xy.x, probe_offset_xy.y));
}
#endif
static constexpr float _min_x(const xy_pos_t &probe_offset_xy = offset_xy) {
return TERN(IS_KINEMATIC,
(X_CENTER) - probe_radius(probe_offset_xy),
_MAX((X_MIN_BED) + (PROBING_MARGIN_LEFT), (X_MIN_POS) + probe_offset_xy.x)
);
}
static constexpr float _max_x(const xy_pos_t &probe_offset_xy = offset_xy) {
return TERN(IS_KINEMATIC,
(X_CENTER) + probe_radius(probe_offset_xy),
_MIN((X_MAX_BED) - (PROBING_MARGIN_RIGHT), (X_MAX_POS) + probe_offset_xy.x)
);
}
static constexpr float _min_y(const xy_pos_t &probe_offset_xy = offset_xy) {
return TERN(IS_KINEMATIC,
(Y_CENTER) - probe_radius(probe_offset_xy),
_MAX((Y_MIN_BED) + (PROBING_MARGIN_FRONT), (Y_MIN_POS) + probe_offset_xy.y)
);
}
static constexpr float _max_y(const xy_pos_t &probe_offset_xy = offset_xy) {
return TERN(IS_KINEMATIC,
(Y_CENTER) + probe_radius(probe_offset_xy),
_MIN((Y_MAX_BED) - (PROBING_MARGIN_BACK), (Y_MAX_POS) + probe_offset_xy.y)
);
}
static float min_x() { return _min_x() TERN_(NOZZLE_AS_PROBE, TERN_(HAS_HOME_OFFSET, - home_offset.x)); }
static float max_x() { return _max_x() TERN_(NOZZLE_AS_PROBE, TERN_(HAS_HOME_OFFSET, - home_offset.x)); }
static float min_y() { return _min_y() TERN_(NOZZLE_AS_PROBE, TERN_(HAS_HOME_OFFSET, - home_offset.y)); }
static float max_y() { return _max_y() TERN_(NOZZLE_AS_PROBE, TERN_(HAS_HOME_OFFSET, - home_offset.y)); }
// constexpr helpers used in build-time static_asserts, relying on default probe offsets.
class build_time {
static constexpr xyz_pos_t default_probe_xyz_offset =
#if HAS_BED_PROBE
NOZZLE_TO_PROBE_OFFSET
#else
{ 0 }
#endif
;
static constexpr xy_pos_t default_probe_xy_offset = { default_probe_xyz_offset.x, default_probe_xyz_offset.y };
public:
static constexpr bool can_reach(float x, float y) {
#if IS_KINEMATIC
return HYPOT2(x, y) <= sq(probe_radius(default_probe_xy_offset));
#else
return COORDINATE_OKAY(x, _min_x(default_probe_xy_offset) - fslop, _max_x(default_probe_xy_offset) + fslop)
&& COORDINATE_OKAY(y, _min_y(default_probe_xy_offset) - fslop, _max_y(default_probe_xy_offset) + fslop);
#endif
}
static constexpr bool can_reach(const xy_pos_t &point) { return can_reach(point.x, point.y); }
};
#if NEEDS_THREE_PROBE_POINTS
// Retrieve three points to probe the bed. Any type exposing set(X,Y) may be used.
template <typename T>
static void get_three_points(T points[3]) {
#if HAS_FIXED_3POINT
#define VALIDATE_PROBE_PT(N) static_assert(Probe::build_time::can_reach(xy_pos_t{PROBE_PT_##N##_X, PROBE_PT_##N##_Y}), \
"PROBE_PT_" STRINGIFY(N) "_(X|Y) is unreachable using default NOZZLE_TO_PROBE_OFFSET and PROBING_MARGIN");
VALIDATE_PROBE_PT(1); VALIDATE_PROBE_PT(2); VALIDATE_PROBE_PT(3);
points[0].set(PROBE_PT_1_X, PROBE_PT_1_Y);
points[1].set(PROBE_PT_2_X, PROBE_PT_2_Y);
points[2].set(PROBE_PT_3_X, PROBE_PT_3_Y);
#else
#if IS_KINEMATIC
constexpr float SIN0 = 0.0, SIN120 = 0.866025, SIN240 = -0.866025,
COS0 = 1.0, COS120 = -0.5 , COS240 = -0.5;
points[0].set((X_CENTER) + probe_radius() * COS0, (Y_CENTER) + probe_radius() * SIN0);
points[1].set((X_CENTER) + probe_radius() * COS120, (Y_CENTER) + probe_radius() * SIN120);
points[2].set((X_CENTER) + probe_radius() * COS240, (Y_CENTER) + probe_radius() * SIN240);
#else
points[0].set(min_x(), min_y());
points[1].set(max_x(), min_y());
points[2].set((min_x() + max_x()) / 2, max_y());
#endif
#endif
}
#endif
#endif // HAS_BED_PROBE
#if HAS_Z_SERVO_PROBE
static void servo_probe_init();
#endif
#if HAS_QUIET_PROBING
static void set_probing_paused(const bool p);
#endif
#if ENABLED(PROBE_TARE)
static void tare_init();
static bool tare();
#endif
private:
static bool probe_down_to_z(const_float_t z, const_feedRate_t fr_mm_s);
static void do_z_raise(const float z_raise);
static float run_z_probe(const bool sanity_check=true);
};
extern Probe probe;
+309
View File
@@ -0,0 +1,309 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
/**
* scara.cpp
*/
#include "../inc/MarlinConfig.h"
#if IS_SCARA
#include "scara.h"
#include "motion.h"
#include "planner.h"
#if ENABLED(AXEL_TPARA)
#include "endstops.h"
#include "../MarlinCore.h"
#endif
float segments_per_second = TERN(AXEL_TPARA, TPARA_SEGMENTS_PER_SECOND, SCARA_SEGMENTS_PER_SECOND);
#if EITHER(MORGAN_SCARA, MP_SCARA)
static constexpr xy_pos_t scara_offset = { SCARA_OFFSET_X, SCARA_OFFSET_Y };
/**
* Morgan SCARA Forward Kinematics. Results in 'cartes'.
* Maths and first version by QHARLEY.
* Integrated into Marlin and slightly restructured by Joachim Cerny.
*/
void forward_kinematics(const_float_t a, const_float_t b) {
const float a_sin = sin(RADIANS(a)) * L1,
a_cos = cos(RADIANS(a)) * L1,
b_sin = sin(RADIANS(SUM_TERN(MP_SCARA, b, a))) * L2,
b_cos = cos(RADIANS(SUM_TERN(MP_SCARA, b, a))) * L2;
cartes.x = a_cos + b_cos + scara_offset.x; // theta
cartes.y = a_sin + b_sin + scara_offset.y; // phi
/*
DEBUG_ECHOLNPAIR(
"SCARA FK Angle a=", a,
" b=", b,
" a_sin=", a_sin,
" a_cos=", a_cos,
" b_sin=", b_sin,
" b_cos=", b_cos
);
DEBUG_ECHOLNPAIR(" cartes (X,Y) = "(cartes.x, ", ", cartes.y, ")");
//*/
}
#endif
#if ENABLED(MORGAN_SCARA)
void scara_set_axis_is_at_home(const AxisEnum axis) {
if (axis == Z_AXIS)
current_position.z = Z_HOME_POS;
else {
// MORGAN_SCARA uses a Cartesian XY home position
xyz_pos_t homeposition = { X_HOME_POS, Y_HOME_POS, Z_HOME_POS };
//DEBUG_ECHOLNPAIR_P(PSTR("homeposition X"), homeposition.x, SP_Y_LBL, homeposition.y);
delta = homeposition;
forward_kinematics(delta.a, delta.b);
current_position[axis] = cartes[axis];
//DEBUG_ECHOLNPAIR_P(PSTR("Cartesian X"), current_position.x, SP_Y_LBL, current_position.y);
update_software_endstops(axis);
}
}
/**
* Morgan SCARA Inverse Kinematics. Results are stored in 'delta'.
*
* See https://reprap.org/forum/read.php?185,283327
*
* Maths and first version by QHARLEY.
* Integrated into Marlin and slightly restructured by Joachim Cerny.
*/
void inverse_kinematics(const xyz_pos_t &raw) {
float C2, S2, SK1, SK2, THETA, PSI;
// Translate SCARA to standard XY with scaling factor
const xy_pos_t spos = raw - scara_offset;
const float H2 = HYPOT2(spos.x, spos.y);
if (L1 == L2)
C2 = H2 / L1_2_2 - 1;
else
C2 = (H2 - (L1_2 + L2_2)) / (2.0f * L1 * L2);
LIMIT(C2, -1, 1);
S2 = SQRT(1.0f - sq(C2));
// Unrotated Arm1 plus rotated Arm2 gives the distance from Center to End
SK1 = L1 + L2 * C2;
// Rotated Arm2 gives the distance from Arm1 to Arm2
SK2 = L2 * S2;
// Angle of Arm1 is the difference between Center-to-End angle and the Center-to-Elbow
THETA = ATAN2(SK1, SK2) - ATAN2(spos.x, spos.y);
// Angle of Arm2
PSI = ATAN2(S2, C2);
delta.set(DEGREES(THETA), DEGREES(SUM_TERN(MORGAN_SCARA, PSI, THETA)), raw.z);
/*
DEBUG_POS("SCARA IK", raw);
DEBUG_POS("SCARA IK", delta);
DEBUG_ECHOLNPAIR(" SCARA (x,y) ", sx, ",", sy, " C2=", C2, " S2=", S2, " Theta=", THETA, " Psi=", PSI);
//*/
}
#elif ENABLED(MP_SCARA)
void scara_set_axis_is_at_home(const AxisEnum axis) {
if (axis == Z_AXIS)
current_position.z = Z_HOME_POS;
else {
// MP_SCARA uses arm angles for AB home position
#ifndef SCARA_OFFSET_THETA1
#define SCARA_OFFSET_THETA1 12 // degrees
#endif
#ifndef SCARA_OFFSET_THETA2
#define SCARA_OFFSET_THETA2 131 // degrees
#endif
ab_float_t homeposition = { SCARA_OFFSET_THETA1, SCARA_OFFSET_THETA2 };
//DEBUG_ECHOLNPAIR("homeposition A:", homeposition.a, " B:", homeposition.b);
inverse_kinematics(homeposition);
forward_kinematics(delta.a, delta.b);
current_position[axis] = cartes[axis];
//DEBUG_ECHOLNPAIR_P(PSTR("Cartesian X"), current_position.x, SP_Y_LBL, current_position.y);
update_software_endstops(axis);
}
}
void inverse_kinematics(const xyz_pos_t &raw) {
const float x = raw.x, y = raw.y, c = HYPOT(x, y),
THETA3 = ATAN2(y, x),
THETA1 = THETA3 + ACOS((sq(c) + sq(L1) - sq(L2)) / (2.0f * c * L1)),
THETA2 = THETA3 - ACOS((sq(c) + sq(L2) - sq(L1)) / (2.0f * c * L2));
delta.set(DEGREES(THETA1), DEGREES(THETA2), raw.z);
/*
DEBUG_POS("SCARA IK", raw);
DEBUG_POS("SCARA IK", delta);
SERIAL_ECHOLNPAIR(" SCARA (x,y) ", x, ",", y," Theta1=", THETA1, " Theta2=", THETA2);
//*/
}
#elif ENABLED(AXEL_TPARA)
static constexpr xyz_pos_t robot_offset = { TPARA_OFFSET_X, TPARA_OFFSET_Y, TPARA_OFFSET_Z };
void scara_set_axis_is_at_home(const AxisEnum axis) {
if (axis == Z_AXIS)
current_position.z = Z_HOME_POS;
else {
xyz_pos_t homeposition = { X_HOME_POS, Y_HOME_POS, Z_HOME_POS };
//DEBUG_ECHOLNPAIR_P(PSTR("homeposition X"), homeposition.x, SP_Y_LBL, homeposition.y, SP_Z_LBL, homeposition.z);
inverse_kinematics(homeposition);
forward_kinematics(delta.a, delta.b, delta.c);
current_position[axis] = cartes[axis];
//DEBUG_ECHOLNPAIR_P(PSTR("Cartesian X"), current_position.x, SP_Y_LBL, current_position.y);
update_software_endstops(axis);
}
}
// Convert ABC inputs in degrees to XYZ outputs in mm
void forward_kinematics(const_float_t a, const_float_t b, const_float_t c) {
const float w = c - b,
r = L1 * cos(RADIANS(b)) + L2 * sin(RADIANS(w - (90 - b))),
x = r * cos(RADIANS(a)),
y = r * sin(RADIANS(a)),
rho2 = L1_2 + L2_2 - 2.0f * L1 * L2 * cos(RADIANS(w));
cartes = robot_offset + xyz_pos_t({ x, y, SQRT(rho2 - sq(x) - sq(y)) });
}
// Home YZ together, then X (or all at once). Based on quick_home_xy & home_delta
void home_TPARA() {
// Init the current position of all carriages to 0,0,0
current_position.reset();
destination.reset();
sync_plan_position();
// Disable stealthChop if used. Enable diag1 pin on driver.
#if ENABLED(SENSORLESS_HOMING)
TERN_(X_SENSORLESS, sensorless_t stealth_states_x = start_sensorless_homing_per_axis(X_AXIS));
TERN_(Y_SENSORLESS, sensorless_t stealth_states_y = start_sensorless_homing_per_axis(Y_AXIS));
TERN_(Z_SENSORLESS, sensorless_t stealth_states_z = start_sensorless_homing_per_axis(Z_AXIS));
#endif
//const int x_axis_home_dir = TOOL_X_HOME_DIR(active_extruder);
//const xy_pos_t pos { max_length(X_AXIS) , max_length(Y_AXIS) };
//const float mlz = max_length(X_AXIS),
// Move all carriages together linearly until an endstop is hit.
//do_blocking_move_to_xy_z(pos, mlz, homing_feedrate(Z_AXIS));
current_position.x = 0 ;
current_position.y = 0 ;
current_position.z = max_length(Z_AXIS) ;
line_to_current_position(homing_feedrate(Z_AXIS));
planner.synchronize();
// Re-enable stealthChop if used. Disable diag1 pin on driver.
#if ENABLED(SENSORLESS_HOMING)
TERN_(X_SENSORLESS, end_sensorless_homing_per_axis(X_AXIS, stealth_states_x));
TERN_(Y_SENSORLESS, end_sensorless_homing_per_axis(Y_AXIS, stealth_states_y));
TERN_(Z_SENSORLESS, end_sensorless_homing_per_axis(Z_AXIS, stealth_states_z));
#endif
endstops.validate_homing_move();
// At least one motor has reached its endstop.
// Now re-home each motor separately.
homeaxis(A_AXIS);
homeaxis(C_AXIS);
homeaxis(B_AXIS);
// Set all carriages to their home positions
// Do this here all at once for Delta, because
// XYZ isn't ABC. Applying this per-tower would
// give the impression that they are the same.
LOOP_LINEAR_AXES(i) set_axis_is_at_home((AxisEnum)i);
sync_plan_position();
}
void inverse_kinematics(const xyz_pos_t &raw) {
const xyz_pos_t spos = raw - robot_offset;
const float RXY = SQRT(HYPOT2(spos.x, spos.y)),
RHO2 = NORMSQ(spos.x, spos.y, spos.z),
//RHO = SQRT(RHO2),
LSS = L1_2 + L2_2,
LM = 2.0f * L1 * L2,
CG = (LSS - RHO2) / LM,
SG = SQRT(1 - POW(CG, 2)), // Method 2
K1 = L1 - L2 * CG,
K2 = L2 * SG,
// Angle of Body Joint
THETA = ATAN2(spos.y, spos.x),
// Angle of Elbow Joint
//GAMMA = ACOS(CG),
GAMMA = ATAN2(SG, CG), // Method 2
// Angle of Shoulder Joint, elevation angle measured from horizontal (r+)
//PHI = asin(spos.z/RHO) + asin(L2 * sin(GAMMA) / RHO),
PHI = ATAN2(spos.z, RXY) + ATAN2(K2, K1), // Method 2
// Elbow motor angle measured from horizontal, same frame as shoulder (r+)
PSI = PHI + GAMMA;
delta.set(DEGREES(THETA), DEGREES(PHI), DEGREES(PSI));
//SERIAL_ECHOLNPAIR(" SCARA (x,y,z) ", spos.x , ",", spos.y, ",", spos.z, " Rho=", RHO, " Rho2=", RHO2, " Theta=", THETA, " Phi=", PHI, " Psi=", PSI, " Gamma=", GAMMA);
}
#endif
void scara_report_positions() {
SERIAL_ECHOLNPAIR("SCARA Theta:", planner.get_axis_position_degrees(A_AXIS)
#if ENABLED(AXEL_TPARA)
, " Phi:", planner.get_axis_position_degrees(B_AXIS)
, " Psi:", planner.get_axis_position_degrees(C_AXIS)
#else
, " Psi" TERN_(MORGAN_SCARA, "+Theta") ":", planner.get_axis_position_degrees(B_AXIS)
#endif
);
SERIAL_EOL();
}
#endif // IS_SCARA
+53
View File
@@ -0,0 +1,53 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* scara.h - SCARA-specific functions
*/
#include "../core/macros.h"
extern float segments_per_second;
#if ENABLED(AXEL_TPARA)
float constexpr L1 = TPARA_LINKAGE_1, L2 = TPARA_LINKAGE_2, // Float constants for Robot arm calculations
L1_2 = sq(float(L1)), L1_2_2 = 2.0 * L1_2,
L2_2 = sq(float(L2));
void forward_kinematics(const_float_t a, const_float_t b, const_float_t c);
void home_TPARA();
#else
float constexpr L1 = SCARA_LINKAGE_1, L2 = SCARA_LINKAGE_2, // Float constants for SCARA calculations
L1_2 = sq(float(L1)), L1_2_2 = 2.0 * L1_2,
L2_2 = sq(float(L2));
void forward_kinematics(const_float_t a, const_float_t b);
#endif
void inverse_kinematics(const xyz_pos_t &raw);
void scara_set_axis_is_at_home(const AxisEnum axis);
void scara_report_positions();
+58
View File
@@ -0,0 +1,58 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
/**
* module/servo.cpp
*/
#include "../inc/MarlinConfig.h"
#if HAS_SERVOS
#include "servo.h"
HAL_SERVO_LIB servo[NUM_SERVOS];
#if ENABLED(EDITABLE_SERVO_ANGLES)
uint16_t servo_angles[NUM_SERVOS][2];
#endif
void servo_init() {
#if NUM_SERVOS >= 1 && HAS_SERVO_0
servo[0].attach(SERVO0_PIN);
servo[0].detach(); // Just set up the pin. We don't have a position yet. Don't move to a random position.
#endif
#if NUM_SERVOS >= 2 && HAS_SERVO_1
servo[1].attach(SERVO1_PIN);
servo[1].detach();
#endif
#if NUM_SERVOS >= 3 && HAS_SERVO_2
servo[2].attach(SERVO2_PIN);
servo[2].detach();
#endif
#if NUM_SERVOS >= 4 && HAS_SERVO_3
servo[3].attach(SERVO3_PIN);
servo[3].detach();
#endif
}
#endif // HAS_SERVOS
+115
View File
@@ -0,0 +1,115 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* module/servo.h
*/
#include "../inc/MarlinConfig.h"
#include "../HAL/shared/servo.h"
#if HAS_SERVO_ANGLES
#if ENABLED(SWITCHING_EXTRUDER)
// Switching extruder can have 2 or 4 angles
#if EXTRUDERS > 3
#define REQ_ANGLES 4
#else
#define REQ_ANGLES 2
#endif
constexpr uint16_t sase[] = SWITCHING_EXTRUDER_SERVO_ANGLES;
static_assert(COUNT(sase) == REQ_ANGLES, "SWITCHING_EXTRUDER_SERVO_ANGLES needs " STRINGIFY(REQ_ANGLES) " angles.");
#else
constexpr uint16_t sase[4] = { 0 };
#endif
#if ENABLED(SWITCHING_NOZZLE)
constexpr uint16_t sasn[] = SWITCHING_NOZZLE_SERVO_ANGLES;
static_assert(COUNT(sasn) == 2, "SWITCHING_NOZZLE_SERVO_ANGLES needs 2 angles.");
#else
constexpr uint16_t sasn[2] = { 0 };
#endif
#ifdef Z_PROBE_SERVO_NR
#if ENABLED(BLTOUCH)
#include "../feature/bltouch.h"
#undef Z_SERVO_ANGLES
#define Z_SERVO_ANGLES { BLTOUCH_DEPLOY, BLTOUCH_STOW }
#endif
constexpr uint16_t sazp[] = Z_SERVO_ANGLES;
static_assert(COUNT(sazp) == 2, "Z_SERVO_ANGLES needs 2 angles.");
#else
constexpr uint16_t sazp[2] = { 0 };
#endif
#ifndef SWITCHING_EXTRUDER_SERVO_NR
#define SWITCHING_EXTRUDER_SERVO_NR -1
#endif
#ifndef SWITCHING_EXTRUDER_E23_SERVO_NR
#define SWITCHING_EXTRUDER_E23_SERVO_NR -1
#endif
#ifndef SWITCHING_NOZZLE_SERVO_NR
#define SWITCHING_NOZZLE_SERVO_NR -1
#endif
#ifndef Z_PROBE_SERVO_NR
#define Z_PROBE_SERVO_NR -1
#endif
#define ASRC(N,I) ( \
N == SWITCHING_EXTRUDER_SERVO_NR ? sase[I] \
: N == SWITCHING_EXTRUDER_E23_SERVO_NR ? sase[I+2] \
: N == SWITCHING_NOZZLE_SERVO_NR ? sasn[I] \
: N == Z_PROBE_SERVO_NR ? sazp[I] \
: 0 )
#if ENABLED(EDITABLE_SERVO_ANGLES)
extern uint16_t servo_angles[NUM_SERVOS][2];
#define CONST_SERVO_ANGLES base_servo_angles
#else
#define CONST_SERVO_ANGLES servo_angles
#endif
constexpr uint16_t CONST_SERVO_ANGLES [NUM_SERVOS][2] = {
{ ASRC(0,0), ASRC(0,1) }
#if NUM_SERVOS > 1
, { ASRC(1,0), ASRC(1,1) }
#if NUM_SERVOS > 2
, { ASRC(2,0), ASRC(2,1) }
#if NUM_SERVOS > 3
, { ASRC(3,0), ASRC(3,1) }
#endif
#endif
#endif
};
#if HAS_Z_SERVO_PROBE
#define DEPLOY_Z_SERVO() MOVE_SERVO(Z_PROBE_SERVO_NR, servo_angles[Z_PROBE_SERVO_NR][0])
#define STOW_Z_SERVO() MOVE_SERVO(Z_PROBE_SERVO_NR, servo_angles[Z_PROBE_SERVO_NR][1])
#endif
#endif // HAS_SERVO_ANGLES
#define MOVE_SERVO(I, P) servo[I].move(P)
extern HAL_SERVO_LIB servo[NUM_SERVOS];
void servo_init();
File diff suppressed because it is too large Load Diff
+149
View File
@@ -0,0 +1,149 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
//
// settings.cpp - Settings and EEPROM storage
//
#include "../inc/MarlinConfig.h"
#if ENABLED(EEPROM_SETTINGS)
#include "../HAL/shared/eeprom_api.h"
#endif
class MarlinSettings {
public:
static uint16_t datasize();
static void reset();
static bool save(); // Return 'true' if data was saved
FORCE_INLINE static bool init_eeprom() {
reset();
#if ENABLED(EEPROM_SETTINGS)
const bool success = save();
if (TERN0(EEPROM_CHITCHAT, success)) report();
return success;
#else
return true;
#endif
}
#if ENABLED(SD_FIRMWARE_UPDATE)
static bool sd_update_status(); // True if the SD-Firmware-Update EEPROM flag is set
static bool set_sd_update_status(const bool enable); // Return 'true' after EEPROM is set (-> always true)
#endif
#if ENABLED(EEPROM_SETTINGS)
static bool load(); // Return 'true' if data was loaded ok
static bool validate(); // Return 'true' if EEPROM data is ok
static inline void first_load() {
static bool loaded = false;
if (!loaded && load()) loaded = true;
}
#if ENABLED(AUTO_BED_LEVELING_UBL) // Eventually make these available if any leveling system
// That can store is enabled
static uint16_t meshes_start_index();
FORCE_INLINE static uint16_t meshes_end_index() { return meshes_end; }
static uint16_t calc_num_meshes();
static int mesh_slot_offset(const int8_t slot);
static void store_mesh(const int8_t slot);
static void load_mesh(const int8_t slot, void * const into=nullptr);
//static void delete_mesh(); // necessary if we have a MAT
//static void defrag_meshes(); // "
#endif
#else // !EEPROM_SETTINGS
FORCE_INLINE
static bool load() { reset(); report(); return true; }
FORCE_INLINE
static void first_load() { (void)load(); }
#endif // !EEPROM_SETTINGS
#if DISABLED(DISABLE_M503)
static void report(const bool forReplay=false);
#else
FORCE_INLINE
static void report(const bool=false) {}
#endif
private:
static void postprocess();
#if ENABLED(EEPROM_SETTINGS)
static bool eeprom_error, validating;
#if ENABLED(AUTO_BED_LEVELING_UBL) // Eventually make these available if any leveling system
// That can store is enabled
static const uint16_t meshes_end; // 128 is a placeholder for the size of the MAT; the MAT will always
// live at the very end of the eeprom
#endif
static bool _load();
static bool size_error(const uint16_t size);
static int eeprom_index;
static uint16_t working_crc;
static bool EEPROM_START(int eeprom_offset) {
if (!persistentStore.access_start()) { SERIAL_ECHO_MSG("No EEPROM."); return false; }
eeprom_index = eeprom_offset;
working_crc = 0;
return true;
}
static void EEPROM_FINISH(void) { persistentStore.access_finish(); }
template<typename T>
static void EEPROM_SKIP(const T &VAR) { eeprom_index += sizeof(VAR); }
template<typename T>
static void EEPROM_WRITE(const T &VAR) {
persistentStore.write_data(eeprom_index, (const uint8_t *) &VAR, sizeof(VAR), &working_crc);
}
template<typename T>
static void EEPROM_READ(T &VAR) {
persistentStore.read_data(eeprom_index, (uint8_t *) &VAR, sizeof(VAR), &working_crc, !validating);
}
static void EEPROM_READ(uint8_t *VAR, size_t sizeof_VAR) {
persistentStore.read_data(eeprom_index, VAR, sizeof_VAR, &working_crc, !validating);
}
template<typename T>
static void EEPROM_READ_ALWAYS(T &VAR) {
persistentStore.read_data(eeprom_index, (uint8_t *) &VAR, sizeof(VAR), &working_crc);
}
#endif // EEPROM_SETTINGS
};
extern MarlinSettings settings;
+168
View File
@@ -0,0 +1,168 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
#if F_CPU == 16000000
const uint16_t speed_lookuptable_fast[256][2] PROGMEM = {
{ 62500, 55556}, { 6944, 3268}, { 3676, 1176}, { 2500, 607}, { 1893, 369}, { 1524, 249}, { 1275, 179}, { 1096, 135},
{ 961, 105}, { 856, 85}, { 771, 69}, { 702, 58}, { 644, 49}, { 595, 42}, { 553, 37}, { 516, 32},
{ 484, 28}, { 456, 25}, { 431, 23}, { 408, 20}, { 388, 19}, { 369, 16}, { 353, 16}, { 337, 14},
{ 323, 13}, { 310, 11}, { 299, 11}, { 288, 11}, { 277, 9}, { 268, 9}, { 259, 8}, { 251, 8},
{ 243, 8}, { 235, 7}, { 228, 6}, { 222, 6}, { 216, 6}, { 210, 6}, { 204, 5}, { 199, 5},
{ 194, 5}, { 189, 4}, { 185, 4}, { 181, 4}, { 177, 4}, { 173, 4}, { 169, 4}, { 165, 3},
{ 162, 3}, { 159, 4}, { 155, 3}, { 152, 3}, { 149, 2}, { 147, 3}, { 144, 3}, { 141, 2},
{ 139, 3}, { 136, 2}, { 134, 2}, { 132, 3}, { 129, 2}, { 127, 2}, { 125, 2}, { 123, 2},
{ 121, 2}, { 119, 1}, { 118, 2}, { 116, 2}, { 114, 1}, { 113, 2}, { 111, 2}, { 109, 1},
{ 108, 2}, { 106, 1}, { 105, 2}, { 103, 1}, { 102, 1}, { 101, 1}, { 100, 2}, { 98, 1},
{ 97, 1}, { 96, 1}, { 95, 2}, { 93, 1}, { 92, 1}, { 91, 1}, { 90, 1}, { 89, 1},
{ 88, 1}, { 87, 1}, { 86, 1}, { 85, 1}, { 84, 1}, { 83, 0}, { 83, 1}, { 82, 1},
{ 81, 1}, { 80, 1}, { 79, 1}, { 78, 0}, { 78, 1}, { 77, 1}, { 76, 1}, { 75, 0},
{ 75, 1}, { 74, 1}, { 73, 1}, { 72, 0}, { 72, 1}, { 71, 1}, { 70, 0}, { 70, 1},
{ 69, 0}, { 69, 1}, { 68, 1}, { 67, 0}, { 67, 1}, { 66, 0}, { 66, 1}, { 65, 0},
{ 65, 1}, { 64, 1}, { 63, 0}, { 63, 1}, { 62, 0}, { 62, 1}, { 61, 0}, { 61, 1},
{ 60, 0}, { 60, 0}, { 60, 1}, { 59, 0}, { 59, 1}, { 58, 0}, { 58, 1}, { 57, 0},
{ 57, 1}, { 56, 0}, { 56, 0}, { 56, 1}, { 55, 0}, { 55, 1}, { 54, 0}, { 54, 0},
{ 54, 1}, { 53, 0}, { 53, 0}, { 53, 1}, { 52, 0}, { 52, 0}, { 52, 1}, { 51, 0},
{ 51, 0}, { 51, 1}, { 50, 0}, { 50, 0}, { 50, 1}, { 49, 0}, { 49, 0}, { 49, 1},
{ 48, 0}, { 48, 0}, { 48, 1}, { 47, 0}, { 47, 0}, { 47, 0}, { 47, 1}, { 46, 0},
{ 46, 0}, { 46, 1}, { 45, 0}, { 45, 0}, { 45, 0}, { 45, 1}, { 44, 0}, { 44, 0},
{ 44, 0}, { 44, 1}, { 43, 0}, { 43, 0}, { 43, 0}, { 43, 1}, { 42, 0}, { 42, 0},
{ 42, 0}, { 42, 1}, { 41, 0}, { 41, 0}, { 41, 0}, { 41, 0}, { 41, 1}, { 40, 0},
{ 40, 0}, { 40, 0}, { 40, 0}, { 40, 1}, { 39, 0}, { 39, 0}, { 39, 0}, { 39, 0},
{ 39, 1}, { 38, 0}, { 38, 0}, { 38, 0}, { 38, 0}, { 38, 1}, { 37, 0}, { 37, 0},
{ 37, 0}, { 37, 0}, { 37, 0}, { 37, 1}, { 36, 0}, { 36, 0}, { 36, 0}, { 36, 0},
{ 36, 1}, { 35, 0}, { 35, 0}, { 35, 0}, { 35, 0}, { 35, 0}, { 35, 0}, { 35, 1},
{ 34, 0}, { 34, 0}, { 34, 0}, { 34, 0}, { 34, 0}, { 34, 1}, { 33, 0}, { 33, 0},
{ 33, 0}, { 33, 0}, { 33, 0}, { 33, 0}, { 33, 1}, { 32, 0}, { 32, 0}, { 32, 0},
{ 32, 0}, { 32, 0}, { 32, 0}, { 32, 0}, { 32, 1}, { 31, 0}, { 31, 0}, { 31, 0},
{ 31, 0}, { 31, 0}, { 31, 0}, { 31, 1}, { 30, 0}, { 30, 0}, { 30, 0}, { 30, 0}
};
const uint16_t speed_lookuptable_slow[256][2] PROGMEM = {
{ 62500, 12500}, { 50000, 8334}, { 41666, 5952}, { 35714, 4464}, { 31250, 3473}, { 27777, 2777}, { 25000, 2273}, { 22727, 1894},
{ 20833, 1603}, { 19230, 1373}, { 17857, 1191}, { 16666, 1041}, { 15625, 920}, { 14705, 817}, { 13888, 731}, { 13157, 657},
{ 12500, 596}, { 11904, 541}, { 11363, 494}, { 10869, 453}, { 10416, 416}, { 10000, 385}, { 9615, 356}, { 9259, 331},
{ 8928, 308}, { 8620, 287}, { 8333, 269}, { 8064, 252}, { 7812, 237}, { 7575, 223}, { 7352, 210}, { 7142, 198},
{ 6944, 188}, { 6756, 178}, { 6578, 168}, { 6410, 160}, { 6250, 153}, { 6097, 145}, { 5952, 139}, { 5813, 132},
{ 5681, 126}, { 5555, 121}, { 5434, 115}, { 5319, 111}, { 5208, 106}, { 5102, 102}, { 5000, 99}, { 4901, 94},
{ 4807, 91}, { 4716, 87}, { 4629, 84}, { 4545, 81}, { 4464, 79}, { 4385, 75}, { 4310, 73}, { 4237, 71},
{ 4166, 68}, { 4098, 66}, { 4032, 64}, { 3968, 62}, { 3906, 60}, { 3846, 59}, { 3787, 56}, { 3731, 55},
{ 3676, 53}, { 3623, 52}, { 3571, 50}, { 3521, 49}, { 3472, 48}, { 3424, 46}, { 3378, 45}, { 3333, 44},
{ 3289, 43}, { 3246, 41}, { 3205, 41}, { 3164, 39}, { 3125, 39}, { 3086, 38}, { 3048, 36}, { 3012, 36},
{ 2976, 35}, { 2941, 35}, { 2906, 33}, { 2873, 33}, { 2840, 32}, { 2808, 31}, { 2777, 30}, { 2747, 30},
{ 2717, 29}, { 2688, 29}, { 2659, 28}, { 2631, 27}, { 2604, 27}, { 2577, 26}, { 2551, 26}, { 2525, 25},
{ 2500, 25}, { 2475, 25}, { 2450, 23}, { 2427, 24}, { 2403, 23}, { 2380, 22}, { 2358, 22}, { 2336, 22},
{ 2314, 21}, { 2293, 21}, { 2272, 20}, { 2252, 20}, { 2232, 20}, { 2212, 20}, { 2192, 19}, { 2173, 18},
{ 2155, 19}, { 2136, 18}, { 2118, 18}, { 2100, 17}, { 2083, 17}, { 2066, 17}, { 2049, 17}, { 2032, 16},
{ 2016, 16}, { 2000, 16}, { 1984, 16}, { 1968, 15}, { 1953, 16}, { 1937, 14}, { 1923, 15}, { 1908, 15},
{ 1893, 14}, { 1879, 14}, { 1865, 14}, { 1851, 13}, { 1838, 14}, { 1824, 13}, { 1811, 13}, { 1798, 13},
{ 1785, 12}, { 1773, 13}, { 1760, 12}, { 1748, 12}, { 1736, 12}, { 1724, 12}, { 1712, 12}, { 1700, 11},
{ 1689, 12}, { 1677, 11}, { 1666, 11}, { 1655, 11}, { 1644, 11}, { 1633, 10}, { 1623, 11}, { 1612, 10},
{ 1602, 10}, { 1592, 10}, { 1582, 10}, { 1572, 10}, { 1562, 10}, { 1552, 9}, { 1543, 10}, { 1533, 9},
{ 1524, 9}, { 1515, 9}, { 1506, 9}, { 1497, 9}, { 1488, 9}, { 1479, 9}, { 1470, 9}, { 1461, 8},
{ 1453, 8}, { 1445, 9}, { 1436, 8}, { 1428, 8}, { 1420, 8}, { 1412, 8}, { 1404, 8}, { 1396, 8},
{ 1388, 7}, { 1381, 8}, { 1373, 7}, { 1366, 8}, { 1358, 7}, { 1351, 7}, { 1344, 8}, { 1336, 7},
{ 1329, 7}, { 1322, 7}, { 1315, 7}, { 1308, 6}, { 1302, 7}, { 1295, 7}, { 1288, 6}, { 1282, 7},
{ 1275, 6}, { 1269, 7}, { 1262, 6}, { 1256, 6}, { 1250, 7}, { 1243, 6}, { 1237, 6}, { 1231, 6},
{ 1225, 6}, { 1219, 6}, { 1213, 6}, { 1207, 6}, { 1201, 5}, { 1196, 6}, { 1190, 6}, { 1184, 5},
{ 1179, 6}, { 1173, 5}, { 1168, 6}, { 1162, 5}, { 1157, 5}, { 1152, 6}, { 1146, 5}, { 1141, 5},
{ 1136, 5}, { 1131, 5}, { 1126, 5}, { 1121, 5}, { 1116, 5}, { 1111, 5}, { 1106, 5}, { 1101, 5},
{ 1096, 5}, { 1091, 5}, { 1086, 4}, { 1082, 5}, { 1077, 5}, { 1072, 4}, { 1068, 5}, { 1063, 4},
{ 1059, 5}, { 1054, 4}, { 1050, 4}, { 1046, 5}, { 1041, 4}, { 1037, 4}, { 1033, 5}, { 1028, 4},
{ 1024, 4}, { 1020, 4}, { 1016, 4}, { 1012, 4}, { 1008, 4}, { 1004, 4}, { 1000, 4}, { 996, 4},
{ 992, 4}, { 988, 4}, { 984, 4}, { 980, 4}, { 976, 4}, { 972, 4}, { 968, 3}, { 965, 3}
};
#elif F_CPU == 20000000
const uint16_t speed_lookuptable_fast[256][2] PROGMEM = {
{62500, 54055}, {8445, 3917}, {4528, 1434}, {3094, 745}, {2349, 456}, {1893, 307}, {1586, 222}, {1364, 167},
{1197, 131}, {1066, 105}, {961, 86}, {875, 72}, {803, 61}, {742, 53}, {689, 45}, {644, 40},
{604, 35}, {569, 32}, {537, 28}, {509, 25}, {484, 23}, {461, 21}, {440, 19}, {421, 17},
{404, 16}, {388, 15}, {373, 14}, {359, 13}, {346, 12}, {334, 11}, {323, 10}, {313, 10},
{303, 9}, {294, 9}, {285, 8}, {277, 7}, {270, 8}, {262, 7}, {255, 6}, {249, 6},
{243, 6}, {237, 6}, {231, 5}, {226, 5}, {221, 5}, {216, 5}, {211, 4}, {207, 5},
{202, 4}, {198, 4}, {194, 4}, {190, 3}, {187, 4}, {183, 3}, {180, 3}, {177, 4},
{173, 3}, {170, 3}, {167, 2}, {165, 3}, {162, 3}, {159, 2}, {157, 3}, {154, 2},
{152, 3}, {149, 2}, {147, 2}, {145, 2}, {143, 2}, {141, 2}, {139, 2}, {137, 2},
{135, 2}, {133, 2}, {131, 2}, {129, 1}, {128, 2}, {126, 2}, {124, 1}, {123, 2},
{121, 1}, {120, 2}, {118, 1}, {117, 1}, {116, 2}, {114, 1}, {113, 1}, {112, 2},
{110, 1}, {109, 1}, {108, 1}, {107, 2}, {105, 1}, {104, 1}, {103, 1}, {102, 1},
{101, 1}, {100, 1}, {99, 1}, {98, 1}, {97, 1}, {96, 1}, {95, 1}, {94, 1},
{93, 1}, {92, 1}, {91, 0}, {91, 1}, {90, 1}, {89, 1}, {88, 1}, {87, 0},
{87, 1}, {86, 1}, {85, 1}, {84, 0}, {84, 1}, {83, 1}, {82, 1}, {81, 0},
{81, 1}, {80, 1}, {79, 0}, {79, 1}, {78, 0}, {78, 1}, {77, 1}, {76, 0},
{76, 1}, {75, 0}, {75, 1}, {74, 1}, {73, 0}, {73, 1}, {72, 0}, {72, 1},
{71, 0}, {71, 1}, {70, 0}, {70, 1}, {69, 0}, {69, 1}, {68, 0}, {68, 1},
{67, 0}, {67, 1}, {66, 0}, {66, 1}, {65, 0}, {65, 0}, {65, 1}, {64, 0},
{64, 1}, {63, 0}, {63, 1}, {62, 0}, {62, 0}, {62, 1}, {61, 0}, {61, 1},
{60, 0}, {60, 0}, {60, 1}, {59, 0}, {59, 0}, {59, 1}, {58, 0}, {58, 0},
{58, 1}, {57, 0}, {57, 0}, {57, 1}, {56, 0}, {56, 0}, {56, 1}, {55, 0},
{55, 0}, {55, 1}, {54, 0}, {54, 0}, {54, 1}, {53, 0}, {53, 0}, {53, 0},
{53, 1}, {52, 0}, {52, 0}, {52, 1}, {51, 0}, {51, 0}, {51, 0}, {51, 1},
{50, 0}, {50, 0}, {50, 0}, {50, 1}, {49, 0}, {49, 0}, {49, 0}, {49, 1},
{48, 0}, {48, 0}, {48, 0}, {48, 1}, {47, 0}, {47, 0}, {47, 0}, {47, 1},
{46, 0}, {46, 0}, {46, 0}, {46, 0}, {46, 1}, {45, 0}, {45, 0}, {45, 0},
{45, 1}, {44, 0}, {44, 0}, {44, 0}, {44, 0}, {44, 1}, {43, 0}, {43, 0},
{43, 0}, {43, 0}, {43, 1}, {42, 0}, {42, 0}, {42, 0}, {42, 0}, {42, 0},
{42, 1}, {41, 0}, {41, 0}, {41, 0}, {41, 0}, {41, 0}, {41, 1}, {40, 0},
{40, 0}, {40, 0}, {40, 0}, {40, 1}, {39, 0}, {39, 0}, {39, 0}, {39, 0},
{39, 0}, {39, 0}, {39, 1}, {38, 0}, {38, 0}, {38, 0}, {38, 0}, {38, 0},
};
const uint16_t speed_lookuptable_slow[256][2] PROGMEM = {
{62500, 10417}, {52083, 7441}, {44642, 5580}, {39062, 4340}, {34722, 3472}, {31250, 2841}, {28409, 2368}, {26041, 2003},
{24038, 1717}, {22321, 1488}, {20833, 1302}, {19531, 1149}, {18382, 1021}, {17361, 914}, {16447, 822}, {15625, 745},
{14880, 676}, {14204, 618}, {13586, 566}, {13020, 520}, {12500, 481}, {12019, 445}, {11574, 414}, {11160, 385},
{10775, 359}, {10416, 336}, {10080, 315}, {9765, 296}, {9469, 278}, {9191, 263}, {8928, 248}, {8680, 235},
{8445, 222}, {8223, 211}, {8012, 200}, {7812, 191}, {7621, 181}, {7440, 173}, {7267, 165}, {7102, 158},
{6944, 151}, {6793, 145}, {6648, 138}, {6510, 133}, {6377, 127}, {6250, 123}, {6127, 118}, {6009, 113},
{5896, 109}, {5787, 106}, {5681, 101}, {5580, 98}, {5482, 95}, {5387, 91}, {5296, 88}, {5208, 86},
{5122, 82}, {5040, 80}, {4960, 78}, {4882, 75}, {4807, 73}, {4734, 70}, {4664, 69}, {4595, 67},
{4528, 64}, {4464, 63}, {4401, 61}, {4340, 60}, {4280, 58}, {4222, 56}, {4166, 55}, {4111, 53},
{4058, 52}, {4006, 51}, {3955, 49}, {3906, 48}, {3858, 48}, {3810, 45}, {3765, 45}, {3720, 44},
{3676, 43}, {3633, 42}, {3591, 40}, {3551, 40}, {3511, 39}, {3472, 38}, {3434, 38}, {3396, 36},
{3360, 36}, {3324, 35}, {3289, 34}, {3255, 34}, {3221, 33}, {3188, 32}, {3156, 31}, {3125, 31},
{3094, 31}, {3063, 30}, {3033, 29}, {3004, 28}, {2976, 28}, {2948, 28}, {2920, 27}, {2893, 27},
{2866, 26}, {2840, 25}, {2815, 25}, {2790, 25}, {2765, 24}, {2741, 24}, {2717, 24}, {2693, 23},
{2670, 22}, {2648, 22}, {2626, 22}, {2604, 22}, {2582, 21}, {2561, 21}, {2540, 20}, {2520, 20},
{2500, 20}, {2480, 20}, {2460, 19}, {2441, 19}, {2422, 19}, {2403, 18}, {2385, 18}, {2367, 18},
{2349, 17}, {2332, 18}, {2314, 17}, {2297, 16}, {2281, 17}, {2264, 16}, {2248, 16}, {2232, 16},
{2216, 16}, {2200, 15}, {2185, 15}, {2170, 15}, {2155, 15}, {2140, 15}, {2125, 14}, {2111, 14},
{2097, 14}, {2083, 14}, {2069, 14}, {2055, 13}, {2042, 13}, {2029, 13}, {2016, 13}, {2003, 13},
{1990, 13}, {1977, 12}, {1965, 12}, {1953, 13}, {1940, 11}, {1929, 12}, {1917, 12}, {1905, 12},
{1893, 11}, {1882, 11}, {1871, 11}, {1860, 11}, {1849, 11}, {1838, 11}, {1827, 11}, {1816, 10},
{1806, 11}, {1795, 10}, {1785, 10}, {1775, 10}, {1765, 10}, {1755, 10}, {1745, 9}, {1736, 10},
{1726, 9}, {1717, 10}, {1707, 9}, {1698, 9}, {1689, 9}, {1680, 9}, {1671, 9}, {1662, 9},
{1653, 9}, {1644, 8}, {1636, 9}, {1627, 8}, {1619, 9}, {1610, 8}, {1602, 8}, {1594, 8},
{1586, 8}, {1578, 8}, {1570, 8}, {1562, 8}, {1554, 7}, {1547, 8}, {1539, 8}, {1531, 7},
{1524, 8}, {1516, 7}, {1509, 7}, {1502, 7}, {1495, 7}, {1488, 7}, {1481, 7}, {1474, 7},
{1467, 7}, {1460, 7}, {1453, 7}, {1446, 6}, {1440, 7}, {1433, 7}, {1426, 6}, {1420, 6},
{1414, 7}, {1407, 6}, {1401, 6}, {1395, 7}, {1388, 6}, {1382, 6}, {1376, 6}, {1370, 6},
{1364, 6}, {1358, 6}, {1352, 6}, {1346, 5}, {1341, 6}, {1335, 6}, {1329, 5}, {1324, 6},
{1318, 5}, {1313, 6}, {1307, 5}, {1302, 6}, {1296, 5}, {1291, 5}, {1286, 6}, {1280, 5},
{1275, 5}, {1270, 5}, {1265, 5}, {1260, 5}, {1255, 5}, {1250, 5}, {1245, 5}, {1240, 5},
{1235, 5}, {1230, 5}, {1225, 5}, {1220, 5}, {1215, 4}, {1211, 5}, {1206, 5}, {1201, 5},
};
#endif
File diff suppressed because it is too large Load Diff
+787
View File
@@ -0,0 +1,787 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* stepper.h - stepper motor driver: executes motion plans of planner.c using the stepper motors
* Derived from Grbl
*
* Copyright (c) 2009-2011 Simen Svale Skogsrud
*
* Grbl is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Grbl is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Grbl. If not, see <https://www.gnu.org/licenses/>.
*/
#include "../inc/MarlinConfig.h"
#include "planner.h"
#include "stepper/indirection.h"
#ifdef __AVR__
#include "speed_lookuptable.h"
#endif
// Disable multiple steps per ISR
//#define DISABLE_MULTI_STEPPING
//
// Estimate the amount of time the Stepper ISR will take to execute
//
/**
* The method of calculating these cycle-constants is unclear.
* Most of them are no longer used directly for pulse timing, and exist
* only to estimate a maximum step rate based on the user's configuration.
* As 32-bit processors continue to diverge, maintaining cycle counts
* will become increasingly difficult and error-prone.
*/
#ifdef CPU_32_BIT
/**
* Duration of START_TIMED_PULSE
*
* ...as measured on an LPC1768 with a scope and converted to cycles.
* Not applicable to other 32-bit processors, but as long as others
* take longer, pulses will be longer. For example the SKR Pro
* (stm32f407zgt6) requires ~60 cyles.
*/
#define TIMER_READ_ADD_AND_STORE_CYCLES 34UL
// The base ISR takes 792 cycles
#define ISR_BASE_CYCLES 792UL
// Linear advance base time is 64 cycles
#if ENABLED(LIN_ADVANCE)
#define ISR_LA_BASE_CYCLES 64UL
#else
#define ISR_LA_BASE_CYCLES 0UL
#endif
// S curve interpolation adds 40 cycles
#if ENABLED(S_CURVE_ACCELERATION)
#define ISR_S_CURVE_CYCLES 40UL
#else
#define ISR_S_CURVE_CYCLES 0UL
#endif
// Input shaping base time
#if HAS_SHAPING
#define ISR_SHAPING_BASE_CYCLES 290UL
#else
#define ISR_SHAPING_BASE_CYCLES 0UL
#endif
// Stepper Loop base cycles
#define ISR_LOOP_BASE_CYCLES 4UL
// To start the step pulse, in the worst case takes
#define ISR_START_STEPPER_CYCLES 13UL
// And each stepper (start + stop pulse) takes in worst case
#define ISR_STEPPER_CYCLES 16UL
#else
// Cycles to perform actions in START_TIMED_PULSE
#define TIMER_READ_ADD_AND_STORE_CYCLES 13UL
// The base ISR takes 752 cycles
#define ISR_BASE_CYCLES 752UL
// Linear advance base time is 32 cycles
#if ENABLED(LIN_ADVANCE)
#define ISR_LA_BASE_CYCLES 32UL
#else
#define ISR_LA_BASE_CYCLES 0UL
#endif
// S curve interpolation adds 160 cycles
#if ENABLED(S_CURVE_ACCELERATION)
#define ISR_S_CURVE_CYCLES 160UL
#else
#define ISR_S_CURVE_CYCLES 0UL
#endif
// Stepper Loop base cycles
#define ISR_LOOP_BASE_CYCLES 32UL
// To start the step pulse, in the worst case takes
#define ISR_START_STEPPER_CYCLES 57UL
// And each stepper (start + stop pulse) takes in worst case
#define ISR_STEPPER_CYCLES 88UL
#endif
// Add time for each stepper
#if HAS_X_STEP
#define ISR_X_STEPPER_CYCLES ISR_STEPPER_CYCLES
#else
#define ISR_X_STEPPER_CYCLES 0UL
#endif
#if HAS_Y_STEP
#define ISR_Y_STEPPER_CYCLES ISR_STEPPER_CYCLES
#else
#define ISR_START_Y_STEPPER_CYCLES 0UL
#define ISR_Y_STEPPER_CYCLES 0UL
#endif
#if HAS_Z_STEP
#define ISR_Z_STEPPER_CYCLES ISR_STEPPER_CYCLES
#else
#define ISR_Z_STEPPER_CYCLES 0UL
#endif
// E is always interpolated, even for mixing extruders
#define ISR_E_STEPPER_CYCLES ISR_STEPPER_CYCLES
// If linear advance is disabled, the loop also handles them
#if DISABLED(LIN_ADVANCE) && ENABLED(MIXING_EXTRUDER)
#define ISR_MIXING_STEPPER_CYCLES ((MIXING_STEPPERS) * (ISR_STEPPER_CYCLES))
#else
#define ISR_MIXING_STEPPER_CYCLES 0UL
#endif
// And the total minimum loop time, not including the base
#define MIN_ISR_LOOP_CYCLES (ISR_X_STEPPER_CYCLES + ISR_Y_STEPPER_CYCLES + ISR_Z_STEPPER_CYCLES + ISR_E_STEPPER_CYCLES + ISR_MIXING_STEPPER_CYCLES)
// Calculate the minimum MPU cycles needed per pulse to enforce, limited to the max stepper rate
#define _MIN_STEPPER_PULSE_CYCLES(N) _MAX(uint32_t((F_CPU) / (MAXIMUM_STEPPER_RATE)), ((F_CPU) / 500000UL) * (N))
#if MINIMUM_STEPPER_PULSE
#define MIN_STEPPER_PULSE_CYCLES _MIN_STEPPER_PULSE_CYCLES(uint32_t(MINIMUM_STEPPER_PULSE))
#elif HAS_DRIVER(LV8729)
#define MIN_STEPPER_PULSE_CYCLES uint32_t((((F_CPU) - 1) / 2000000) + 1) // 0.5µs, aka 500ns
#else
#define MIN_STEPPER_PULSE_CYCLES _MIN_STEPPER_PULSE_CYCLES(1UL)
#endif
// Calculate the minimum pulse times (high and low)
#if MINIMUM_STEPPER_PULSE && MAXIMUM_STEPPER_RATE
constexpr uint32_t _MIN_STEP_PERIOD_NS = 1000000000UL / MAXIMUM_STEPPER_RATE;
constexpr uint32_t _MIN_PULSE_HIGH_NS = 1000UL * MINIMUM_STEPPER_PULSE;
constexpr uint32_t _MIN_PULSE_LOW_NS = _MAX((_MIN_STEP_PERIOD_NS - _MIN(_MIN_STEP_PERIOD_NS, _MIN_PULSE_HIGH_NS)), _MIN_PULSE_HIGH_NS);
#elif MINIMUM_STEPPER_PULSE
// Assume 50% duty cycle
constexpr uint32_t _MIN_PULSE_HIGH_NS = 1000UL * MINIMUM_STEPPER_PULSE;
constexpr uint32_t _MIN_PULSE_LOW_NS = _MIN_PULSE_HIGH_NS;
#elif MAXIMUM_STEPPER_RATE
// Assume 50% duty cycle
constexpr uint32_t _MIN_PULSE_HIGH_NS = 500000000UL / MAXIMUM_STEPPER_RATE;
constexpr uint32_t _MIN_PULSE_LOW_NS = _MIN_PULSE_HIGH_NS;
#else
#error "Expected at least one of MINIMUM_STEPPER_PULSE or MAXIMUM_STEPPER_RATE to be defined"
#endif
// But the user could be enforcing a minimum time, so the loop time is
#define ISR_LOOP_CYCLES (ISR_LOOP_BASE_CYCLES + _MAX(MIN_STEPPER_PULSE_CYCLES, MIN_ISR_LOOP_CYCLES))
// Model input shaping as an extra loop call
#define ISR_SHAPING_LOOP_CYCLES(R) ((TERN0(HAS_SHAPING, ISR_LOOP_BASE_CYCLES) + TERN0(INPUT_SHAPING_X, ISR_X_STEPPER_CYCLES) + TERN0(INPUT_SHAPING_Y, ISR_Y_STEPPER_CYCLES)) * (R) + (MIN_ISR_LOOP_CYCLES) * (R - 1))
// If linear advance is enabled, then it is handled separately
#if ENABLED(LIN_ADVANCE)
// Estimate the minimum LA loop time
#if ENABLED(MIXING_EXTRUDER) // ToDo: ???
// HELP ME: What is what?
// Directions are set up for MIXING_STEPPERS - like before.
// Finding the right stepper may last up to MIXING_STEPPERS loops in get_next_stepper().
// These loops are a bit faster than advancing a bresenham counter.
// Always only one e-stepper is stepped.
#define MIN_ISR_LA_LOOP_CYCLES ((MIXING_STEPPERS) * (ISR_STEPPER_CYCLES))
#else
#define MIN_ISR_LA_LOOP_CYCLES ISR_STEPPER_CYCLES
#endif
// And the real loop time
#define ISR_LA_LOOP_CYCLES _MAX(MIN_STEPPER_PULSE_CYCLES, MIN_ISR_LA_LOOP_CYCLES)
#else
#define ISR_LA_LOOP_CYCLES 0UL
#endif
// Now estimate the total ISR execution time in cycles given a step per ISR multiplier
#define ISR_EXECUTION_CYCLES(R) (((ISR_BASE_CYCLES + ISR_S_CURVE_CYCLES + (ISR_LOOP_CYCLES) * (R) + ISR_LA_BASE_CYCLES + ISR_LA_LOOP_CYCLES)) / (R))
// The maximum allowable stepping frequency when doing x128-x1 stepping (in Hz)
#define MAX_STEP_ISR_FREQUENCY_128X ((F_CPU) / ISR_EXECUTION_CYCLES(128))
#define MAX_STEP_ISR_FREQUENCY_64X ((F_CPU) / ISR_EXECUTION_CYCLES(64))
#define MAX_STEP_ISR_FREQUENCY_32X ((F_CPU) / ISR_EXECUTION_CYCLES(32))
#define MAX_STEP_ISR_FREQUENCY_16X ((F_CPU) / ISR_EXECUTION_CYCLES(16))
#define MAX_STEP_ISR_FREQUENCY_8X ((F_CPU) / ISR_EXECUTION_CYCLES(8))
#define MAX_STEP_ISR_FREQUENCY_4X ((F_CPU) / ISR_EXECUTION_CYCLES(4))
#define MAX_STEP_ISR_FREQUENCY_2X ((F_CPU) / ISR_EXECUTION_CYCLES(2))
#define MAX_STEP_ISR_FREQUENCY_1X ((F_CPU) / ISR_EXECUTION_CYCLES(1))
// The minimum step ISR rate used by ADAPTIVE_STEP_SMOOTHING to target 50% CPU usage
// This does not account for the possibility of multi-stepping.
// Perhaps DISABLE_MULTI_STEPPING should be required with ADAPTIVE_STEP_SMOOTHING.
#define MIN_STEP_ISR_FREQUENCY (MAX_STEP_ISR_FREQUENCY_1X / 2)
#if HAS_SHAPING
#ifdef SHAPING_MAX_STEPRATE
constexpr float max_step_rate = SHAPING_MAX_STEPRATE;
#else
constexpr float _ISDASU[] = DEFAULT_AXIS_STEPS_PER_UNIT;
constexpr feedRate_t _ISDMF[] = DEFAULT_MAX_FEEDRATE;
constexpr float max_shaped_rate = TERN0(INPUT_SHAPING_X, _ISDMF[X_AXIS] * _ISDASU[X_AXIS]) +
TERN0(INPUT_SHAPING_Y, _ISDMF[Y_AXIS] * _ISDASU[Y_AXIS]);
#if defined(__AVR__) || !defined(ADAPTIVE_STEP_SMOOTHING)
// MIN_STEP_ISR_FREQUENCY is known at compile time on AVRs and any reduction in SRAM is welcome
template<int INDEX=DISTINCT_AXES> constexpr float max_isr_rate() {
return _MAX(_ISDMF[INDEX - 1] * _ISDASU[INDEX - 1], max_isr_rate<INDEX - 1>());
}
template<> constexpr float max_isr_rate<0>() {
return TERN0(ADAPTIVE_STEP_SMOOTHING, MIN_STEP_ISR_FREQUENCY);
}
constexpr float max_step_rate = _MIN(max_isr_rate(), max_shaped_rate);
#else
constexpr float max_step_rate = max_shaped_rate;
#endif
#endif
#ifndef SHAPING_MIN_FREQ
#define SHAPING_MIN_FREQ _MIN(0x7FFFFFFFL OPTARG(INPUT_SHAPING_X, SHAPING_FREQ_X) OPTARG(INPUT_SHAPING_Y, SHAPING_FREQ_Y))
#endif
constexpr uint16_t shaping_min_freq = SHAPING_MIN_FREQ,
// shaping_echoes = max_step_rate / shaping_min_freq / 2 + 3;
shaping_echoes = max_step_rate / shaping_min_freq / 2 + 3;
// shaping_echoes = 3;
typedef IF<ENABLED(__AVR__), uint16_t, uint32_t>::type shaping_time_t;
enum shaping_echo_t { ECHO_NONE = 0, ECHO_FWD = 1, ECHO_BWD = 2 };
struct shaping_echo_axis_t {
TERN_(INPUT_SHAPING_X, shaping_echo_t x:2);
TERN_(INPUT_SHAPING_Y, shaping_echo_t y:2);
};
class ShapingQueue {
private:
static shaping_time_t now;
static shaping_time_t times[shaping_echoes];
static shaping_echo_axis_t echo_axes[shaping_echoes];
static uint16_t tail;
#if ENABLED(INPUT_SHAPING_X)
static shaping_time_t delay_x; // = shaping_time_t(-1) to disable queueing
static shaping_time_t peek_x_val;
static uint16_t head_x;
static uint16_t _free_count_x;
#endif
#if ENABLED(INPUT_SHAPING_Y)
static shaping_time_t delay_y; // = shaping_time_t(-1) to disable queueing
static shaping_time_t peek_y_val;
static uint16_t head_y;
static uint16_t _free_count_y;
#endif
public:
static void decrement_delays(const shaping_time_t interval) {
now += interval;
TERN_(INPUT_SHAPING_X, if (peek_x_val != shaping_time_t(-1)) peek_x_val -= interval);
TERN_(INPUT_SHAPING_Y, if (peek_y_val != shaping_time_t(-1)) peek_y_val -= interval);
}
static void set_delay(const AxisEnum axis, const shaping_time_t delay) {
TERN_(INPUT_SHAPING_X, if (axis == X_AXIS) delay_x = delay);
TERN_(INPUT_SHAPING_Y, if (axis == Y_AXIS) delay_y = delay);
}
static void enqueue(const bool x_step, const bool x_forward, const bool y_step, const bool y_forward) {
TERN_(INPUT_SHAPING_X, if (head_x == tail && x_step) peek_x_val = delay_x);
TERN_(INPUT_SHAPING_Y, if (head_y == tail && y_step) peek_y_val = delay_y);
times[tail] = now;
TERN_(INPUT_SHAPING_X, echo_axes[tail].x = x_step ? (x_forward ? ECHO_FWD : ECHO_BWD) : ECHO_NONE);
TERN_(INPUT_SHAPING_Y, echo_axes[tail].y = y_step ? (y_forward ? ECHO_FWD : ECHO_BWD) : ECHO_NONE);
if (++tail == shaping_echoes) tail = 0;
TERN_(INPUT_SHAPING_X, _free_count_x--);
TERN_(INPUT_SHAPING_Y, _free_count_y--);
TERN_(INPUT_SHAPING_X, if (echo_axes[head_x].x == ECHO_NONE) dequeue_x());
TERN_(INPUT_SHAPING_Y, if (echo_axes[head_y].y == ECHO_NONE) dequeue_y());
}
#if ENABLED(INPUT_SHAPING_X)
static shaping_time_t peek_x() { return peek_x_val; }
static bool dequeue_x() {
bool forward = echo_axes[head_x].x == ECHO_FWD;
do {
_free_count_x++;
if (++head_x == shaping_echoes) head_x = 0;
} while (head_x != tail && echo_axes[head_x].x == ECHO_NONE);
peek_x_val = head_x == tail ? shaping_time_t(-1) : times[head_x] + delay_x - now;
return forward;
}
static bool empty_x() { return head_x == tail; }
static uint16_t free_count_x() { return _free_count_x; }
#endif
#if ENABLED(INPUT_SHAPING_Y)
static shaping_time_t peek_y() { return peek_y_val; }
static bool dequeue_y() {
bool forward = echo_axes[head_y].y == ECHO_FWD;
do {
_free_count_y++;
if (++head_y == shaping_echoes) head_y = 0;
} while (head_y != tail && echo_axes[head_y].y == ECHO_NONE);
peek_y_val = head_y == tail ? shaping_time_t(-1) : times[head_y] + delay_y - now;
return forward;
}
static bool empty_y() { return head_y == tail; }
static uint16_t free_count_y() { return _free_count_y; }
#endif
static void purge() {
const auto st = shaping_time_t(-1);
#if ENABLED(INPUT_SHAPING_X)
head_x = tail; _free_count_x = shaping_echoes - 1; peek_x_val = st;
#endif
#if ENABLED(INPUT_SHAPING_Y)
head_y = tail; _free_count_y = shaping_echoes - 1; peek_y_val = st;
#endif
}
};
struct ShapeParams {
float frequency;
float zeta;
bool enabled;
int16_t delta_error = 0; // delta_error for seconday bresenham mod 128
uint8_t factor1;
uint8_t factor2;
bool forward;
int32_t last_block_end_pos = 0;
};
#endif // HAS_SHAPING
//
// Stepper class definition
//
class Stepper {
public:
#if EITHER(HAS_EXTRA_ENDSTOPS, Z_STEPPER_AUTO_ALIGN)
static bool separate_multi_axis;
#endif
#if HAS_MOTOR_CURRENT_SPI || HAS_MOTOR_CURRENT_PWM
#if HAS_MOTOR_CURRENT_PWM
#ifndef PWM_MOTOR_CURRENT
#define PWM_MOTOR_CURRENT DEFAULT_PWM_MOTOR_CURRENT
#endif
#define MOTOR_CURRENT_COUNT LINEAR_AXES
#elif HAS_MOTOR_CURRENT_SPI
static constexpr uint32_t digipot_count[] = DIGIPOT_MOTOR_CURRENT;
#define MOTOR_CURRENT_COUNT COUNT(Stepper::digipot_count)
#endif
static bool initialized;
static uint32_t motor_current_setting[MOTOR_CURRENT_COUNT]; // Initialized by settings.load()
#endif
// Last-moved extruder, as set when the last movement was fetched from planner
#if HAS_MULTI_EXTRUDER
static uint8_t last_moved_extruder;
#else
static constexpr uint8_t last_moved_extruder = 0;
#endif
#if HAS_FREEZE_PIN
static bool frozen; // Set this flag to instantly freeze motion
#endif
private:
static block_t* current_block; // A pointer to the block currently being traced
static uint8_t last_direction_bits, // The next stepping-bits to be output
axis_did_move; // Last Movement in the given direction is not null, as computed when the last movement was fetched from planner
static bool abort_current_block; // Signals to the stepper that current block should be aborted
#if ENABLED(X_DUAL_ENDSTOPS)
static bool locked_X_motor, locked_X2_motor;
#endif
#if ENABLED(Y_DUAL_ENDSTOPS)
static bool locked_Y_motor, locked_Y2_motor;
#endif
#if EITHER(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN)
static bool locked_Z_motor, locked_Z2_motor
#if NUM_Z_STEPPER_DRIVERS >= 3
, locked_Z3_motor
#if NUM_Z_STEPPER_DRIVERS >= 4
, locked_Z4_motor
#endif
#endif
;
#endif
static uint32_t acceleration_time, deceleration_time; // time measured in Stepper Timer ticks
static uint8_t steps_per_isr; // Count of steps to perform per Stepper ISR call
#if ENABLED(ADAPTIVE_STEP_SMOOTHING)
static uint8_t oversampling_factor; // Oversampling factor (log2(multiplier)) to increase temporal resolution of axis
#else
static constexpr uint8_t oversampling_factor = 0;
#endif
// Delta error variables for the Bresenham line tracer
static xyze_long_t delta_error;
static xyze_ulong_t advance_dividend;
static uint32_t advance_divisor,
step_events_completed, // The number of step events executed in the current block
accelerate_until, // The point from where we need to stop acceleration
decelerate_after, // The point from where we need to start decelerating
step_event_count; // The total event count for the current block
#if EITHER(HAS_MULTI_EXTRUDER, MIXING_EXTRUDER)
static uint8_t stepper_extruder;
#else
static constexpr uint8_t stepper_extruder = 0;
#endif
#if ENABLED(S_CURVE_ACCELERATION)
static int32_t bezier_A, // A coefficient in Bézier speed curve
bezier_B, // B coefficient in Bézier speed curve
bezier_C; // C coefficient in Bézier speed curve
static uint32_t bezier_F, // F coefficient in Bézier speed curve
bezier_AV; // AV coefficient in Bézier speed curve
#ifdef __AVR__
static bool A_negative; // If A coefficient was negative
#endif
static bool bezier_2nd_half; // If Bézier curve has been initialized or not
#endif
#if HAS_SHAPING
#if ENABLED(INPUT_SHAPING_X)
static ShapeParams shaping_x;
#endif
#if ENABLED(INPUT_SHAPING_Y)
static ShapeParams shaping_y;
#endif
#endif
#if ENABLED(LIN_ADVANCE)
static constexpr uint32_t LA_ADV_NEVER = 0xFFFFFFFF;
static uint32_t nextAdvanceISR, LA_isr_rate;
static uint16_t LA_current_adv_steps, LA_final_adv_steps, LA_max_adv_steps; // Copy from current executed block. Needed because current_block is set to NULL "too early".
static int8_t LA_steps;
static bool LA_use_advance_lead;
#endif
#if ENABLED(INTEGRATED_BABYSTEPPING)
static constexpr uint32_t BABYSTEP_NEVER = 0xFFFFFFFF;
static uint32_t nextBabystepISR;
#endif
#if ENABLED(DIRECT_STEPPING)
static page_step_state_t page_step_state;
#endif
static int32_t ticks_nominal;
#if DISABLED(S_CURVE_ACCELERATION)
static uint32_t acc_step_rate; // needed for deceleration start point
#endif
// Exact steps at which an endstop was triggered
static xyz_long_t endstops_trigsteps;
// Positions of stepper motors, in step units
static xyze_long_t count_position;
// Current stepper motor directions (+1 or -1)
static xyze_int8_t count_direction;
#if ENABLED(LASER_POWER_INLINE_TRAPEZOID)
typedef struct {
bool enabled; // Trapezoid needed flag (i.e., laser on, planner in control)
uint8_t cur_power; // Current laser power
bool cruise_set; // Power set up for cruising?
#if DISABLED(LASER_POWER_INLINE_TRAPEZOID_CONT)
uint32_t last_step_count, // Step count from the last update
acc_step_count; // Bresenham counter for laser accel/decel
#else
uint16_t till_update; // Countdown to the next update
#endif
} stepper_laser_t;
static stepper_laser_t laser_trap;
#endif
public:
// Initialize stepper hardware
static void init();
// Interrupt Service Routine and phases
// The stepper subsystem goes to sleep when it runs out of things to execute.
// Call this to notify the subsystem that it is time to go to work.
static inline void wake_up() { ENABLE_STEPPER_DRIVER_INTERRUPT(); }
static inline bool is_awake() { return STEPPER_ISR_ENABLED(); }
static inline bool suspend() {
const bool awake = is_awake();
if (awake) DISABLE_STEPPER_DRIVER_INTERRUPT();
return awake;
}
// The ISR scheduler
static void isr();
// The stepper pulse ISR phase
static void pulse_phase_isr();
// The stepper block processing ISR phase
static uint32_t block_phase_isr();
#if HAS_SHAPING
static void shaping_isr();
#endif
#if ENABLED(LIN_ADVANCE)
// The Linear advance ISR phase
static uint32_t advance_isr();
FORCE_INLINE static void initiateLA() { nextAdvanceISR = 0; }
#endif
#if ENABLED(INTEGRATED_BABYSTEPPING)
// The Babystepping ISR phase
static uint32_t babystepping_isr();
FORCE_INLINE static void initiateBabystepping() {
if (nextBabystepISR == BABYSTEP_NEVER) {
nextBabystepISR = 0;
wake_up();
}
}
#endif
// Check if the given block is busy or not - Must not be called from ISR contexts
static bool is_block_busy(const block_t * const block);
#if HAS_SHAPING
// Check whether the stepper is processing any input shaping echoes
static bool input_shaping_busy() {
const bool was_on = ISRS_ENABLED();
DISABLE_ISRS();
const bool result = TERN0(INPUT_SHAPING_X, !ShapingQueue::empty_x()) || TERN0(INPUT_SHAPING_Y, !ShapingQueue::empty_y());
if (was_on) ENABLE_ISRS();
return result;
}
#endif
// Get the position of a stepper, in steps
static int32_t position(const AxisEnum axis);
// Set the current position in steps
static void set_position(const int32_t &a, const int32_t &b, const int32_t &c, const int32_t &e);
static inline void set_position(const xyze_long_t &abce) { set_position(abce.a, abce.b, abce.c, abce.e); }
static void set_axis_position(const AxisEnum a, const int32_t &v);
// Report the positions of the steppers, in steps
static void report_a_position(const xyz_long_t &pos);
static void report_positions();
// Discard current block and free any resources
FORCE_INLINE static void discard_current_block() {
#if ENABLED(DIRECT_STEPPING)
if (IS_PAGE(current_block))
page_manager.free_page(current_block->page_idx);
#endif
current_block = nullptr;
axis_did_move = 0;
planner.release_current_block();
}
// Quickly stop all steppers
FORCE_INLINE static void quick_stop() { abort_current_block = true; }
// The direction of a single motor
FORCE_INLINE static bool motor_direction(const AxisEnum axis) { return TEST(last_direction_bits, axis); }
// The last movement direction was not null on the specified axis. Note that motor direction is not necessarily the same.
FORCE_INLINE static bool axis_is_moving(const AxisEnum axis) { return TEST(axis_did_move, axis); }
// Handle a triggered endstop
static void endstop_triggered(const AxisEnum axis);
// Triggered position of an axis in steps
static int32_t triggered_position(const AxisEnum axis);
#if HAS_MOTOR_CURRENT_SPI || HAS_MOTOR_CURRENT_PWM
static void set_digipot_value_spi(const int16_t address, const int16_t value);
static void set_digipot_current(const uint8_t driver, const int16_t current);
#endif
#if HAS_MICROSTEPS
static void microstep_ms(const uint8_t driver, const int8_t ms1, const int8_t ms2, const int8_t ms3);
static void microstep_mode(const uint8_t driver, const uint8_t stepping);
static void microstep_readings();
#endif
#if EITHER(HAS_EXTRA_ENDSTOPS, Z_STEPPER_AUTO_ALIGN)
FORCE_INLINE static void set_separate_multi_axis(const bool state) { separate_multi_axis = state; }
#endif
#if ENABLED(X_DUAL_ENDSTOPS)
FORCE_INLINE static void set_x_lock(const bool state) { locked_X_motor = state; }
FORCE_INLINE static void set_x2_lock(const bool state) { locked_X2_motor = state; }
#endif
#if ENABLED(Y_DUAL_ENDSTOPS)
FORCE_INLINE static void set_y_lock(const bool state) { locked_Y_motor = state; }
FORCE_INLINE static void set_y2_lock(const bool state) { locked_Y2_motor = state; }
#endif
#if EITHER(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN)
FORCE_INLINE static void set_z1_lock(const bool state) { locked_Z_motor = state; }
FORCE_INLINE static void set_z2_lock(const bool state) { locked_Z2_motor = state; }
#if NUM_Z_STEPPER_DRIVERS >= 3
FORCE_INLINE static void set_z3_lock(const bool state) { locked_Z3_motor = state; }
#if NUM_Z_STEPPER_DRIVERS >= 4
FORCE_INLINE static void set_z4_lock(const bool state) { locked_Z4_motor = state; }
#endif
#endif
static inline void set_all_z_lock(const bool lock, const int8_t except=-1) {
set_z1_lock(lock ^ (except == 0));
set_z2_lock(lock ^ (except == 1));
#if NUM_Z_STEPPER_DRIVERS >= 3
set_z3_lock(lock ^ (except == 2));
#if NUM_Z_STEPPER_DRIVERS >= 4
set_z4_lock(lock ^ (except == 3));
#endif
#endif
}
#endif
#if ENABLED(BABYSTEPPING)
static void do_babystep(const AxisEnum axis, const bool direction); // perform a short step with a single stepper motor, outside of any convention
#endif
#if HAS_MOTOR_CURRENT_PWM
static void refresh_motor_power();
#endif
// Update direction states for all steppers
static void set_directions();
// Set direction bits and update all stepper DIR states
static void set_directions(const uint8_t bits) {
last_direction_bits = bits;
set_directions();
}
#if HAS_SHAPING
static void set_shaping_damping_ratio(const AxisEnum axis, const float zeta);
static float get_shaping_damping_ratio(const AxisEnum axis);
static void set_shaping_frequency(const AxisEnum axis, const float freq);
static float get_shaping_frequency(const AxisEnum axis);
#endif
private:
// Set the current position in steps
static void _set_position(const int32_t &a, const int32_t &b, const int32_t &c, const int32_t &e);
FORCE_INLINE static void _set_position(const abce_long_t &spos) { _set_position(spos.a, spos.b, spos.c, spos.e); }
FORCE_INLINE static uint32_t calc_timer_interval(uint32_t step_rate, uint8_t *loops) {
uint32_t timer;
// Scale the frequency, as requested by the caller
step_rate <<= oversampling_factor;
uint8_t multistep = 1;
#if DISABLED(DISABLE_MULTI_STEPPING)
// The stepping frequency limits for each multistepping rate
static const uint32_t limit[] PROGMEM = {
( MAX_STEP_ISR_FREQUENCY_1X ),
( MAX_STEP_ISR_FREQUENCY_2X >> 1),
( MAX_STEP_ISR_FREQUENCY_4X >> 2),
( MAX_STEP_ISR_FREQUENCY_8X >> 3),
( MAX_STEP_ISR_FREQUENCY_16X >> 4),
( MAX_STEP_ISR_FREQUENCY_32X >> 5),
( MAX_STEP_ISR_FREQUENCY_64X >> 6),
(MAX_STEP_ISR_FREQUENCY_128X >> 7)
};
// Select the proper multistepping
uint8_t idx = 0;
while (idx < 7 && step_rate > (uint32_t)pgm_read_dword(&limit[idx])) {
step_rate >>= 1;
multistep <<= 1;
++idx;
};
#else
NOMORE(step_rate, uint32_t(MAX_STEP_ISR_FREQUENCY_1X));
#endif
*loops = multistep;
#ifdef CPU_32_BIT
// In case of high-performance processor, it is able to calculate in real-time
timer = uint32_t(STEPPER_TIMER_RATE) / step_rate;
#else
constexpr uint32_t min_step_rate = (F_CPU) / 500000U;
NOLESS(step_rate, min_step_rate);
step_rate -= min_step_rate; // Correct for minimal speed
if (step_rate >= (8 * 256)) { // higher step rate
const uint8_t tmp_step_rate = (step_rate & 0x00FF);
const uint16_t table_address = (uint16_t)&speed_lookuptable_fast[(uint8_t)(step_rate >> 8)][0],
gain = (uint16_t)pgm_read_word(table_address + 2);
timer = MultiU16X8toH16(tmp_step_rate, gain);
timer = (uint16_t)pgm_read_word(table_address) - timer;
}
else { // lower step rates
uint16_t table_address = (uint16_t)&speed_lookuptable_slow[0][0];
table_address += ((step_rate) >> 1) & 0xFFFC;
timer = (uint16_t)pgm_read_word(table_address)
- (((uint16_t)pgm_read_word(table_address + 2) * (uint8_t)(step_rate & 0x0007)) >> 3);
}
// (there is no need to limit the timer value here. All limits have been
// applied above, and AVR is able to keep up at 30khz Stepping ISR rate)
#endif
return timer;
}
#if ENABLED(S_CURVE_ACCELERATION)
static void _calc_bezier_curve_coeffs(const int32_t v0, const int32_t v1, const uint32_t av);
static int32_t _eval_bezier_curve(const uint32_t curr_step);
#endif
#if HAS_MOTOR_CURRENT_SPI || HAS_MOTOR_CURRENT_PWM
static void digipot_init();
#endif
#if HAS_MICROSTEPS
static void microstep_init();
#endif
};
extern Stepper stepper;
+228
View File
@@ -0,0 +1,228 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
/**
* stepper/L64xx.cpp
* Stepper driver indirection for L64XX drivers
*/
#include "../../inc/MarlinConfig.h"
#if HAS_L64XX
#include "L64xx.h"
#if AXIS_IS_L64XX(X)
L64XX_CLASS(X) stepperX(L6470_CHAIN_SS_PIN);
#endif
#if AXIS_IS_L64XX(X2)
L64XX_CLASS(X2) stepperX2(L6470_CHAIN_SS_PIN);
#endif
#if AXIS_IS_L64XX(Y)
L64XX_CLASS(Y) stepperY(L6470_CHAIN_SS_PIN);
#endif
#if AXIS_IS_L64XX(Y2)
L64XX_CLASS(Y2) stepperY2(L6470_CHAIN_SS_PIN);
#endif
#if AXIS_IS_L64XX(Z)
L64XX_CLASS(Z) stepperZ(L6470_CHAIN_SS_PIN);
#endif
#if AXIS_IS_L64XX(Z2)
L64XX_CLASS(Z2) stepperZ2(L6470_CHAIN_SS_PIN);
#endif
#if AXIS_IS_L64XX(Z3)
L64XX_CLASS(Z3) stepperZ3(L6470_CHAIN_SS_PIN);
#endif
#if AXIS_IS_L64XX(Z4)
L64XX_CLASS(Z4) stepperZ4(L6470_CHAIN_SS_PIN);
#endif
#if AXIS_IS_L64XX(E0)
L64XX_CLASS(E0) stepperE0(L6470_CHAIN_SS_PIN);
#endif
#if AXIS_IS_L64XX(E1)
L64XX_CLASS(E1) stepperE1(L6470_CHAIN_SS_PIN);
#endif
#if AXIS_IS_L64XX(E2)
L64XX_CLASS(E2) stepperE2(L6470_CHAIN_SS_PIN);
#endif
#if AXIS_IS_L64XX(E3)
L64XX_CLASS(E3) stepperE3(L6470_CHAIN_SS_PIN);
#endif
#if AXIS_IS_L64XX(E4)
L64XX_CLASS(E4) stepperE4(L6470_CHAIN_SS_PIN);
#endif
#if AXIS_IS_L64XX(E5)
L64XX_CLASS(E5) stepperE5(L6470_CHAIN_SS_PIN);
#endif
#if AXIS_IS_L64XX(E6)
L64XX_CLASS(E6) stepperE6(L6470_CHAIN_SS_PIN);
#endif
#if AXIS_IS_L64XX(E7)
L64XX_CLASS(E7) stepperE7(L6470_CHAIN_SS_PIN);
#endif
// Not using L64XX class init method because it
// briefly sends power to the steppers
inline void L6470_init_chip(L64XX &st, const int ms, const int oc, const int sc, const int mv, const int slew_rate) {
st.set_handlers(L64xxManager.spi_init, L64xxManager.transfer_single, L64xxManager.transfer_chain); // specify which external SPI routines to use
switch (st.L6470_status_layout) {
case L6470_STATUS_LAYOUT: {
st.resetDev();
st.softFree();
st.SetParam(st.L64XX_CONFIG, CONFIG_PWM_DIV_1 | CONFIG_PWM_MUL_2 | CONFIG_OC_SD_DISABLE | CONFIG_VS_COMP_DISABLE | CONFIG_SW_HARD_STOP | CONFIG_INT_16MHZ);
st.SetParam(L6470_KVAL_RUN, 0xFF);
st.SetParam(L6470_KVAL_ACC, 0xFF);
st.SetParam(L6470_KVAL_DEC, 0xFF);
st.setMicroSteps(ms);
st.setOverCurrent(oc);
st.setStallCurrent(sc);
st.SetParam(L6470_KVAL_HOLD, mv);
st.SetParam(L6470_ABS_POS, 0);
uint32_t config_temp = st.GetParam(st.L64XX_CONFIG);
config_temp &= ~CONFIG_POW_SR;
switch (slew_rate) {
case 0: st.SetParam(st.L64XX_CONFIG, config_temp | CONFIG_SR_75V_us); break;
default:
case 1: st.SetParam(st.L64XX_CONFIG, config_temp | CONFIG_SR_110V_us); break;
case 3:
case 2: st.SetParam(st.L64XX_CONFIG, config_temp | CONFIG_SR_260V_us); break;
}
st.getStatus();
st.getStatus();
break;
}
case L6474_STATUS_LAYOUT: {
st.free();
//st.SetParam(st.L64XX_CONFIG, CONFIG_PWM_DIV_1 | CONFIG_PWM_MUL_2 | CONFIG_OC_SD_DISABLE | CONFIG_VS_COMP_DISABLE | CONFIG_SW_HARD_STOP | CONFIG_INT_16MHZ);
//st.SetParam(L6474_TVAL, 0xFF);
st.setMicroSteps(ms);
st.setOverCurrent(oc);
st.setTVALCurrent(sc);
st.SetParam(L6470_ABS_POS, 0);
uint32_t config_temp = st.GetParam(st.L64XX_CONFIG);
config_temp &= ~CONFIG_POW_SR & ~CONFIG_EN_TQREG; // clear out slew rate and set current to be controlled by TVAL register
switch (slew_rate) {
case 0: st.SetParam(st.L64XX_CONFIG, config_temp | CONFIG_SR_75V_us); break;
default:
case 1: st.SetParam(st.L64XX_CONFIG, config_temp | CONFIG_SR_110V_us); break;
case 3:
case 2: st.SetParam(st.L64XX_CONFIG, config_temp | CONFIG_SR_260V_us); break;
//case 0: st.SetParam(st.L64XX_CONFIG, 0x2E88 | CONFIG_EN_TQREG | CONFIG_SR_75V_us); break;
//default:
//case 1: st.SetParam(st.L64XX_CONFIG, 0x2E88 | CONFIG_EN_TQREG | CONFIG_SR_110V_us); break;
//case 3:
//case 2: st.SetParam(st.L64XX_CONFIG, 0x2E88 | CONFIG_EN_TQREG | CONFIG_SR_260V_us); break;
//case 0: st.SetParam(st.L64XX_CONFIG, 0x2E88 ); break;
//default:
//case 1: st.SetParam(st.L64XX_CONFIG, 0x2E88 ); break;
//case 3:
//case 2: st.SetParam(st.L64XX_CONFIG, 0x2E88 ); break;
}
st.getStatus();
st.getStatus();
break;
}
case L6480_STATUS_LAYOUT: {
st.resetDev();
st.softFree();
st.SetParam(st.L64XX_CONFIG, CONFIG_PWM_DIV_1 | CONFIG_PWM_MUL_2 | CONFIG_OC_SD_DISABLE | CONFIG_VS_COMP_DISABLE | CONFIG_SW_HARD_STOP | CONFIG_INT_16MHZ);
st.SetParam(L6470_KVAL_RUN, 0xFF);
st.SetParam(L6470_KVAL_ACC, 0xFF);
st.SetParam(L6470_KVAL_DEC, 0xFF);
st.setMicroSteps(ms);
st.setOverCurrent(oc);
st.setStallCurrent(sc);
st.SetParam(+-L6470_KVAL_HOLD, mv);
st.SetParam(L6470_ABS_POS, 0);
st.SetParam(st.L64XX_CONFIG,(st.GetParam(st.L64XX_CONFIG) | PWR_VCC_7_5V));
st.getStatus(); // must clear out status bits before can set slew rate
st.getStatus();
switch (slew_rate) {
case 0: st.SetParam(L6470_GATECFG1, CONFIG1_SR_220V_us); st.SetParam(L6470_GATECFG2, CONFIG2_SR_220V_us); break;
default:
case 1: st.SetParam(L6470_GATECFG1, CONFIG1_SR_400V_us); st.SetParam(L6470_GATECFG2, CONFIG2_SR_400V_us); break;
case 2: st.SetParam(L6470_GATECFG1, CONFIG1_SR_520V_us); st.SetParam(L6470_GATECFG2, CONFIG2_SR_520V_us); break;
case 3: st.SetParam(L6470_GATECFG1, CONFIG1_SR_980V_us); st.SetParam(L6470_GATECFG2, CONFIG2_SR_980V_us); break;
}
break;
}
}
}
#define L6470_INIT_CHIP(Q) L6470_init_chip(stepper##Q, Q##_MICROSTEPS, Q##_OVERCURRENT, Q##_STALLCURRENT, Q##_MAX_VOLTAGE, Q##_SLEW_RATE)
void L64XX_Marlin::init_to_defaults() {
#if AXIS_IS_L64XX(X)
L6470_INIT_CHIP(X);
#endif
#if AXIS_IS_L64XX(X2)
L6470_INIT_CHIP(X2);
#endif
#if AXIS_IS_L64XX(Y)
L6470_INIT_CHIP(Y);
#endif
#if AXIS_IS_L64XX(Y2)
L6470_INIT_CHIP(Y2);
#endif
#if AXIS_IS_L64XX(Z)
L6470_INIT_CHIP(Z);
#endif
#if AXIS_IS_L64XX(Z2)
L6470_INIT_CHIP(Z2);
#endif
#if AXIS_IS_L64XX(Z3)
L6470_INIT_CHIP(Z3);
#endif
#if AXIS_IS_L64XX(Z4)
L6470_INIT_CHIP(Z4);
#endif
#if AXIS_IS_L64XX(E0)
L6470_INIT_CHIP(E0);
#endif
#if AXIS_IS_L64XX(E1)
L6470_INIT_CHIP(E1);
#endif
#if AXIS_IS_L64XX(E2)
L6470_INIT_CHIP(E2);
#endif
#if AXIS_IS_L64XX(E3)
L6470_INIT_CHIP(E3);
#endif
#if AXIS_IS_L64XX(E4)
L6470_INIT_CHIP(E4);
#endif
#if AXIS_IS_L64XX(E5)
L6470_INIT_CHIP(E5);
#endif
#if AXIS_IS_L64XX(E6)
L6470_INIT_CHIP(E6);
#endif
#if AXIS_IS_L64XX(E7)
L6470_INIT_CHIP(E7);
#endif
}
#endif // HAS_L64XX
+364
View File
@@ -0,0 +1,364 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* stepper/L64xx.h
* Stepper driver indirection for L64XX drivers
*/
#include "../../inc/MarlinConfig.h"
#include "../../libs/L64XX/L64XX_Marlin.h"
// Convert option names to L64XX classes
#define CLASS_L6470 L6470
#define CLASS_L6474 L6474
#define CLASS_POWERSTEP01 powerSTEP01
#define __L64XX_CLASS(TYPE) CLASS_##TYPE
#define _L64XX_CLASS(TYPE) __L64XX_CLASS(TYPE)
#define L64XX_CLASS(ST) _L64XX_CLASS(ST##_DRIVER_TYPE)
#define L6474_DIR_WRITE(A,STATE) do{ L64xxManager.dir_commands[A] = dSPIN_L6474_ENABLE; WRITE(A##_DIR_PIN, STATE); }while(0)
#define L64XX_DIR_WRITE(A,STATE) do{ L64xxManager.dir_commands[A] = (STATE) ? dSPIN_STEP_CLOCK_REV : dSPIN_STEP_CLOCK_FWD; }while(0)
// X Stepper
#if AXIS_IS_L64XX(X)
extern L64XX_CLASS(X) stepperX;
#define X_ENABLE_INIT() NOOP
#define X_ENABLE_WRITE(STATE) (STATE ? stepperX.hardStop() : stepperX.free())
#define X_ENABLE_READ() (stepperX.getStatus() & STATUS_HIZ)
#if AXIS_DRIVER_TYPE_X(L6474)
#define X_DIR_INIT() SET_OUTPUT(X_DIR_PIN)
#define X_DIR_WRITE(STATE) L6474_DIR_WRITE(X, STATE)
#define X_DIR_READ() READ(X_DIR_PIN)
#else
#define X_DIR_INIT() NOOP
#define X_DIR_WRITE(STATE) L64XX_DIR_WRITE(X, STATE)
#define X_DIR_READ() (stepper##X.getStatus() & STATUS_DIR);
#if AXIS_DRIVER_TYPE_X(L6470)
#define DISABLE_STEPPER_X() stepperX.free()
#endif
#endif
#endif
// Y Stepper
#if AXIS_IS_L64XX(Y)
extern L64XX_CLASS(Y) stepperY;
#define Y_ENABLE_INIT() NOOP
#define Y_ENABLE_WRITE(STATE) (STATE ? stepperY.hardStop() : stepperY.free())
#define Y_ENABLE_READ() (stepperY.getStatus() & STATUS_HIZ)
#if AXIS_DRIVER_TYPE_Y(L6474)
#define Y_DIR_INIT() SET_OUTPUT(Y_DIR_PIN)
#define Y_DIR_WRITE(STATE) L6474_DIR_WRITE(Y, STATE)
#define Y_DIR_READ() READ(Y_DIR_PIN)
#else
#define Y_DIR_INIT() NOOP
#define Y_DIR_WRITE(STATE) L64XX_DIR_WRITE(Y, STATE)
#define Y_DIR_READ() (stepper##Y.getStatus() & STATUS_DIR);
#if AXIS_DRIVER_TYPE_Y(L6470)
#define DISABLE_STEPPER_Y() stepperY.free()
#endif
#endif
#endif
// Z Stepper
#if AXIS_IS_L64XX(Z)
extern L64XX_CLASS(Z) stepperZ;
#define Z_ENABLE_INIT() NOOP
#define Z_ENABLE_WRITE(STATE) (STATE ? stepperZ.hardStop() : stepperZ.free())
#define Z_ENABLE_READ() (stepperZ.getStatus() & STATUS_HIZ)
#if AXIS_DRIVER_TYPE_Z(L6474)
#define Z_DIR_INIT() SET_OUTPUT(Z_DIR_PIN)
#define Z_DIR_WRITE(STATE) L6474_DIR_WRITE(Z, STATE)
#define Z_DIR_READ() READ(Z_DIR_PIN)
#else
#define Z_DIR_INIT() NOOP
#define Z_DIR_WRITE(STATE) L64XX_DIR_WRITE(Z, STATE)
#define Z_DIR_READ() (stepper##Z.getStatus() & STATUS_DIR);
#if AXIS_DRIVER_TYPE_Z(L6470)
#define DISABLE_STEPPER_Z() stepperZ.free()
#endif
#endif
#endif
// X2 Stepper
#if HAS_X2_ENABLE && AXIS_IS_L64XX(X2)
extern L64XX_CLASS(X2) stepperX2;
#define X2_ENABLE_INIT() NOOP
#define X2_ENABLE_WRITE(STATE) (STATE ? stepperX2.hardStop() : stepperX2.free())
#define X2_ENABLE_READ() (stepperX2.getStatus() & STATUS_HIZ)
#if AXIS_DRIVER_TYPE_X2(L6474)
#define X2_DIR_INIT() SET_OUTPUT(X2_DIR_PIN)
#define X2_DIR_WRITE(STATE) L6474_DIR_WRITE(X2, STATE)
#define X2_DIR_READ() READ(X2_DIR_PIN)
#else
#define X2_DIR_INIT() NOOP
#define X2_DIR_WRITE(STATE) L64XX_DIR_WRITE(X2, STATE)
#define X2_DIR_READ() (stepper##X2.getStatus() & STATUS_DIR);
#endif
#endif
#if AXIS_DRIVER_TYPE_X2(L6470)
#define DISABLE_STEPPER_X2() stepperX2.free()
#endif
// Y2 Stepper
#if HAS_Y2_ENABLE && AXIS_IS_L64XX(Y2)
extern L64XX_CLASS(Y2) stepperY2;
#define Y2_ENABLE_INIT() NOOP
#define Y2_ENABLE_WRITE(STATE) (STATE ? stepperY2.hardStop() : stepperY2.free())
#define Y2_ENABLE_READ() (stepperY2.getStatus() & STATUS_HIZ)
#if AXIS_DRIVER_TYPE_Y2(L6474)
#define Y2_DIR_INIT() SET_OUTPUT(Y2_DIR_PIN)
#define Y2_DIR_WRITE(STATE) L6474_DIR_WRITE(Y2, STATE)
#define Y2_DIR_READ() READ(Y2_DIR_PIN)
#else
#define Y2_DIR_INIT() NOOP
#define Y2_DIR_WRITE(STATE) L64XX_DIR_WRITE(Y2, STATE)
#define Y2_DIR_READ() (stepper##Y2.getStatus() & STATUS_DIR);
#endif
#endif
#if AXIS_DRIVER_TYPE_Y2(L6470)
#define DISABLE_STEPPER_Y2() stepperY2.free()
#endif
// Z2 Stepper
#if HAS_Z2_ENABLE && AXIS_IS_L64XX(Z2)
extern L64XX_CLASS(Z2) stepperZ2;
#define Z2_ENABLE_INIT() NOOP
#define Z2_ENABLE_WRITE(STATE) (STATE ? stepperZ2.hardStop() : stepperZ2.free())
#define Z2_ENABLE_READ() (stepperZ2.getStatus() & STATUS_HIZ)
#if AXIS_DRIVER_TYPE_Z2(L6474)
#define Z2_DIR_INIT() SET_OUTPUT(Z2_DIR_PIN)
#define Z2_DIR_WRITE(STATE) L6474_DIR_WRITE(Z2, STATE)
#define Z2_DIR_READ() READ(Z2_DIR_PIN)
#else
#define Z2_DIR_INIT() NOOP
#define Z2_DIR_WRITE(STATE) L64XX_DIR_WRITE(Z2, STATE)
#define Z2_DIR_READ() (stepper##Z2.getStatus() & STATUS_DIR);
#endif
#endif
#if AXIS_DRIVER_TYPE_Z2(L6470)
#define DISABLE_STEPPER_Z2() stepperZ2.free()
#endif
// Z3 Stepper
#if HAS_Z3_ENABLE && AXIS_IS_L64XX(Z3)
extern L64XX_CLASS(Z3) stepperZ3;
#define Z3_ENABLE_INIT() NOOP
#define Z3_ENABLE_WRITE(STATE) (STATE ? stepperZ3.hardStop() : stepperZ3.free())
#define Z3_ENABLE_READ() (stepperZ3.getStatus() & STATUS_HIZ)
#if AXIS_DRIVER_TYPE_Z3(L6474)
#define Z3_DIR_INIT() SET_OUTPUT(Z3_DIR_PIN)
#define Z3_DIR_WRITE(STATE) L6474_DIR_WRITE(Z3, STATE)
#define Z3_DIR_READ() READ(Z3_DIR_PIN)
#else
#define Z3_DIR_INIT() NOOP
#define Z3_DIR_WRITE(STATE) L64XX_DIR_WRITE(Z3, STATE)
#define Z3_DIR_READ() (stepper##Z3.getStatus() & STATUS_DIR);
#endif
#endif
#if AXIS_DRIVER_TYPE_Z3(L6470)
#define DISABLE_STEPPER_Z3() stepperZ3.free()
#endif
// Z4 Stepper
#if HAS_Z4_ENABLE && AXIS_IS_L64XX(Z4)
extern L64XX_CLASS(Z4) stepperZ4;
#define Z4_ENABLE_INIT() NOOP
#define Z4_ENABLE_WRITE(STATE) (STATE ? stepperZ4.hardStop() : stepperZ4.free())
#define Z4_ENABLE_READ() (stepperZ4.getStatus() & STATUS_HIZ)
#if AXIS_DRIVER_TYPE_Z4(L6474)
#define Z4_DIR_INIT() SET_OUTPUT(Z4_DIR_PIN)
#define Z4_DIR_WRITE(STATE) L6474_DIR_WRITE(Z4, STATE)
#define Z4_DIR_READ() READ(Z4_DIR_PIN)
#else
#define Z4_DIR_INIT() NOOP
#define Z4_DIR_WRITE(STATE) L64XX_DIR_WRITE(Z4, STATE)
#define Z4_DIR_READ() (stepper##Z4.getStatus() & STATUS_DIR);
#endif
#endif
#if AXIS_DRIVER_TYPE_Z4(L6470)
#define DISABLE_STEPPER_Z4() stepperZ4.free()
#endif
// E0 Stepper
#if AXIS_IS_L64XX(E0)
extern L64XX_CLASS(E0) stepperE0;
#define E0_ENABLE_INIT() NOOP
#define E0_ENABLE_WRITE(STATE) (STATE ? stepperE0.hardStop() : stepperE0.free())
#define E0_ENABLE_READ() (stepperE0.getStatus() & STATUS_HIZ)
#if AXIS_DRIVER_TYPE_E0(L6474)
#define E0_DIR_INIT() SET_OUTPUT(E0_DIR_PIN)
#define E0_DIR_WRITE(STATE) L6474_DIR_WRITE(E0, STATE)
#define E0_DIR_READ() READ(E0_DIR_PIN)
#else
#define E0_DIR_INIT() NOOP
#define E0_DIR_WRITE(STATE) L64XX_DIR_WRITE(E0, STATE)
#define E0_DIR_READ() (stepper##E0.getStatus() & STATUS_DIR);
#if AXIS_DRIVER_TYPE_E0(L6470)
#define DISABLE_STEPPER_E0() do{ stepperE0.free(); }while(0)
#endif
#endif
#endif
// E1 Stepper
#if AXIS_IS_L64XX(E1)
extern L64XX_CLASS(E1) stepperE1;
#define E1_ENABLE_INIT() NOOP
#define E1_ENABLE_WRITE(STATE) (STATE ? stepperE1.hardStop() : stepperE1.free())
#define E1_ENABLE_READ() (stepperE1.getStatus() & STATUS_HIZ)
#if AXIS_DRIVER_TYPE_E1(L6474)
#define E1_DIR_INIT() SET_OUTPUT(E1_DIR_PIN)
#define E1_DIR_WRITE(STATE) L6474_DIR_WRITE(E1, STATE)
#define E1_DIR_READ() READ(E1_DIR_PIN)
#else
#define E1_DIR_INIT() NOOP
#define E1_DIR_WRITE(STATE) L64XX_DIR_WRITE(E1, STATE)
#define E1_DIR_READ() (stepper##E1.getStatus() & STATUS_DIR);
#if AXIS_DRIVER_TYPE_E1(L6470)
#define DISABLE_STEPPER_E1() do{ stepperE1.free(); }while(0)
#endif
#endif
#endif
// E2 Stepper
#if AXIS_IS_L64XX(E2)
extern L64XX_CLASS(E2) stepperE2;
#define E2_ENABLE_INIT() NOOP
#define E2_ENABLE_WRITE(STATE) (STATE ? stepperE2.hardStop() : stepperE2.free())
#define E2_ENABLE_READ() (stepperE2.getStatus() & STATUS_HIZ)
#if AXIS_DRIVER_TYPE_E2(L6474)
#define E2_DIR_INIT() SET_OUTPUT(E2_DIR_PIN)
#define E2_DIR_WRITE(STATE) L6474_DIR_WRITE(E2, STATE)
#define E2_DIR_READ() READ(E2_DIR_PIN)
#else
#define E2_DIR_INIT() NOOP
#define E2_DIR_WRITE(STATE) L64XX_DIR_WRITE(E2, STATE)
#define E2_DIR_READ() (stepper##E2.getStatus() & STATUS_DIR);
#if AXIS_DRIVER_TYPE_E2(L6470)
#define DISABLE_STEPPER_E2() do{ stepperE2.free(); }while(0)
#endif
#endif
#endif
// E3 Stepper
#if AXIS_IS_L64XX(E3)
extern L64XX_CLASS(E3) stepperE3;
#define E3_ENABLE_INIT() NOOP
#define E3_ENABLE_WRITE(STATE) (STATE ? stepperE3.hardStop() : stepperE3.free())
#define E3_ENABLE_READ() (stepperE3.getStatus() & STATUS_HIZ)
#if AXIS_DRIVER_TYPE_E3(L6474)
#define E3_DIR_INIT() SET_OUTPUT(E3_DIR_PIN)
#define E3_DIR_WRITE(STATE) L6474_DIR_WRITE(E3, STATE)
#define E3_DIR_READ() READ(E3_DIR_PIN)
#else
#define E3_DIR_INIT() NOOP
#define E3_DIR_WRITE(STATE) L64XX_DIR_WRITE(E3, STATE)
#define E3_DIR_READ() (stepper##E3.getStatus() & STATUS_DIR);
#endif
#endif
// E4 Stepper
#if AXIS_IS_L64XX(E4)
extern L64XX_CLASS(E4) stepperE4;
#define E4_ENABLE_INIT() NOOP
#define E4_ENABLE_WRITE(STATE) (STATE ? stepperE4.hardStop() : stepperE4.free())
#define E4_ENABLE_READ() (stepperE4.getStatus() & STATUS_HIZ)
#if AXIS_DRIVER_TYPE_E4(L6474)
#define E4_DIR_INIT() SET_OUTPUT(E4_DIR_PIN)
#define E4_DIR_WRITE(STATE) L6474_DIR_WRITE(E4, STATE)
#define E4_DIR_READ() READ(E4_DIR_PIN)
#else
#define E4_DIR_INIT() NOOP
#define E4_DIR_WRITE(STATE) L64XX_DIR_WRITE(E4, STATE)
#define E4_DIR_READ() (stepper##E4.getStatus() & STATUS_DIR);
#if AXIS_DRIVER_TYPE_E4(L6470)
#define DISABLE_STEPPER_E4() do{ stepperE4.free(); }while(0)
#endif
#endif
#endif
// E5 Stepper
#if AXIS_IS_L64XX(E5)
extern L64XX_CLASS(E5) stepperE5;
#define E5_ENABLE_INIT() NOOP
#define E5_ENABLE_WRITE(STATE) (STATE ? stepperE5.hardStop() : stepperE5.free())
#define E5_ENABLE_READ() (stepperE5.getStatus() & STATUS_HIZ)
#if AXIS_DRIVER_TYPE_E5(L6474)
#define E5_DIR_INIT() SET_OUTPUT(E5_DIR_PIN)
#define E5_DIR_WRITE(STATE) L6474_DIR_WRITE(E5, STATE)
#define E5_DIR_READ() READ(E5_DIR_PIN)
#else
#define E5_DIR_INIT() NOOP
#define E5_DIR_WRITE(STATE) L64XX_DIR_WRITE(E5, STATE)
#define E5_DIR_READ() (stepper##E5.getStatus() & STATUS_DIR);
#if AXIS_DRIVER_TYPE_E5(L6470)
#define DISABLE_STEPPER_E5() do{ stepperE5.free(); }while(0)
#endif
#endif
#endif
// E6 Stepper
#if AXIS_IS_L64XX(E6)
extern L64XX_CLASS(E6) stepperE6;
#define E6_ENABLE_INIT() NOOP
#define E6_ENABLE_WRITE(STATE) (STATE ? stepperE6.hardStop() : stepperE6.free())
#define E6_ENABLE_READ() (stepperE6.getStatus() & STATUS_HIZ)
#if AXIS_DRIVER_TYPE_E6(L6474)
#define E6_DIR_INIT() SET_OUTPUT(E6_DIR_PIN)
#define E6_DIR_WRITE(STATE) L6474_DIR_WRITE(E6, STATE)
#define E6_DIR_READ() READ(E6_DIR_PIN)
#else
#define E6_DIR_INIT() NOOP
#define E6_DIR_WRITE(STATE) L64XX_DIR_WRITE(E6, STATE)
#define E6_DIR_READ() (stepper##E6.getStatus() & STATUS_DIR);
#if AXIS_DRIVER_TYPE_E6(L6470)
#define DISABLE_STEPPER_E6() do{ stepperE6.free(); }while(0)
#endif
#endif
#endif
// E7 Stepper
#if AXIS_IS_L64XX(E7)
extern L64XX_CLASS(E7) stepperE7;
#define E7_ENABLE_INIT() NOOP
#define E7_ENABLE_WRITE(STATE) (STATE ? stepperE7.hardStop() : stepperE7.free())
#define E7_ENABLE_READ() (stepperE7.getStatus() & STATUS_HIZ)
#if AXIS_DRIVER_TYPE_E7(L6474)
#define E7_DIR_INIT() SET_OUTPUT(E7_DIR_PIN)
#define E7_DIR_WRITE(STATE) L6474_DIR_WRITE(E7, STATE)
#define E7_DIR_READ() READ(E7_DIR_PIN)
#else
#define E7_DIR_INIT() NOOP
#define E7_DIR_WRITE(STATE) L64XX_DIR_WRITE(E7, STATE)
#define E7_DIR_READ() (stepper##E7.getStatus() & STATUS_DIR);
#if AXIS_DRIVER_TYPE_E7(L6470)
#define DISABLE_STEPPER_E7() do{ stepperE7.free(); }while(0)
#endif
#endif
#endif
+144
View File
@@ -0,0 +1,144 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
/**
* stepper/TMC26X.cpp
* Stepper driver indirection for TMC26X drivers
*/
#include "../../inc/MarlinConfig.h"
//
// TMC26X Driver objects and inits
//
#if HAS_TMC26X
#include "TMC26X.h"
#define _TMC26X_DEFINE(ST) TMC26XStepper stepper##ST(200, ST##_CS_PIN, ST##_STEP_PIN, ST##_DIR_PIN, ST##_MAX_CURRENT, ST##_SENSE_RESISTOR)
#if AXIS_DRIVER_TYPE_X(TMC26X)
_TMC26X_DEFINE(X);
#endif
#if AXIS_DRIVER_TYPE_X2(TMC26X)
_TMC26X_DEFINE(X2);
#endif
#if AXIS_DRIVER_TYPE_Y(TMC26X)
_TMC26X_DEFINE(Y);
#endif
#if AXIS_DRIVER_TYPE_Y2(TMC26X)
_TMC26X_DEFINE(Y2);
#endif
#if AXIS_DRIVER_TYPE_Z(TMC26X)
_TMC26X_DEFINE(Z);
#endif
#if AXIS_DRIVER_TYPE_Z2(TMC26X)
_TMC26X_DEFINE(Z2);
#endif
#if AXIS_DRIVER_TYPE_Z3(TMC26X)
_TMC26X_DEFINE(Z3);
#endif
#if AXIS_DRIVER_TYPE_Z4(TMC26X)
_TMC26X_DEFINE(Z4);
#endif
#if AXIS_DRIVER_TYPE_E0(TMC26X)
_TMC26X_DEFINE(E0);
#endif
#if AXIS_DRIVER_TYPE_E1(TMC26X)
_TMC26X_DEFINE(E1);
#endif
#if AXIS_DRIVER_TYPE_E2(TMC26X)
_TMC26X_DEFINE(E2);
#endif
#if AXIS_DRIVER_TYPE_E3(TMC26X)
_TMC26X_DEFINE(E3);
#endif
#if AXIS_DRIVER_TYPE_E4(TMC26X)
_TMC26X_DEFINE(E4);
#endif
#if AXIS_DRIVER_TYPE_E5(TMC26X)
_TMC26X_DEFINE(E5);
#endif
#if AXIS_DRIVER_TYPE_E6(TMC26X)
_TMC26X_DEFINE(E6);
#endif
#if AXIS_DRIVER_TYPE_E7(TMC26X)
_TMC26X_DEFINE(E7);
#endif
#define _TMC26X_INIT(A) do{ \
stepper##A.setMicrosteps(A##_MICROSTEPS); \
stepper##A.start(); \
}while(0)
void tmc26x_init_to_defaults() {
#if AXIS_DRIVER_TYPE_X(TMC26X)
_TMC26X_INIT(X);
#endif
#if AXIS_DRIVER_TYPE_X2(TMC26X)
_TMC26X_INIT(X2);
#endif
#if AXIS_DRIVER_TYPE_Y(TMC26X)
_TMC26X_INIT(Y);
#endif
#if AXIS_DRIVER_TYPE_Y2(TMC26X)
_TMC26X_INIT(Y2);
#endif
#if AXIS_DRIVER_TYPE_Z(TMC26X)
_TMC26X_INIT(Z);
#endif
#if AXIS_DRIVER_TYPE_Z2(TMC26X)
_TMC26X_INIT(Z2);
#endif
#if AXIS_DRIVER_TYPE_Z3(TMC26X)
_TMC26X_INIT(Z3);
#endif
#if AXIS_DRIVER_TYPE_Z4(TMC26X)
_TMC26X_INIT(Z4);
#endif
#if AXIS_DRIVER_TYPE_E0(TMC26X)
_TMC26X_INIT(E0);
#endif
#if AXIS_DRIVER_TYPE_E1(TMC26X)
_TMC26X_INIT(E1);
#endif
#if AXIS_DRIVER_TYPE_E2(TMC26X)
_TMC26X_INIT(E2);
#endif
#if AXIS_DRIVER_TYPE_E3(TMC26X)
_TMC26X_INIT(E3);
#endif
#if AXIS_DRIVER_TYPE_E4(TMC26X)
_TMC26X_INIT(E4);
#endif
#if AXIS_DRIVER_TYPE_E5(TMC26X)
_TMC26X_INIT(E5);
#endif
#if AXIS_DRIVER_TYPE_E6(TMC26X)
_TMC26X_INIT(E6);
#endif
#if AXIS_DRIVER_TYPE_E7(TMC26X)
_TMC26X_INIT(E7);
#endif
}
#endif // HAS_TMC26X
+164
View File
@@ -0,0 +1,164 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* stepper/TMC26X.h
* Stepper driver indirection for TMC26X drivers
*/
#include "../../inc/MarlinConfig.h"
// TMC26X drivers have STEP/DIR on normal pins, but ENABLE via SPI
#include <SPI.h>
#include <TMC26XStepper.h>
void tmc26x_init_to_defaults();
// X Stepper
#if AXIS_DRIVER_TYPE_X(TMC26X)
extern TMC26XStepper stepperX;
#define X_ENABLE_INIT() NOOP
#define X_ENABLE_WRITE(STATE) stepperX.setEnabled(STATE)
#define X_ENABLE_READ() stepperX.isEnabled()
#endif
// Y Stepper
#if AXIS_DRIVER_TYPE_Y(TMC26X)
extern TMC26XStepper stepperY;
#define Y_ENABLE_INIT() NOOP
#define Y_ENABLE_WRITE(STATE) stepperY.setEnabled(STATE)
#define Y_ENABLE_READ() stepperY.isEnabled()
#endif
// Z Stepper
#if AXIS_DRIVER_TYPE_Z(TMC26X)
extern TMC26XStepper stepperZ;
#define Z_ENABLE_INIT() NOOP
#define Z_ENABLE_WRITE(STATE) stepperZ.setEnabled(STATE)
#define Z_ENABLE_READ() stepperZ.isEnabled()
#endif
// X2 Stepper
#if HAS_X2_ENABLE && AXIS_DRIVER_TYPE_X2(TMC26X)
extern TMC26XStepper stepperX2;
#define X2_ENABLE_INIT() NOOP
#define X2_ENABLE_WRITE(STATE) stepperX2.setEnabled(STATE)
#define X2_ENABLE_READ() stepperX2.isEnabled()
#endif
// Y2 Stepper
#if HAS_Y2_ENABLE && AXIS_DRIVER_TYPE_Y2(TMC26X)
extern TMC26XStepper stepperY2;
#define Y2_ENABLE_INIT() NOOP
#define Y2_ENABLE_WRITE(STATE) stepperY2.setEnabled(STATE)
#define Y2_ENABLE_READ() stepperY2.isEnabled()
#endif
// Z2 Stepper
#if HAS_Z2_ENABLE && AXIS_DRIVER_TYPE_Z2(TMC26X)
extern TMC26XStepper stepperZ2;
#define Z2_ENABLE_INIT() NOOP
#define Z2_ENABLE_WRITE(STATE) stepperZ2.setEnabled(STATE)
#define Z2_ENABLE_READ() stepperZ2.isEnabled()
#endif
// Z3 Stepper
#if HAS_Z3_ENABLE && AXIS_DRIVER_TYPE_Z3(TMC26X)
extern TMC26XStepper stepperZ3;
#define Z3_ENABLE_INIT() NOOP
#define Z3_ENABLE_WRITE(STATE) stepperZ3.setEnabled(STATE)
#define Z3_ENABLE_READ() stepperZ3.isEnabled()
#endif
// Z4 Stepper
#if HAS_Z4_ENABLE && AXIS_DRIVER_TYPE_Z4(TMC26X)
extern TMC26XStepper stepperZ4;
#define Z4_ENABLE_INIT() NOOP
#define Z4_ENABLE_WRITE(STATE) stepperZ4.setEnabled(STATE)
#define Z4_ENABLE_READ() stepperZ4.isEnabled()
#endif
// E0 Stepper
#if AXIS_DRIVER_TYPE_E0(TMC26X)
extern TMC26XStepper stepperE0;
#define E0_ENABLE_INIT() NOOP
#define E0_ENABLE_WRITE(STATE) stepperE0.setEnabled(STATE)
#define E0_ENABLE_READ() stepperE0.isEnabled()
#endif
// E1 Stepper
#if AXIS_DRIVER_TYPE_E1(TMC26X)
extern TMC26XStepper stepperE1;
#define E1_ENABLE_INIT() NOOP
#define E1_ENABLE_WRITE(STATE) stepperE1.setEnabled(STATE)
#define E1_ENABLE_READ() stepperE1.isEnabled()
#endif
// E2 Stepper
#if AXIS_DRIVER_TYPE_E2(TMC26X)
extern TMC26XStepper stepperE2;
#define E2_ENABLE_INIT() NOOP
#define E2_ENABLE_WRITE(STATE) stepperE2.setEnabled(STATE)
#define E2_ENABLE_READ() stepperE2.isEnabled()
#endif
// E3 Stepper
#if AXIS_DRIVER_TYPE_E3(TMC26X)
extern TMC26XStepper stepperE3;
#define E3_ENABLE_INIT() NOOP
#define E3_ENABLE_WRITE(STATE) stepperE3.setEnabled(STATE)
#define E3_ENABLE_READ() stepperE3.isEnabled()
#endif
// E4 Stepper
#if AXIS_DRIVER_TYPE_E4(TMC26X)
extern TMC26XStepper stepperE4;
#define E4_ENABLE_INIT() NOOP
#define E4_ENABLE_WRITE(STATE) stepperE4.setEnabled(STATE)
#define E4_ENABLE_READ() stepperE4.isEnabled()
#endif
// E5 Stepper
#if AXIS_DRIVER_TYPE_E5(TMC26X)
extern TMC26XStepper stepperE5;
#define E5_ENABLE_INIT() NOOP
#define E5_ENABLE_WRITE(STATE) stepperE5.setEnabled(STATE)
#define E5_ENABLE_READ() stepperE5.isEnabled()
#endif
// E6 Stepper
#if AXIS_DRIVER_TYPE_E6(TMC26X)
extern TMC26XStepper stepperE6;
#define E6_ENABLE_INIT() NOOP
#define E6_ENABLE_WRITE(STATE) stepperE6.setEnabled(STATE)
#define E6_ENABLE_READ() stepperE6.isEnabled()
#endif
// E7 Stepper
#if AXIS_DRIVER_TYPE_E7(TMC26X)
extern TMC26XStepper stepperE7;
#define E7_ENABLE_INIT() NOOP
#define E7_ENABLE_WRITE(STATE) stepperE7.setEnabled(STATE)
#define E7_ENABLE_READ() stepperE7.isEnabled()
#endif
+50
View File
@@ -0,0 +1,50 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
/**
* stepper/indirection.cpp
*
* Stepper motor driver indirection to allow some stepper functions to
* be done via SPI/I2c instead of direct pin manipulation.
*
* Copyright (c) 2015 Dominik Wenger
*/
#include "../../inc/MarlinConfig.h"
#include "indirection.h"
void restore_stepper_drivers() {
TERN_(HAS_TRINAMIC_CONFIG, restore_trinamic_drivers());
}
void reset_stepper_drivers() {
#if HAS_DRIVER(TMC26X)
tmc26x_init_to_defaults();
#endif
TERN_(HAS_L64XX, L64xxManager.init_to_defaults());
TERN_(HAS_TRINAMIC_CONFIG, reset_trinamic_drivers());
}
#if ENABLED(SOFTWARE_DRIVER_ENABLE)
// Flags to optimize XYZ Enabled state
xyz_bool_t axis_sw_enabled; // = { false, false, false }
#endif
File diff suppressed because it is too large Load Diff
+880
View File
@@ -0,0 +1,880 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
/**
* stepper/trinamic.cpp
* Stepper driver indirection for Trinamic
*/
#include "../../inc/MarlinConfig.h"
#if HAS_TRINAMIC_CONFIG
#include "trinamic.h"
#include "../stepper.h"
#include <HardwareSerial.h>
#include <SPI.h>
enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E };
#define TMC_INIT(ST, STEALTH_INDEX) tmc_init(stepper##ST, ST##_CURRENT, ST##_MICROSTEPS, ST##_HYBRID_THRESHOLD, stealthchop_by_axis[STEALTH_INDEX], chopper_timing_##ST, ST##_INTERPOLATE,ST##_HOLD_MULTIPLIER)
// IC = TMC model number
// ST = Stepper object letter
// L = Label characters
// AI = Axis Enum Index
// SWHW = SW/SH UART selection
#if ENABLED(TMC_USE_SW_SPI)
#define __TMC_SPI_DEFINE(IC, ST, L, AI) TMCMarlin<IC##Stepper, L, AI> stepper##ST(ST##_CS_PIN, float(ST##_RSENSE), TMC_SW_MOSI, TMC_SW_MISO, TMC_SW_SCK, ST##_CHAIN_POS)
#else
#define __TMC_SPI_DEFINE(IC, ST, L, AI) TMCMarlin<IC##Stepper, L, AI> stepper##ST(ST##_CS_PIN, float(ST##_RSENSE), ST##_CHAIN_POS)
#endif
#if ENABLED(TMC_SERIAL_MULTIPLEXER)
#define TMC_UART_HW_DEFINE(IC, ST, L, AI) TMCMarlin<IC##Stepper, L, AI> stepper##ST(&ST##_HARDWARE_SERIAL, float(ST##_RSENSE), ST##_SLAVE_ADDRESS, SERIAL_MUL_PIN1, SERIAL_MUL_PIN2)
#else
#define TMC_UART_HW_DEFINE(IC, ST, L, AI) TMCMarlin<IC##Stepper, L, AI> stepper##ST(&ST##_HARDWARE_SERIAL, float(ST##_RSENSE), ST##_SLAVE_ADDRESS)
#endif
#define TMC_UART_SW_DEFINE(IC, ST, L, AI) TMCMarlin<IC##Stepper, L, AI> stepper##ST(ST##_SERIAL_RX_PIN, ST##_SERIAL_TX_PIN, float(ST##_RSENSE), ST##_SLAVE_ADDRESS)
#define _TMC_SPI_DEFINE(IC, ST, AI) __TMC_SPI_DEFINE(IC, ST, TMC_##ST##_LABEL, AI)
#define TMC_SPI_DEFINE(ST, AI) _TMC_SPI_DEFINE(ST##_DRIVER_TYPE, ST, AI##_AXIS)
#define _TMC_UART_DEFINE(SWHW, IC, ST, AI) TMC_UART_##SWHW##_DEFINE(IC, ST, TMC_##ST##_LABEL, AI)
#define TMC_UART_DEFINE(SWHW, ST, AI) _TMC_UART_DEFINE(SWHW, ST##_DRIVER_TYPE, ST, AI##_AXIS)
#if ENABLED(DISTINCT_E_FACTORS)
#define TMC_SPI_DEFINE_E(AI) TMC_SPI_DEFINE(E##AI, E##AI)
#define TMC_UART_DEFINE_E(SWHW, AI) TMC_UART_DEFINE(SWHW, E##AI, E##AI)
#else
#define TMC_SPI_DEFINE_E(AI) TMC_SPI_DEFINE(E##AI, E)
#define TMC_UART_DEFINE_E(SWHW, AI) TMC_UART_DEFINE(SWHW, E##AI, E)
#endif
// Stepper objects of TMC2130/TMC2160/TMC2660/TMC5130/TMC5160 steppers used
#if AXIS_HAS_SPI(X)
TMC_SPI_DEFINE(X, X);
#endif
#if AXIS_HAS_SPI(X2)
TMC_SPI_DEFINE(X2, X);
#endif
#if AXIS_HAS_SPI(Y)
TMC_SPI_DEFINE(Y, Y);
#endif
#if AXIS_HAS_SPI(Y2)
TMC_SPI_DEFINE(Y2, Y);
#endif
#if AXIS_HAS_SPI(Z)
TMC_SPI_DEFINE(Z, Z);
#endif
#if AXIS_HAS_SPI(Z2)
TMC_SPI_DEFINE(Z2, Z);
#endif
#if AXIS_HAS_SPI(Z3)
TMC_SPI_DEFINE(Z3, Z);
#endif
#if AXIS_HAS_SPI(Z4)
TMC_SPI_DEFINE(Z4, Z);
#endif
#if AXIS_HAS_SPI(E0)
TMC_SPI_DEFINE_E(0);
#endif
#if AXIS_HAS_SPI(E1)
TMC_SPI_DEFINE_E(1);
#endif
#if AXIS_HAS_SPI(E2)
TMC_SPI_DEFINE_E(2);
#endif
#if AXIS_HAS_SPI(E3)
TMC_SPI_DEFINE_E(3);
#endif
#if AXIS_HAS_SPI(E4)
TMC_SPI_DEFINE_E(4);
#endif
#if AXIS_HAS_SPI(E5)
TMC_SPI_DEFINE_E(5);
#endif
#if AXIS_HAS_SPI(E6)
TMC_SPI_DEFINE_E(6);
#endif
#if AXIS_HAS_SPI(E7)
TMC_SPI_DEFINE_E(7);
#endif
#ifndef TMC_BAUD_RATE
// Reduce baud rate for boards not already overriding TMC_BAUD_RATE for software serial.
// Testing has shown that 115200 is not 100% reliable on AVR platforms, occasionally
// failing to read status properly. 32-bit platforms typically define an even lower
// TMC_BAUD_RATE, due to differences in how SoftwareSerial libraries work on different
// platforms.
#define TMC_BAUD_RATE TERN(HAS_TMC_SW_SERIAL, 57600, 115200)
#endif
#if HAS_DRIVER(TMC2130)
template<char AXIS_LETTER, char DRIVER_ID, AxisEnum AXIS_ID>
void tmc_init(TMCMarlin<TMC2130Stepper, AXIS_LETTER, DRIVER_ID, AXIS_ID> &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate) {
st.begin();
CHOPCONF_t chopconf{0};
chopconf.tbl = 0b01;
chopconf.toff = chop_init.toff;
chopconf.intpol = interpolate;
chopconf.hend = chop_init.hend + 3;
chopconf.hstrt = chop_init.hstrt - 1;
TERN_(SQUARE_WAVE_STEPPING, chopconf.dedge = true);
st.CHOPCONF(chopconf.sr);
st.rms_current(mA, HOLD_MULTIPLIER);
st.microsteps(microsteps);
st.iholddelay(10);
st.TPOWERDOWN(128); // ~2s until driver lowers to hold current
st.en_pwm_mode(stealth);
st.stored.stealthChop_enabled = stealth;
PWMCONF_t pwmconf{0};
pwmconf.pwm_freq = 0b01; // f_pwm = 2/683 f_clk
pwmconf.pwm_autoscale = true;
pwmconf.pwm_grad = 5;
pwmconf.pwm_ampl = 180;
st.PWMCONF(pwmconf.sr);
TERN(HYBRID_THRESHOLD, st.set_pwm_thrs(hyb_thrs), UNUSED(hyb_thrs));
st.GSTAT(); // Clear GSTAT
}
#endif // TMC2130
#if HAS_DRIVER(TMC2160)
template<char AXIS_LETTER, char DRIVER_ID, AxisEnum AXIS_ID>
void tmc_init(TMCMarlin<TMC2160Stepper, AXIS_LETTER, DRIVER_ID, AXIS_ID> &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate) {
st.begin();
CHOPCONF_t chopconf{0};
chopconf.tbl = 0b01;
chopconf.toff = chop_init.toff;
chopconf.intpol = interpolate;
chopconf.hend = chop_init.hend + 3;
chopconf.hstrt = chop_init.hstrt - 1;
TERN_(SQUARE_WAVE_STEPPING, chopconf.dedge = true);
st.CHOPCONF(chopconf.sr);
st.rms_current(mA, HOLD_MULTIPLIER);
st.microsteps(microsteps);
st.iholddelay(10);
st.TPOWERDOWN(128); // ~2s until driver lowers to hold current
st.en_pwm_mode(stealth);
st.stored.stealthChop_enabled = stealth;
TMC2160_n::PWMCONF_t pwmconf{0};
pwmconf.pwm_lim = 12;
pwmconf.pwm_reg = 8;
pwmconf.pwm_autograd = true;
pwmconf.pwm_autoscale = true;
pwmconf.pwm_freq = 0b01;
pwmconf.pwm_grad = 14;
pwmconf.pwm_ofs = 36;
st.PWMCONF(pwmconf.sr);
TERN(HYBRID_THRESHOLD, st.set_pwm_thrs(hyb_thrs), UNUSED(hyb_thrs));
st.GSTAT(); // Clear GSTAT
}
#endif // TMC2160
//
// TMC2208/2209 Driver objects and inits
//
#if HAS_TMC220x
#if AXIS_HAS_UART(X)
#ifdef X_HARDWARE_SERIAL
TMC_UART_DEFINE(HW, X, X);
#define X_HAS_HW_SERIAL 1
#else
TMC_UART_DEFINE(SW, X, X);
#define X_HAS_SW_SERIAL 1
#endif
#endif
#if AXIS_HAS_UART(X2)
#ifdef X2_HARDWARE_SERIAL
TMC_UART_DEFINE(HW, X2, X);
#define X2_HAS_HW_SERIAL 1
#else
TMC_UART_DEFINE(SW, X2, X);
#define X2_HAS_SW_SERIAL 1
#endif
#endif
#if AXIS_HAS_UART(Y)
#ifdef Y_HARDWARE_SERIAL
TMC_UART_DEFINE(HW, Y, Y);
#define Y_HAS_HW_SERIAL 1
#else
TMC_UART_DEFINE(SW, Y, Y);
#define Y_HAS_SW_SERIAL 1
#endif
#endif
#if AXIS_HAS_UART(Y2)
#ifdef Y2_HARDWARE_SERIAL
TMC_UART_DEFINE(HW, Y2, Y);
#define Y2_HAS_HW_SERIAL 1
#else
TMC_UART_DEFINE(SW, Y2, Y);
#define Y2_HAS_SW_SERIAL 1
#endif
#endif
#if AXIS_HAS_UART(Z)
#ifdef Z_HARDWARE_SERIAL
TMC_UART_DEFINE(HW, Z, Z);
#define Z_HAS_HW_SERIAL 1
#else
TMC_UART_DEFINE(SW, Z, Z);
#define Z_HAS_SW_SERIAL 1
#endif
#endif
#if AXIS_HAS_UART(Z2)
#ifdef Z2_HARDWARE_SERIAL
TMC_UART_DEFINE(HW, Z2, Z);
#define Z2_HAS_HW_SERIAL 1
#else
TMC_UART_DEFINE(SW, Z2, Z);
#define Z2_HAS_SW_SERIAL 1
#endif
#endif
#if AXIS_HAS_UART(Z3)
#ifdef Z3_HARDWARE_SERIAL
TMC_UART_DEFINE(HW, Z3, Z);
#define Z3_HAS_HW_SERIAL 1
#else
TMC_UART_DEFINE(SW, Z3, Z);
#define Z3_HAS_SW_SERIAL 1
#endif
#endif
#if AXIS_HAS_UART(Z4)
#ifdef Z4_HARDWARE_SERIAL
TMC_UART_DEFINE(HW, Z4, Z);
#define Z4_HAS_HW_SERIAL 1
#else
TMC_UART_DEFINE(SW, Z4, Z);
#define Z4_HAS_SW_SERIAL 1
#endif
#endif
#if AXIS_HAS_UART(E0)
#ifdef E0_HARDWARE_SERIAL
TMC_UART_DEFINE_E(HW, 0);
#define E0_HAS_HW_SERIAL 1
#else
TMC_UART_DEFINE_E(SW, 0);
#define E0_HAS_SW_SERIAL 1
#endif
#endif
#if AXIS_HAS_UART(E1)
#ifdef E1_HARDWARE_SERIAL
TMC_UART_DEFINE_E(HW, 1);
#define E1_HAS_HW_SERIAL 1
#else
TMC_UART_DEFINE_E(SW, 1);
#define E1_HAS_SW_SERIAL 1
#endif
#endif
#if AXIS_HAS_UART(E2)
#ifdef E2_HARDWARE_SERIAL
TMC_UART_DEFINE_E(HW, 2);
#define E2_HAS_HW_SERIAL 1
#else
TMC_UART_DEFINE_E(SW, 2);
#define E2_HAS_SW_SERIAL 1
#endif
#endif
#if AXIS_HAS_UART(E3)
#ifdef E3_HARDWARE_SERIAL
TMC_UART_DEFINE_E(HW, 3);
#define E3_HAS_HW_SERIAL 1
#else
TMC_UART_DEFINE_E(SW, 3);
#define E3_HAS_SW_SERIAL 1
#endif
#endif
#if AXIS_HAS_UART(E4)
#ifdef E4_HARDWARE_SERIAL
TMC_UART_DEFINE_E(HW, 4);
#define E4_HAS_HW_SERIAL 1
#else
TMC_UART_DEFINE_E(SW, 4);
#define E4_HAS_SW_SERIAL 1
#endif
#endif
#if AXIS_HAS_UART(E5)
#ifdef E5_HARDWARE_SERIAL
TMC_UART_DEFINE_E(HW, 5);
#define E5_HAS_HW_SERIAL 1
#else
TMC_UART_DEFINE_E(SW, 5);
#define E5_HAS_SW_SERIAL 1
#endif
#endif
#if AXIS_HAS_UART(E6)
#ifdef E6_HARDWARE_SERIAL
TMC_UART_DEFINE_E(HW, 6);
#define E6_HAS_HW_SERIAL 1
#else
TMC_UART_DEFINE_E(SW, 6);
#define E6_HAS_SW_SERIAL 1
#endif
#endif
#if AXIS_HAS_UART(E7)
#ifdef E7_HARDWARE_SERIAL
TMC_UART_DEFINE_E(HW, 7);
#define E7_HAS_HW_SERIAL 1
#else
TMC_UART_DEFINE_E(SW, 7);
#define E7_HAS_SW_SERIAL 1
#endif
#endif
enum TMCAxis : uint8_t { X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7, TOTAL };
void tmc_serial_begin() {
#if HAS_TMC_HW_SERIAL
struct {
const void *ptr[TMCAxis::TOTAL];
bool began(const TMCAxis a, const void * const p) {
LOOP_L_N(i, a) if (p == ptr[i]) return true;
ptr[a] = p; return false;
};
} sp_helper;
#define HW_SERIAL_BEGIN(A) do{ if (!sp_helper.began(TMCAxis::A, &A##_HARDWARE_SERIAL)) \
A##_HARDWARE_SERIAL.begin(TMC_BAUD_RATE); }while(0)
#endif
#if AXIS_HAS_UART(X)
#ifdef X_HARDWARE_SERIAL
HW_SERIAL_BEGIN(X);
#else
stepperX.beginSerial(TMC_BAUD_RATE);
#endif
#endif
#if AXIS_HAS_UART(X2)
#ifdef X2_HARDWARE_SERIAL
HW_SERIAL_BEGIN(X2);
#else
stepperX2.beginSerial(TMC_BAUD_RATE);
#endif
#endif
#if AXIS_HAS_UART(Y)
#ifdef Y_HARDWARE_SERIAL
HW_SERIAL_BEGIN(Y);
#else
stepperY.beginSerial(TMC_BAUD_RATE);
#endif
#endif
#if AXIS_HAS_UART(Y2)
#ifdef Y2_HARDWARE_SERIAL
HW_SERIAL_BEGIN(Y2);
#else
stepperY2.beginSerial(TMC_BAUD_RATE);
#endif
#endif
#if AXIS_HAS_UART(Z)
#ifdef Z_HARDWARE_SERIAL
HW_SERIAL_BEGIN(Z);
#else
stepperZ.beginSerial(TMC_BAUD_RATE);
#endif
#endif
#if AXIS_HAS_UART(Z2)
#ifdef Z2_HARDWARE_SERIAL
HW_SERIAL_BEGIN(Z2);
#else
stepperZ2.beginSerial(TMC_BAUD_RATE);
#endif
#endif
#if AXIS_HAS_UART(Z3)
#ifdef Z3_HARDWARE_SERIAL
HW_SERIAL_BEGIN(Z3);
#else
stepperZ3.beginSerial(TMC_BAUD_RATE);
#endif
#endif
#if AXIS_HAS_UART(Z4)
#ifdef Z4_HARDWARE_SERIAL
HW_SERIAL_BEGIN(Z4);
#else
stepperZ4.beginSerial(TMC_BAUD_RATE);
#endif
#endif
#if AXIS_HAS_UART(E0)
#ifdef E0_HARDWARE_SERIAL
HW_SERIAL_BEGIN(E0);
#else
stepperE0.beginSerial(TMC_BAUD_RATE);
#endif
#endif
#if AXIS_HAS_UART(E1)
#ifdef E1_HARDWARE_SERIAL
HW_SERIAL_BEGIN(E1);
#else
stepperE1.beginSerial(TMC_BAUD_RATE);
#endif
#endif
#if AXIS_HAS_UART(E2)
#ifdef E2_HARDWARE_SERIAL
HW_SERIAL_BEGIN(E2);
#else
stepperE2.beginSerial(TMC_BAUD_RATE);
#endif
#endif
#if AXIS_HAS_UART(E3)
#ifdef E3_HARDWARE_SERIAL
HW_SERIAL_BEGIN(E3);
#else
stepperE3.beginSerial(TMC_BAUD_RATE);
#endif
#endif
#if AXIS_HAS_UART(E4)
#ifdef E4_HARDWARE_SERIAL
HW_SERIAL_BEGIN(E4);
#else
stepperE4.beginSerial(TMC_BAUD_RATE);
#endif
#endif
#if AXIS_HAS_UART(E5)
#ifdef E5_HARDWARE_SERIAL
HW_SERIAL_BEGIN(E5);
#else
stepperE5.beginSerial(TMC_BAUD_RATE);
#endif
#endif
#if AXIS_HAS_UART(E6)
#ifdef E6_HARDWARE_SERIAL
HW_SERIAL_BEGIN(E6);
#else
stepperE6.beginSerial(TMC_BAUD_RATE);
#endif
#endif
#if AXIS_HAS_UART(E7)
#ifdef E7_HARDWARE_SERIAL
HW_SERIAL_BEGIN(E7);
#else
stepperE7.beginSerial(TMC_BAUD_RATE);
#endif
#endif
}
#endif
#if HAS_DRIVER(TMC2208) //2208-2209配置
template<char AXIS_LETTER, char DRIVER_ID, AxisEnum AXIS_ID>
void tmc_init(TMCMarlin<TMC2208Stepper, AXIS_LETTER, DRIVER_ID, AXIS_ID> &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate,float hold_current) {
TMC2208_n::GCONF_t gconf{0};
gconf.pdn_disable = true; // Use UART
gconf.i_scale_analog = false;
gconf.mstep_reg_select = true; // Select microsteps with UART
gconf.en_spreadcycle = !stealth;
st.GCONF(gconf.sr);
st.stored.stealthChop_enabled = stealth;
TMC2208_n::CHOPCONF_t chopconf{0};
chopconf.tbl = 0b01; // blank_time = 24
chopconf.toff = chop_init.toff;
chopconf.intpol = interpolate;
chopconf.hend = chop_init.hend + 3;
chopconf.hstrt = chop_init.hstrt - 1;
TERN_(SQUARE_WAVE_STEPPING, chopconf.dedge = true);
st.CHOPCONF(chopconf.sr);
st.rms_current(mA, hold_current);
st.microsteps(microsteps);
st.iholddelay(10);
st.TPOWERDOWN(128); // ~2s until driver lowers to hold current
TMC2208_n::PWMCONF_t pwmconf{0};
pwmconf.pwm_lim = 12;
pwmconf.pwm_reg = 8;
pwmconf.pwm_autograd = true;
pwmconf.pwm_autoscale = true;
pwmconf.pwm_freq = 0b01;
pwmconf.pwm_grad = 14;
pwmconf.pwm_ofs = 36;
st.PWMCONF(pwmconf.sr);
TERN(HYBRID_THRESHOLD, st.set_pwm_thrs(hyb_thrs), UNUSED(hyb_thrs));
st.GSTAT(0b111); // Clear
delay(200);
}
#endif // TMC2208
#if HAS_DRIVER(TMC2209)
template<char AXIS_LETTER, char DRIVER_ID, AxisEnum AXIS_ID>
void tmc_init(TMCMarlin<TMC2209Stepper, AXIS_LETTER, DRIVER_ID, AXIS_ID> &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate,float hold_current) {
TMC2208_n::GCONF_t gconf{0};
gconf.pdn_disable = true; // Use UART
gconf.mstep_reg_select = true; // Select microsteps with UART
gconf.i_scale_analog = false;
// gconf.i_scale_analog = true; //内部参考电压
gconf.en_spreadcycle = !stealth;
st.GCONF(gconf.sr);
st.stored.stealthChop_enabled = stealth;
TMC2208_n::CHOPCONF_t chopconf{0};
chopconf.tbl = 0b01; // blank_time = 24
chopconf.toff = chop_init.toff;
chopconf.intpol = interpolate;
chopconf.hend = chop_init.hend + 3;
chopconf.hstrt = chop_init.hstrt - 1;
TERN_(SQUARE_WAVE_STEPPING, chopconf.dedge = true);
st.CHOPCONF(chopconf.sr);
st.rms_current(mA, hold_current);
// st.rms_current(mA, HOLD_MULTIPLIER);
st.microsteps(microsteps);
st.iholddelay(10);
st.TPOWERDOWN(128); // ~2s until driver lowers to hold current
TMC2208_n::PWMCONF_t pwmconf{0};
pwmconf.pwm_lim = 12;
pwmconf.pwm_reg = 8;
pwmconf.pwm_autograd = true;
pwmconf.pwm_autoscale = true;
pwmconf.pwm_freq = 0b01;
pwmconf.pwm_grad = 14;
pwmconf.pwm_ofs = 36;
st.PWMCONF(pwmconf.sr);
TERN(HYBRID_THRESHOLD, st.set_pwm_thrs(hyb_thrs), UNUSED(hyb_thrs));
st.GSTAT(0b111); // Clear
delay(200);
}
#endif // TMC2209
#if HAS_DRIVER(TMC2660)
template<char AXIS_LETTER, char DRIVER_ID, AxisEnum AXIS_ID>
void tmc_init(TMCMarlin<TMC2660Stepper, AXIS_LETTER, DRIVER_ID, AXIS_ID> &st, const uint16_t mA, const uint16_t microsteps, const uint32_t, const bool, const chopper_timing_t &chop_init, const bool interpolate) {
st.begin();
TMC2660_n::CHOPCONF_t chopconf{0};
chopconf.tbl = 0b01;
chopconf.toff = chop_init.toff;
chopconf.hend = chop_init.hend + 3;
chopconf.hstrt = chop_init.hstrt - 1;
st.CHOPCONF(chopconf.sr);
st.sdoff(0);
st.rms_current(mA);
st.microsteps(microsteps);
TERN_(SQUARE_WAVE_STEPPING, st.dedge(true));
st.intpol(interpolate);
st.diss2g(true); // Disable short to ground protection. Too many false readings?
TERN_(TMC_DEBUG, st.rdsel(0b01));
}
#endif // TMC2660
#if HAS_DRIVER(TMC5130)
template<char AXIS_LETTER, char DRIVER_ID, AxisEnum AXIS_ID>
void tmc_init(TMCMarlin<TMC5130Stepper, AXIS_LETTER, DRIVER_ID, AXIS_ID> &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate) {
st.begin();
CHOPCONF_t chopconf{0};
chopconf.tbl = 0b01;
chopconf.toff = chop_init.toff;
chopconf.intpol = interpolate;
chopconf.hend = chop_init.hend + 3;
chopconf.hstrt = chop_init.hstrt - 1;
TERN_(SQUARE_WAVE_STEPPING, chopconf.dedge = true);
st.CHOPCONF(chopconf.sr);
st.rms_current(mA, HOLD_MULTIPLIER);
st.microsteps(microsteps);
st.iholddelay(10);
st.TPOWERDOWN(128); // ~2s until driver lowers to hold current
st.en_pwm_mode(stealth);
st.stored.stealthChop_enabled = stealth;
PWMCONF_t pwmconf{0};
pwmconf.pwm_freq = 0b01; // f_pwm = 2/683 f_clk
pwmconf.pwm_autoscale = true;
pwmconf.pwm_grad = 5;
pwmconf.pwm_ampl = 180;
st.PWMCONF(pwmconf.sr);
TERN(HYBRID_THRESHOLD, st.set_pwm_thrs(hyb_thrs), UNUSED(hyb_thrs));
st.GSTAT(); // Clear GSTAT
}
#endif // TMC5130
#if HAS_DRIVER(TMC5160)
template<char AXIS_LETTER, char DRIVER_ID, AxisEnum AXIS_ID>
void tmc_init(TMCMarlin<TMC5160Stepper, AXIS_LETTER, DRIVER_ID, AXIS_ID> &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate) {
st.begin();
CHOPCONF_t chopconf{0};
chopconf.tbl = 0b01;
chopconf.toff = chop_init.toff;
chopconf.intpol = interpolate;
chopconf.hend = chop_init.hend + 3;
chopconf.hstrt = chop_init.hstrt - 1;
TERN_(SQUARE_WAVE_STEPPING, chopconf.dedge = true);
st.CHOPCONF(chopconf.sr);
st.rms_current(mA, HOLD_MULTIPLIER);
st.microsteps(microsteps);
st.iholddelay(10);
st.TPOWERDOWN(128); // ~2s until driver lowers to hold current
st.en_pwm_mode(stealth);
st.stored.stealthChop_enabled = stealth;
TMC2160_n::PWMCONF_t pwmconf{0};
pwmconf.pwm_lim = 12;
pwmconf.pwm_reg = 8;
pwmconf.pwm_autograd = true;
pwmconf.pwm_autoscale = true;
pwmconf.pwm_freq = 0b01;
pwmconf.pwm_grad = 14;
pwmconf.pwm_ofs = 36;
st.PWMCONF(pwmconf.sr);
#if ENABLED(HYBRID_THRESHOLD)
st.set_pwm_thrs(hyb_thrs);
#else
UNUSED(hyb_thrs);
#endif
st.GSTAT(); // Clear GSTAT
}
#endif // TMC5160
void restore_trinamic_drivers() {
#if AXIS_IS_TMC(X)
stepperX.push();
#endif
#if AXIS_IS_TMC(X2)
stepperX2.push();
#endif
#if AXIS_IS_TMC(Y)
stepperY.push();
#endif
#if AXIS_IS_TMC(Y2)
stepperY2.push();
#endif
#if AXIS_IS_TMC(Z)
stepperZ.push();
#endif
#if AXIS_IS_TMC(Z2)
stepperZ2.push();
#endif
#if AXIS_IS_TMC(Z3)
stepperZ3.push();
#endif
#if AXIS_IS_TMC(Z4)
stepperZ4.push();
#endif
#if AXIS_IS_TMC(E0)
stepperE0.push();
#endif
#if AXIS_IS_TMC(E1)
stepperE1.push();
#endif
#if AXIS_IS_TMC(E2)
stepperE2.push();
#endif
#if AXIS_IS_TMC(E3)
stepperE3.push();
#endif
#if AXIS_IS_TMC(E4)
stepperE4.push();
#endif
#if AXIS_IS_TMC(E5)
stepperE5.push();
#endif
#if AXIS_IS_TMC(E6)
stepperE6.push();
#endif
#if AXIS_IS_TMC(E7)
stepperE7.push();
#endif
}
void reset_trinamic_drivers() {
static constexpr bool stealthchop_by_axis[] = { ENABLED(STEALTHCHOP_XY), ENABLED(STEALTHCHOP_Z), ENABLED(STEALTHCHOP_E) };
#if AXIS_IS_TMC(X)
TMC_INIT(X, STEALTH_AXIS_XY);
#endif
#if AXIS_IS_TMC(X2)
TMC_INIT(X2, STEALTH_AXIS_XY);
#endif
#if AXIS_IS_TMC(Y)
TMC_INIT(Y, STEALTH_AXIS_XY);
#endif
#if AXIS_IS_TMC(Y2)
TMC_INIT(Y2, STEALTH_AXIS_XY);
#endif
#if AXIS_IS_TMC(Z)
TMC_INIT(Z, STEALTH_AXIS_Z);
#endif
#if AXIS_IS_TMC(Z2)
TMC_INIT(Z2, STEALTH_AXIS_Z);
#endif
#if AXIS_IS_TMC(Z3)
TMC_INIT(Z3, STEALTH_AXIS_Z);
#endif
#if AXIS_IS_TMC(Z4)
TMC_INIT(Z4, STEALTH_AXIS_Z);
#endif
#if AXIS_IS_TMC(E0)
TMC_INIT(E0, STEALTH_AXIS_E);
#endif
#if AXIS_IS_TMC(E1)
TMC_INIT(E1, STEALTH_AXIS_E);
#endif
#if AXIS_IS_TMC(E2)
TMC_INIT(E2, STEALTH_AXIS_E);
#endif
#if AXIS_IS_TMC(E3)
TMC_INIT(E3, STEALTH_AXIS_E);
#endif
#if AXIS_IS_TMC(E4)
TMC_INIT(E4, STEALTH_AXIS_E);
#endif
#if AXIS_IS_TMC(E5)
TMC_INIT(E5, STEALTH_AXIS_E);
#endif
#if AXIS_IS_TMC(E6)
TMC_INIT(E6, STEALTH_AXIS_E);
#endif
#if AXIS_IS_TMC(E7)
TMC_INIT(E7, STEALTH_AXIS_E);
#endif
#if USE_SENSORLESS
#if X_SENSORLESS
stepperX.homing_threshold(X_STALL_SENSITIVITY);
#if AXIS_HAS_STALLGUARD(X2)
stepperX2.homing_threshold(CAT(TERN(X2_SENSORLESS, X2, X), _STALL_SENSITIVITY));
#endif
#endif
#if Y_SENSORLESS
stepperY.homing_threshold(Y_STALL_SENSITIVITY);
#if AXIS_HAS_STALLGUARD(Y2)
stepperY2.homing_threshold(CAT(TERN(Y2_SENSORLESS, Y2, Y), _STALL_SENSITIVITY));
#endif
#endif
#if Z_SENSORLESS
stepperZ.homing_threshold(Z_STALL_SENSITIVITY);
#if AXIS_HAS_STALLGUARD(Z2)
stepperZ2.homing_threshold(CAT(TERN(Z2_SENSORLESS, Z2, Z), _STALL_SENSITIVITY));
#endif
#if AXIS_HAS_STALLGUARD(Z3)
stepperZ3.homing_threshold(CAT(TERN(Z3_SENSORLESS, Z3, Z), _STALL_SENSITIVITY));
#endif
#if AXIS_HAS_STALLGUARD(Z4)
stepperZ4.homing_threshold(CAT(TERN(Z4_SENSORLESS, Z4, Z), _STALL_SENSITIVITY));
#endif
#endif
#endif
#ifdef TMC_ADV
TMC_ADV()
#endif
stepper.set_directions();
}
// TMC Slave Address Conflict Detection
//
// Conflict detection is performed in the following way. Similar methods are used for
// hardware and software serial, but the implementations are indepenent.
//
// 1. Populate a data structure with UART parameters and addresses for all possible axis.
// If an axis is not in use, populate it with recognizable placeholder data.
// 2. For each axis in use, static_assert using a constexpr function, which counts the
// number of matching/conflicting axis. If the value is not exactly 1, fail.
#if ANY_AXIS_HAS(HW_SERIAL)
// Hardware serial names are compared as strings, since actually resolving them cannot occur in a constexpr.
// Using a fixed-length character array for the port name allows this to be constexpr compatible.
struct SanityHwSerialDetails { const char port[20]; uint32_t address; };
#define TMC_HW_DETAIL_ARGS(A) TERN(A##_HAS_HW_SERIAL, STRINGIFY(A##_HARDWARE_SERIAL), ""), TERN0(A##_HAS_HW_SERIAL, A##_SLAVE_ADDRESS)
#define TMC_HW_DETAIL(A) {TMC_HW_DETAIL_ARGS(A)}
constexpr SanityHwSerialDetails sanity_tmc_hw_details[] = {
TMC_HW_DETAIL(X), TMC_HW_DETAIL(X2),
TMC_HW_DETAIL(Y), TMC_HW_DETAIL(Y2),
TMC_HW_DETAIL(Z), TMC_HW_DETAIL(Z2), TMC_HW_DETAIL(Z3), TMC_HW_DETAIL(Z4),
TMC_HW_DETAIL(E0), TMC_HW_DETAIL(E1), TMC_HW_DETAIL(E2), TMC_HW_DETAIL(E3), TMC_HW_DETAIL(E4), TMC_HW_DETAIL(E5), TMC_HW_DETAIL(E6), TMC_HW_DETAIL(E7)
};
// constexpr compatible string comparison
constexpr bool str_eq_ce(const char * a, const char * b) {
return *a == *b && (*a == '\0' || str_eq_ce(a+1,b+1));
}
constexpr bool sc_hw_done(size_t start, size_t end) { return start == end; }
constexpr bool sc_hw_skip(const char *port_name) { return !(*port_name); }
constexpr bool sc_hw_match(const char *port_name, uint32_t address, size_t start, size_t end) {
return !sc_hw_done(start, end) && !sc_hw_skip(port_name) && (address == sanity_tmc_hw_details[start].address && str_eq_ce(port_name, sanity_tmc_hw_details[start].port));
}
constexpr int count_tmc_hw_serial_matches(const char *port_name, uint32_t address, size_t start, size_t end) {
return sc_hw_done(start, end) ? 0 : ((sc_hw_skip(port_name) ? 0 : (sc_hw_match(port_name, address, start, end) ? 1 : 0)) + count_tmc_hw_serial_matches(port_name, address, start + 1, end));
}
#define TMC_HWSERIAL_CONFLICT_MSG(A) STRINGIFY(A) "_SLAVE_ADDRESS conflicts with another driver using the same " STRINGIFY(A) "_HARDWARE_SERIAL"
#define SA_NO_TMC_HW_C(A) static_assert(1 >= count_tmc_hw_serial_matches(TMC_HW_DETAIL_ARGS(A), 0, COUNT(sanity_tmc_hw_details)), TMC_HWSERIAL_CONFLICT_MSG(A));
SA_NO_TMC_HW_C(X);SA_NO_TMC_HW_C(X2);
SA_NO_TMC_HW_C(Y);SA_NO_TMC_HW_C(Y2);
SA_NO_TMC_HW_C(Z);SA_NO_TMC_HW_C(Z2);SA_NO_TMC_HW_C(Z3);SA_NO_TMC_HW_C(Z4);
SA_NO_TMC_HW_C(E0);SA_NO_TMC_HW_C(E1);SA_NO_TMC_HW_C(E2);SA_NO_TMC_HW_C(E3);SA_NO_TMC_HW_C(E4);SA_NO_TMC_HW_C(E5);SA_NO_TMC_HW_C(E6);SA_NO_TMC_HW_C(E7);
#endif
#if ANY_AXIS_HAS(SW_SERIAL)
struct SanitySwSerialDetails { int32_t txpin; int32_t rxpin; uint32_t address; };
#define TMC_SW_DETAIL_ARGS(A) TERN(A##_HAS_SW_SERIAL, A##_SERIAL_TX_PIN, -1), TERN(A##_HAS_SW_SERIAL, A##_SERIAL_RX_PIN, -1), TERN0(A##_HAS_SW_SERIAL, A##_SLAVE_ADDRESS)
#define TMC_SW_DETAIL(A) TMC_SW_DETAIL_ARGS(A)
constexpr SanitySwSerialDetails sanity_tmc_sw_details[] = {
TMC_SW_DETAIL(X), TMC_SW_DETAIL(X2),
TMC_SW_DETAIL(Y), TMC_SW_DETAIL(Y2),
TMC_SW_DETAIL(Z), TMC_SW_DETAIL(Z2), TMC_SW_DETAIL(Z3), TMC_SW_DETAIL(Z4),
TMC_SW_DETAIL(E0), TMC_SW_DETAIL(E1), TMC_SW_DETAIL(E2), TMC_SW_DETAIL(E3), TMC_SW_DETAIL(E4), TMC_SW_DETAIL(E5), TMC_SW_DETAIL(E6), TMC_SW_DETAIL(E7)
};
constexpr bool sc_sw_done(size_t start, size_t end) { return start == end; }
constexpr bool sc_sw_skip(int32_t txpin) { return txpin < 0; }
constexpr bool sc_sw_match(int32_t txpin, int32_t rxpin, uint32_t address, size_t start, size_t end) {
return !sc_sw_done(start, end) && !sc_sw_skip(txpin) && (txpin == sanity_tmc_sw_details[start].txpin || rxpin == sanity_tmc_sw_details[start].rxpin) && (address == sanity_tmc_sw_details[start].address);
}
constexpr int count_tmc_sw_serial_matches(int32_t txpin, int32_t rxpin, uint32_t address, size_t start, size_t end) {
return sc_sw_done(start, end) ? 0 : ((sc_sw_skip(txpin) ? 0 : (sc_sw_match(txpin, rxpin, address, start, end) ? 1 : 0)) + count_tmc_sw_serial_matches(txpin, rxpin, address, start + 1, end));
}
#define TMC_SWSERIAL_CONFLICT_MSG(A) STRINGIFY(A) "_SLAVE_ADDRESS conflicts with another driver using the same " STRINGIFY(A) "_SERIAL_RX_PIN or " STRINGIFY(A) "_SERIAL_TX_PIN"
#define SA_NO_TMC_SW_C(A) static_assert(1 >= count_tmc_sw_serial_matches(TMC_SW_DETAIL_ARGS(A), 0, COUNT(sanity_tmc_sw_details)), TMC_SWSERIAL_CONFLICT_MSG(A));
SA_NO_TMC_SW_C(X);SA_NO_TMC_SW_C(X2);
SA_NO_TMC_SW_C(Y);SA_NO_TMC_SW_C(Y2);
SA_NO_TMC_SW_C(Z);SA_NO_TMC_SW_C(Z2);SA_NO_TMC_SW_C(Z3);SA_NO_TMC_SW_C(Z4);
SA_NO_TMC_SW_C(E0);SA_NO_TMC_SW_C(E1);SA_NO_TMC_SW_C(E2);SA_NO_TMC_SW_C(E3);SA_NO_TMC_SW_C(E4);SA_NO_TMC_SW_C(E5);SA_NO_TMC_SW_C(E6);SA_NO_TMC_SW_C(E7);
#endif
#endif // HAS_TRINAMIC_CONFIG
+362
View File
@@ -0,0 +1,362 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* stepper/trinamic.h
* Stepper driver indirection for Trinamic
*/
#include <TMCStepper.h>
#if TMCSTEPPER_VERSION < 0x000500
#error "Update TMCStepper library to 0.5.0 or newer."
#endif
#include "../../inc/MarlinConfig.h"
#include "../../feature/tmc_util.h"
#define CLASS_TMC2130 TMC2130Stepper
#define CLASS_TMC2160 TMC2160Stepper
#define CLASS_TMC2208 TMC2208Stepper
#define CLASS_TMC2209 TMC2209Stepper
#define CLASS_TMC2660 TMC2660Stepper
#define CLASS_TMC5130 TMC5130Stepper
#define CLASS_TMC5160 TMC5160Stepper
#define TMC_X_LABEL 'X', '0'
#define TMC_Y_LABEL 'Y', '0'
#define TMC_Z_LABEL 'Z', '0'
#define TMC_X2_LABEL 'X', '2'
#define TMC_Y2_LABEL 'Y', '2'
#define TMC_Z2_LABEL 'Z', '2'
#define TMC_Z3_LABEL 'Z', '3'
#define TMC_Z4_LABEL 'Z', '4'
#define TMC_E0_LABEL 'E', '0'
#define TMC_E1_LABEL 'E', '1'
#define TMC_E2_LABEL 'E', '2'
#define TMC_E3_LABEL 'E', '3'
#define TMC_E4_LABEL 'E', '4'
#define TMC_E5_LABEL 'E', '5'
#define TMC_E6_LABEL 'E', '6'
#define TMC_E7_LABEL 'E', '7'
#define __TMC_CLASS(TYPE, L, I, A) TMCMarlin<CLASS_##TYPE, L, I, A>
#define _TMC_CLASS(TYPE, LandI, A) __TMC_CLASS(TYPE, LandI, A)
#define TMC_CLASS(ST, A) _TMC_CLASS(ST##_DRIVER_TYPE, TMC_##ST##_LABEL, A##_AXIS)
#if ENABLED(DISTINCT_E_FACTORS)
#define TMC_CLASS_E(N) TMC_CLASS(E##N, E##N)
#else
#define TMC_CLASS_E(N) TMC_CLASS(E##N, E)
#endif
typedef struct {
uint8_t toff;
int8_t hend;
uint8_t hstrt;
} chopper_timing_t;
#ifndef CHOPPER_TIMING_X
#define CHOPPER_TIMING_X CHOPPER_TIMING
#endif
#ifndef CHOPPER_TIMING_Y
#define CHOPPER_TIMING_Y CHOPPER_TIMING
#endif
#ifndef CHOPPER_TIMING_Z
#define CHOPPER_TIMING_Z CHOPPER_TIMING
#endif
#ifndef CHOPPER_TIMING_E
#define CHOPPER_TIMING_E CHOPPER_TIMING
#endif
#if HAS_TMC220x
void tmc_serial_begin();
#endif
void restore_trinamic_drivers();
void reset_trinamic_drivers();
#define AXIS_HAS_SQUARE_WAVE(A) (AXIS_IS_TMC(A) && ENABLED(SQUARE_WAVE_STEPPING))
// X Stepper
#if AXIS_IS_TMC(X)
extern TMC_CLASS(X, X) stepperX;
static constexpr chopper_timing_t chopper_timing_X = CHOPPER_TIMING_X;
#if ENABLED(SOFTWARE_DRIVER_ENABLE)
#define X_ENABLE_INIT() NOOP
#define X_ENABLE_WRITE(STATE) stepperX.toff((STATE)==X_ENABLE_ON ? chopper_timing_X.toff : 0)
#define X_ENABLE_READ() stepperX.isEnabled()
#endif
#if AXIS_HAS_SQUARE_WAVE(X)
#define X_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(X_STEP_PIN); }while(0)
#endif
#endif
// Y Stepper
#if AXIS_IS_TMC(Y)
extern TMC_CLASS(Y, Y) stepperY;
static constexpr chopper_timing_t chopper_timing_Y = CHOPPER_TIMING_Y;
#if ENABLED(SOFTWARE_DRIVER_ENABLE)
#define Y_ENABLE_INIT() NOOP
#define Y_ENABLE_WRITE(STATE) stepperY.toff((STATE)==Y_ENABLE_ON ? chopper_timing_Y.toff : 0)
#define Y_ENABLE_READ() stepperY.isEnabled()
#endif
#if AXIS_HAS_SQUARE_WAVE(Y)
#define Y_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(Y_STEP_PIN); }while(0)
#endif
#endif
// Z Stepper
#if AXIS_IS_TMC(Z)
extern TMC_CLASS(Z, Z) stepperZ;
static constexpr chopper_timing_t chopper_timing_Z = CHOPPER_TIMING_Z;
#if ENABLED(SOFTWARE_DRIVER_ENABLE)
#define Z_ENABLE_INIT() NOOP
#define Z_ENABLE_WRITE(STATE) stepperZ.toff((STATE)==Z_ENABLE_ON ? chopper_timing_Z.toff : 0)
#define Z_ENABLE_READ() stepperZ.isEnabled()
#endif
#if AXIS_HAS_SQUARE_WAVE(Z)
#define Z_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(Z_STEP_PIN); }while(0)
#endif
#endif
// X2 Stepper
#if HAS_X2_ENABLE && AXIS_IS_TMC(X2)
extern TMC_CLASS(X2, X) stepperX2;
#ifndef CHOPPER_TIMING_X2
#define CHOPPER_TIMING_X2 CHOPPER_TIMING_X
#endif
static constexpr chopper_timing_t chopper_timing_X2 = CHOPPER_TIMING_X2;
#if ENABLED(SOFTWARE_DRIVER_ENABLE)
#define X2_ENABLE_INIT() NOOP
#define X2_ENABLE_WRITE(STATE) stepperX2.toff((STATE)==X_ENABLE_ON ? chopper_timing_X2.toff : 0)
#define X2_ENABLE_READ() stepperX2.isEnabled()
#endif
#if AXIS_HAS_SQUARE_WAVE(X2)
#define X2_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(X2_STEP_PIN); }while(0)
#endif
#endif
// Y2 Stepper
#if HAS_Y2_ENABLE && AXIS_IS_TMC(Y2)
extern TMC_CLASS(Y2, Y) stepperY2;
#ifndef CHOPPER_TIMING_Y2
#define CHOPPER_TIMING_Y2 CHOPPER_TIMING_Y
#endif
static constexpr chopper_timing_t chopper_timing_Y2 = CHOPPER_TIMING_Y2;
#if ENABLED(SOFTWARE_DRIVER_ENABLE)
#define Y2_ENABLE_INIT() NOOP
#define Y2_ENABLE_WRITE(STATE) stepperY2.toff((STATE)==Y_ENABLE_ON ? chopper_timing_Y2.toff : 0)
#define Y2_ENABLE_READ() stepperY2.isEnabled()
#endif
#if AXIS_HAS_SQUARE_WAVE(Y2)
#define Y2_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(Y2_STEP_PIN); }while(0)
#endif
#endif
// Z2 Stepper
#if HAS_Z2_ENABLE && AXIS_IS_TMC(Z2)
extern TMC_CLASS(Z2, Z) stepperZ2;
#ifndef CHOPPER_TIMING_Z2
#define CHOPPER_TIMING_Z2 CHOPPER_TIMING_Z
#endif
static constexpr chopper_timing_t chopper_timing_Z2 = CHOPPER_TIMING_Z2;
#if ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z2)
#define Z2_ENABLE_INIT() NOOP
#define Z2_ENABLE_WRITE(STATE) stepperZ2.toff((STATE)==Z_ENABLE_ON ? chopper_timing_Z2.toff : 0)
#define Z2_ENABLE_READ() stepperZ2.isEnabled()
#endif
#if AXIS_HAS_SQUARE_WAVE(Z2)
#define Z2_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(Z2_STEP_PIN); }while(0)
#endif
#endif
// Z3 Stepper
#if HAS_Z3_ENABLE && AXIS_IS_TMC(Z3)
extern TMC_CLASS(Z3, Z) stepperZ3;
#ifndef CHOPPER_TIMING_Z3
#define CHOPPER_TIMING_Z3 CHOPPER_TIMING_Z
#endif
static constexpr chopper_timing_t chopper_timing_Z3 = CHOPPER_TIMING_Z3;
#if ENABLED(SOFTWARE_DRIVER_ENABLE)
#define Z3_ENABLE_INIT() NOOP
#define Z3_ENABLE_WRITE(STATE) stepperZ3.toff((STATE)==Z_ENABLE_ON ? chopper_timing_Z3.toff : 0)
#define Z3_ENABLE_READ() stepperZ3.isEnabled()
#endif
#if AXIS_HAS_SQUARE_WAVE(Z3)
#define Z3_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(Z3_STEP_PIN); }while(0)
#endif
#endif
// Z4 Stepper
#if HAS_Z4_ENABLE && AXIS_IS_TMC(Z4)
extern TMC_CLASS(Z4, Z) stepperZ4;
#ifndef CHOPPER_TIMING_Z4
#define CHOPPER_TIMING_Z4 CHOPPER_TIMING_Z
#endif
static constexpr chopper_timing_t chopper_timing_Z4 = CHOPPER_TIMING_Z4;
#if ENABLED(SOFTWARE_DRIVER_ENABLE)
#define Z4_ENABLE_INIT() NOOP
#define Z4_ENABLE_WRITE(STATE) stepperZ4.toff((STATE)==Z_ENABLE_ON ? chopper_timing_Z4.toff : 0)
#define Z4_ENABLE_READ() stepperZ4.isEnabled()
#endif
#if AXIS_HAS_SQUARE_WAVE(Z4)
#define Z4_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(Z4_STEP_PIN); }while(0)
#endif
#endif
// E0 Stepper
#if AXIS_IS_TMC(E0)
extern TMC_CLASS_E(0) stepperE0;
#ifndef CHOPPER_TIMING_E0
#define CHOPPER_TIMING_E0 CHOPPER_TIMING_E
#endif
static constexpr chopper_timing_t chopper_timing_E0 = CHOPPER_TIMING_E0;
#if ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E0)
#define E0_ENABLE_INIT() NOOP
#define E0_ENABLE_WRITE(STATE) stepperE0.toff((STATE)==E_ENABLE_ON ? chopper_timing_E0.toff : 0)
#define E0_ENABLE_READ() stepperE0.isEnabled()
#endif
#if AXIS_HAS_SQUARE_WAVE(E0)
#define E0_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(E0_STEP_PIN); }while(0)
#endif
#endif
// E1 Stepper
#if AXIS_IS_TMC(E1)
extern TMC_CLASS_E(1) stepperE1;
#ifndef CHOPPER_TIMING_E1
#define CHOPPER_TIMING_E1 CHOPPER_TIMING_E
#endif
static constexpr chopper_timing_t chopper_timing_E1 = CHOPPER_TIMING_E1;
#if ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E1)
#define E1_ENABLE_INIT() NOOP
#define E1_ENABLE_WRITE(STATE) stepperE1.toff((STATE)==E_ENABLE_ON ? chopper_timing_E1.toff : 0)
#define E1_ENABLE_READ() stepperE1.isEnabled()
#endif
#if AXIS_HAS_SQUARE_WAVE(E1)
#define E1_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(E1_STEP_PIN); }while(0)
#endif
#endif
// E2 Stepper
#if AXIS_IS_TMC(E2)
extern TMC_CLASS_E(2) stepperE2;
#ifndef CHOPPER_TIMING_E2
#define CHOPPER_TIMING_E2 CHOPPER_TIMING_E
#endif
static constexpr chopper_timing_t chopper_timing_E2 = CHOPPER_TIMING_E2;
#if ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E2)
#define E2_ENABLE_INIT() NOOP
#define E2_ENABLE_WRITE(STATE) stepperE2.toff((STATE)==E_ENABLE_ON ? chopper_timing_E2.toff : 0)
#define E2_ENABLE_READ() stepperE2.isEnabled()
#endif
#if AXIS_HAS_SQUARE_WAVE(E2)
#define E2_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(E2_STEP_PIN); }while(0)
#endif
#endif
// E3 Stepper
#if AXIS_IS_TMC(E3)
extern TMC_CLASS_E(3) stepperE3;
#ifndef CHOPPER_TIMING_E3
#define CHOPPER_TIMING_E3 CHOPPER_TIMING_E
#endif
static constexpr chopper_timing_t chopper_timing_E3 = CHOPPER_TIMING_E3;
#if ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E3)
#define E3_ENABLE_INIT() NOOP
#define E3_ENABLE_WRITE(STATE) stepperE3.toff((STATE)==E_ENABLE_ON ? chopper_timing_E3.toff : 0)
#define E3_ENABLE_READ() stepperE3.isEnabled()
#endif
#if AXIS_HAS_SQUARE_WAVE(E3)
#define E3_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(E3_STEP_PIN); }while(0)
#endif
#endif
// E4 Stepper
#if AXIS_IS_TMC(E4)
extern TMC_CLASS_E(4) stepperE4;
#ifndef CHOPPER_TIMING_E4
#define CHOPPER_TIMING_E4 CHOPPER_TIMING_E
#endif
static constexpr chopper_timing_t chopper_timing_E4 = CHOPPER_TIMING_E4;
#if ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E4)
#define E4_ENABLE_INIT() NOOP
#define E4_ENABLE_WRITE(STATE) stepperE4.toff((STATE)==E_ENABLE_ON ? chopper_timing_E4.toff : 0)
#define E4_ENABLE_READ() stepperE4.isEnabled()
#endif
#if AXIS_HAS_SQUARE_WAVE(E4)
#define E4_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(E4_STEP_PIN); }while(0)
#endif
#endif
// E5 Stepper
#if AXIS_IS_TMC(E5)
extern TMC_CLASS_E(5) stepperE5;
#ifndef CHOPPER_TIMING_E5
#define CHOPPER_TIMING_E5 CHOPPER_TIMING_E
#endif
static constexpr chopper_timing_t chopper_timing_E5 = CHOPPER_TIMING_E5;
#if ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E5)
#define E5_ENABLE_INIT() NOOP
#define E5_ENABLE_WRITE(STATE) stepperE5.toff((STATE)==E_ENABLE_ON ? chopper_timing_E5.toff : 0)
#define E5_ENABLE_READ() stepperE5.isEnabled()
#endif
#if AXIS_HAS_SQUARE_WAVE(E5)
#define E5_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(E5_STEP_PIN); }while(0)
#endif
#endif
// E6 Stepper
#if AXIS_IS_TMC(E6)
extern TMC_CLASS_E(6) stepperE6;
#ifndef CHOPPER_TIMING_E6
#define CHOPPER_TIMING_E6 CHOPPER_TIMING_E
#endif
static constexpr chopper_timing_t chopper_timing_E6 = CHOPPER_TIMING_E6;
#if ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E6)
#define E6_ENABLE_INIT() NOOP
#define E6_ENABLE_WRITE(STATE) stepperE6.toff((STATE)==E_ENABLE_ON ? chopper_timing_E6.toff : 0)
#define E6_ENABLE_READ() stepperE6.isEnabled()
#endif
#if AXIS_HAS_SQUARE_WAVE(E6)
#define E6_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(E6_STEP_PIN); }while(0)
#endif
#endif
// E7 Stepper
#if AXIS_IS_TMC(E7)
extern TMC_CLASS_E(7) stepperE7;
#ifndef CHOPPER_TIMING_E7
#define CHOPPER_TIMING_E7 CHOPPER_TIMING_E
#endif
static constexpr chopper_timing_t chopper_timing_E7 = CHOPPER_TIMING_E7;
#if ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E7)
#define E7_ENABLE_INIT() NOOP
#define E7_ENABLE_WRITE(STATE) stepperE7.toff((STATE)==E_ENABLE_ON ? chopper_timing_E7.toff : 0)
#define E7_ENABLE_READ() stepperE7.isEnabled()
#endif
#if AXIS_HAS_SQUARE_WAVE(E7)
#define E7_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(E7_STEP_PIN); }while(0)
#endif
#endif
File diff suppressed because it is too large Load Diff
+958
View File
@@ -0,0 +1,958 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* temperature.h - temperature controller
*/
#include "thermistor/thermistors.h"
#include "../inc/MarlinConfig.h"
#if ENABLED(AUTO_POWER_CONTROL)
#include "../feature/power.h"
#endif
#if ENABLED(AUTO_REPORT_TEMPERATURES)
#include "../libs/autoreport.h"
#endif
#ifndef SOFT_PWM_SCALE
#define SOFT_PWM_SCALE 0
#endif
#define HOTEND_INDEX TERN(HAS_MULTI_HOTEND, e, 0)
#define E_NAME TERN_(HAS_MULTI_HOTEND, e)
// Element identifiers. Positive values are hotends. Negative values are other heaters or coolers.
typedef enum : int8_t {
H_NONE = -6,
H_COOLER, H_PROBE, H_REDUNDANT, H_CHAMBER, H_BED,
H_E0, H_E1, H_E2, H_E3, H_E4, H_E5, H_E6, H_E7
} heater_id_t;
// PID storage
typedef struct { float Kp, Ki, Kd; } PID_t;
typedef struct { float Kp, Ki, Kd, Kc; } PIDC_t;
typedef struct { float Kp, Ki, Kd, Kf; } PIDF_t;
typedef struct { float Kp, Ki, Kd, Kc, Kf; } PIDCF_t;
typedef
#if BOTH(PID_EXTRUSION_SCALING, PID_FAN_SCALING)
PIDCF_t
#elif ENABLED(PID_EXTRUSION_SCALING)
PIDC_t
#elif ENABLED(PID_FAN_SCALING)
PIDF_t
#else
PID_t
#endif
hotend_pid_t;
#if ENABLED(PID_EXTRUSION_SCALING)
typedef IF<(LPQ_MAX_LEN > 255), uint16_t, uint8_t>::type lpq_ptr_t;
#endif
#define PID_PARAM(F,H) _PID_##F(TERN(PID_PARAMS_PER_HOTEND, H, 0 & H)) // Always use 'H' to suppress warning
#define _PID_Kp(H) TERN(PIDTEMP, Temperature::temp_hotend[H].pid.Kp, NAN)
#define _PID_Ki(H) TERN(PIDTEMP, Temperature::temp_hotend[H].pid.Ki, NAN)
#define _PID_Kd(H) TERN(PIDTEMP, Temperature::temp_hotend[H].pid.Kd, NAN)
#if ENABLED(PIDTEMP)
#define _PID_Kc(H) TERN(PID_EXTRUSION_SCALING, Temperature::temp_hotend[H].pid.Kc, 1)
#define _PID_Kf(H) TERN(PID_FAN_SCALING, Temperature::temp_hotend[H].pid.Kf, 0)
#else
#define _PID_Kc(H) 1
#define _PID_Kf(H) 0
#endif
/**
* States for ADC reading in the ISR
*/
enum ADCSensorState : char {
StartSampling,
#if HAS_TEMP_ADC_0
PrepareTemp_0, MeasureTemp_0,
#endif
#if HAS_TEMP_ADC_BED
PrepareTemp_BED, MeasureTemp_BED,
#endif
#if HAS_TEMP_ADC_CHAMBER
PrepareTemp_CHAMBER, MeasureTemp_CHAMBER,
#endif
#if HAS_TEMP_ADC_COOLER
PrepareTemp_COOLER, MeasureTemp_COOLER,
#endif
#if HAS_TEMP_ADC_PROBE
PrepareTemp_PROBE, MeasureTemp_PROBE,
#endif
#if HAS_TEMP_ADC_1
PrepareTemp_1, MeasureTemp_1,
#endif
#if HAS_TEMP_ADC_2
PrepareTemp_2, MeasureTemp_2,
#endif
#if HAS_TEMP_ADC_3
PrepareTemp_3, MeasureTemp_3,
#endif
#if HAS_TEMP_ADC_4
PrepareTemp_4, MeasureTemp_4,
#endif
#if HAS_TEMP_ADC_5
PrepareTemp_5, MeasureTemp_5,
#endif
#if HAS_TEMP_ADC_6
PrepareTemp_6, MeasureTemp_6,
#endif
#if HAS_TEMP_ADC_7
PrepareTemp_7, MeasureTemp_7,
#endif
#if HAS_JOY_ADC_X
PrepareJoy_X, MeasureJoy_X,
#endif
#if HAS_JOY_ADC_Y
PrepareJoy_Y, MeasureJoy_Y,
#endif
#if HAS_JOY_ADC_Z
PrepareJoy_Z, MeasureJoy_Z,
#endif
#if ENABLED(FILAMENT_WIDTH_SENSOR)
Prepare_FILWIDTH, Measure_FILWIDTH,
#endif
#if ENABLED(POWER_MONITOR_CURRENT)
Prepare_POWER_MONITOR_CURRENT,
Measure_POWER_MONITOR_CURRENT,
#endif
#if ENABLED(POWER_MONITOR_VOLTAGE)
Prepare_POWER_MONITOR_VOLTAGE,
Measure_POWER_MONITOR_VOLTAGE,
#endif
#if HAS_ADC_BUTTONS
Prepare_ADC_KEY, Measure_ADC_KEY,
#endif
SensorsReady, // Temperatures ready. Delay the next round of readings to let ADC pins settle.
StartupDelay // Startup, delay initial temp reading a tiny bit so the hardware can settle
};
// Minimum number of Temperature::ISR loops between sensor readings.
// Multiplied by 16 (OVERSAMPLENR) to obtain the total time to
// get all oversampled sensor readings
#define MIN_ADC_ISR_LOOPS 10
#define ACTUAL_ADC_SAMPLES _MAX(int(MIN_ADC_ISR_LOOPS), int(SensorsReady))
#if HAS_PID_HEATING
#define PID_K2 (1-float(PID_K1))
#define PID_dT ((OVERSAMPLENR * float(ACTUAL_ADC_SAMPLES)) / TEMP_TIMER_FREQUENCY)
// Apply the scale factors to the PID values
#define scalePID_i(i) ( float(i) * PID_dT )
#define unscalePID_i(i) ( float(i) / PID_dT )
#define scalePID_d(d) ( float(d) / PID_dT )
#define unscalePID_d(d) ( float(d) * PID_dT )
#endif
#if BOTH(HAS_LCD_MENU, G26_MESH_VALIDATION)
#define G26_CLICK_CAN_CANCEL 1
#endif
// A temperature sensor
typedef struct TempInfo {
uint16_t acc;
int16_t raw;
celsius_float_t celsius;
inline void reset() { acc = 0; }
inline void sample(const uint16_t s) { acc += s; }
inline void update() { raw = acc; }
} temp_info_t;
// A PWM heater with temperature sensor
typedef struct HeaterInfo : public TempInfo {
celsius_t target;
uint8_t soft_pwm_amount;
} heater_info_t;
// A heater with PID stabilization
template<typename T>
struct PIDHeaterInfo : public HeaterInfo {
T pid; // Initialized by settings.load()
};
#if ENABLED(PIDTEMP)
typedef struct PIDHeaterInfo<hotend_pid_t> hotend_info_t;
#else
typedef heater_info_t hotend_info_t;
#endif
#if HAS_HEATED_BED
#if ENABLED(PIDTEMPBED)
typedef struct PIDHeaterInfo<PID_t> bed_info_t;
#else
typedef heater_info_t bed_info_t;
#endif
#endif
#if HAS_TEMP_PROBE
typedef temp_info_t probe_info_t;
#endif
#if HAS_HEATED_CHAMBER
#if ENABLED(PIDTEMPCHAMBER)
typedef struct PIDHeaterInfo<PID_t> chamber_info_t;
#else
typedef heater_info_t chamber_info_t;
#endif
#elif HAS_TEMP_CHAMBER
typedef temp_info_t chamber_info_t;
#endif
#if EITHER(HAS_COOLER, HAS_TEMP_COOLER)
typedef heater_info_t cooler_info_t;
#endif
// Heater watch handling
template <int INCREASE, int HYSTERESIS, millis_t PERIOD>
struct HeaterWatch {
celsius_t target;
millis_t next_ms;
inline bool elapsed(const millis_t &ms) { return next_ms && ELAPSED(ms, next_ms); }
inline bool elapsed() { return elapsed(millis()); }
inline bool check(const celsius_t curr) { return curr >= target; }
inline void restart(const celsius_t curr, const celsius_t tgt) {
if (tgt) {
const celsius_t newtarget = curr + INCREASE;
if (newtarget < tgt - HYSTERESIS - 1) {
target = newtarget;
next_ms = millis() + SEC_TO_MS(PERIOD);
return;
}
}
next_ms = 0;
}
};
#if WATCH_HOTENDS
typedef struct HeaterWatch<WATCH_TEMP_INCREASE, TEMP_HYSTERESIS, WATCH_TEMP_PERIOD> hotend_watch_t;
#endif
#if WATCH_BED
typedef struct HeaterWatch<WATCH_BED_TEMP_INCREASE, TEMP_BED_HYSTERESIS, WATCH_BED_TEMP_PERIOD> bed_watch_t;
#endif
#if WATCH_CHAMBER
typedef struct HeaterWatch<WATCH_CHAMBER_TEMP_INCREASE, TEMP_CHAMBER_HYSTERESIS, WATCH_CHAMBER_TEMP_PERIOD> chamber_watch_t;
#endif
#if WATCH_COOLER
typedef struct HeaterWatch<WATCH_COOLER_TEMP_INCREASE, TEMP_COOLER_HYSTERESIS, WATCH_COOLER_TEMP_PERIOD> cooler_watch_t;
#endif
// Temperature sensor read value ranges
typedef struct { int16_t raw_min, raw_max; } raw_range_t;
typedef struct { celsius_t mintemp, maxtemp; } celsius_range_t;
typedef struct { int16_t raw_min, raw_max; celsius_t mintemp, maxtemp; } temp_range_t;
#define THERMISTOR_ABS_ZERO_C -273.15f // bbbbrrrrr cold !
#define THERMISTOR_RESISTANCE_NOMINAL_C 25.0f // mmmmm comfortable
#if HAS_USER_THERMISTORS
enum CustomThermistorIndex : uint8_t {
#if TEMP_SENSOR_0_IS_CUSTOM
CTI_HOTEND_0,
#endif
#if TEMP_SENSOR_1_IS_CUSTOM
CTI_HOTEND_1,
#endif
#if TEMP_SENSOR_2_IS_CUSTOM
CTI_HOTEND_2,
#endif
#if TEMP_SENSOR_3_IS_CUSTOM
CTI_HOTEND_3,
#endif
#if TEMP_SENSOR_4_IS_CUSTOM
CTI_HOTEND_4,
#endif
#if TEMP_SENSOR_5_IS_CUSTOM
CTI_HOTEND_5,
#endif
#if TEMP_SENSOR_BED_IS_CUSTOM
CTI_BED,
#endif
#if TEMP_SENSOR_PROBE_IS_CUSTOM
CTI_PROBE,
#endif
#if TEMP_SENSOR_CHAMBER_IS_CUSTOM
CTI_CHAMBER,
#endif
#if COOLER_USER_THERMISTOR
CTI_COOLER,
#endif
USER_THERMISTORS
};
// User-defined thermistor
typedef struct {
bool pre_calc; // true if pre-calculations update needed
float sh_c_coeff, // Steinhart-Hart C coefficient .. defaults to '0.0'
sh_alpha,
series_res,
res_25, res_25_recip,
res_25_log,
beta, beta_recip;
} user_thermistor_t;
#endif
class Temperature {
public:
#if HAS_HOTEND
#if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT)
static temp_info_t temp_redundant;
#endif
static hotend_info_t temp_hotend[HOTENDS];
static const celsius_t hotend_maxtemp[HOTENDS];
static inline celsius_t hotend_max_target(const uint8_t e) { return hotend_maxtemp[e] - (HOTEND_OVERSHOOT); }
#endif
#if ENABLED(HAS_HEATED_BED)
static bed_info_t temp_bed;
#endif
#if ENABLED(HAS_TEMP_PROBE)
static probe_info_t temp_probe;
#endif
#if ENABLED(HAS_TEMP_CHAMBER)
static chamber_info_t temp_chamber;
#endif
#if ENABLED(HAS_TEMP_COOLER)
static cooler_info_t temp_cooler;
#endif
#if ENABLED(AUTO_POWER_E_FANS)
static uint8_t autofan_speed[HOTENDS];
#endif
#if ENABLED(AUTO_POWER_CHAMBER_FAN)
static uint8_t chamberfan_speed;
#endif
#if ENABLED(AUTO_POWER_COOLER_FAN)
static uint8_t coolerfan_speed;
#endif
#if ENABLED(FAN_SOFT_PWM)
static uint8_t soft_pwm_amount_fan[FAN_COUNT],
soft_pwm_count_fan[FAN_COUNT];
#endif
#if ENABLED(PREVENT_COLD_EXTRUSION)
static bool allow_cold_extrude;
static celsius_t extrude_min_temp;
static inline bool tooCold(const celsius_t temp) { return allow_cold_extrude ? false : temp < extrude_min_temp - (TEMP_WINDOW); }
static inline bool tooColdToExtrude(const uint8_t E_NAME) { return tooCold(wholeDegHotend(HOTEND_INDEX)); }
static inline bool targetTooColdToExtrude(const uint8_t E_NAME) { return tooCold(degTargetHotend(HOTEND_INDEX)); }
#else
static inline bool tooColdToExtrude(const uint8_t) { return false; }
static inline bool targetTooColdToExtrude(const uint8_t) { return false; }
#endif
static inline bool hotEnoughToExtrude(const uint8_t e) { return !tooColdToExtrude(e); }
static inline bool targetHotEnoughToExtrude(const uint8_t e) { return !targetTooColdToExtrude(e); }
#if EITHER(SINGLENOZZLE_STANDBY_TEMP, SINGLENOZZLE_STANDBY_FAN)
#if ENABLED(SINGLENOZZLE_STANDBY_TEMP)
static celsius_t singlenozzle_temp[EXTRUDERS];
#endif
#if ENABLED(SINGLENOZZLE_STANDBY_FAN)
static uint8_t singlenozzle_fan_speed[EXTRUDERS];
#endif
static void singlenozzle_change(const uint8_t old_tool, const uint8_t new_tool);
#endif
#if HEATER_IDLE_HANDLER
// Heater idle handling. Marlin creates one per hotend and one for the heated bed.
typedef struct {
millis_t timeout_ms;
bool timed_out;
inline void update(const millis_t &ms) { if (!timed_out && timeout_ms && ELAPSED(ms, timeout_ms)) timed_out = true; }
inline void start(const millis_t &ms) { timeout_ms = millis() + ms; timed_out = false; }
inline void reset() { timeout_ms = 0; timed_out = false; }
inline void expire() { start(0); }
} heater_idle_t;
// Indices and size for the heater_idle array
enum IdleIndex : int8_t {
_II = -1
#define _IDLE_INDEX_E(N) ,IDLE_INDEX_E##N
REPEAT(HOTENDS, _IDLE_INDEX_E)
#undef _IDLE_INDEX_E
OPTARG(HAS_HEATED_BED, IDLE_INDEX_BED)
, NR_HEATER_IDLE
};
// Convert the given heater_id_t to idle array index
static inline IdleIndex idle_index_for_id(const int8_t heater_id) {
TERN_(HAS_HEATED_BED, if (heater_id == H_BED) return IDLE_INDEX_BED);
return (IdleIndex)_MAX(heater_id, 0);
}
static heater_idle_t heater_idle[NR_HEATER_IDLE];
#endif
private:
#if ENABLED(WATCH_HOTENDS)
static hotend_watch_t watch_hotend[HOTENDS];
#endif
#if ENABLED(PID_EXTRUSION_SCALING)
static int32_t last_e_position, lpq[LPQ_MAX_LEN];
static lpq_ptr_t lpq_ptr;
#endif
#if ENABLED(HAS_HOTEND)
static temp_range_t temp_range[HOTENDS];
#endif
#if HAS_HEATED_BED
#if ENABLED(WATCH_BED)
static bed_watch_t watch_bed;
#endif
IF_DISABLED(PIDTEMPBED, static millis_t next_bed_check_ms);
static int16_t mintemp_raw_BED, maxtemp_raw_BED;
#endif
#if HAS_HEATED_CHAMBER
#if ENABLED(WATCH_CHAMBER)
static chamber_watch_t watch_chamber;
#endif
TERN(PIDTEMPCHAMBER,,static millis_t next_chamber_check_ms);
static int16_t mintemp_raw_CHAMBER, maxtemp_raw_CHAMBER;
#endif
#if HAS_COOLER
#if ENABLED(WATCH_COOLER)
static cooler_watch_t watch_cooler;
#endif
static millis_t next_cooler_check_ms, cooler_fan_flush_ms;
static int16_t mintemp_raw_COOLER, maxtemp_raw_COOLER;
#endif
#if MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED > 1
static uint8_t consecutive_low_temperature_error[HOTENDS];
#endif
#if MILLISECONDS_PREHEAT_TIME > 0
static millis_t preheat_end_time[HOTENDS];
#endif
#if ENABLED(HAS_AUTO_FAN)
static millis_t next_auto_fan_check_ms;
#endif
#if ENABLED(PROBING_HEATERS_OFF)
static bool paused_for_probing;
#endif
public:
#if HAS_ADC_BUTTONS
static uint32_t current_ADCKey_raw;
static uint16_t ADCKey_count;
#endif
#if ENABLED(PID_EXTRUSION_SCALING)
static int16_t lpq_len;
#endif
/**
* Instance Methods
*/
void init();
/**
* Static (class) methods
*/
#if HAS_USER_THERMISTORS
static user_thermistor_t user_thermistor[USER_THERMISTORS];
static void log_user_thermistor(const uint8_t t_index, const bool eprom=false);
static void reset_user_thermistors();
static celsius_float_t user_thermistor_to_deg_c(const uint8_t t_index, const int16_t raw);
static inline bool set_pull_up_res(int8_t t_index, float value) {
//if (!WITHIN(t_index, 0, USER_THERMISTORS - 1)) return false;
if (!WITHIN(value, 1, 1000000)) return false;
user_thermistor[t_index].series_res = value;
return true;
}
static inline bool set_res25(int8_t t_index, float value) {
if (!WITHIN(value, 1, 10000000)) return false;
user_thermistor[t_index].res_25 = value;
user_thermistor[t_index].pre_calc = true;
return true;
}
static inline bool set_beta(int8_t t_index, float value) {
if (!WITHIN(value, 1, 1000000)) return false;
user_thermistor[t_index].beta = value;
user_thermistor[t_index].pre_calc = true;
return true;
}
static inline bool set_sh_coeff(int8_t t_index, float value) {
if (!WITHIN(value, -0.01f, 0.01f)) return false;
user_thermistor[t_index].sh_c_coeff = value;
user_thermistor[t_index].pre_calc = true;
return true;
}
#endif
#if HAS_HOTEND
static celsius_float_t analog_to_celsius_hotend(const int16_t raw, const uint8_t e);
#endif
#if HAS_HEATED_BED
static celsius_float_t analog_to_celsius_bed(const int16_t raw);
#endif
#if HAS_TEMP_PROBE
static celsius_float_t analog_to_celsius_probe(const int16_t raw);
#endif
#if HAS_TEMP_CHAMBER
static celsius_float_t analog_to_celsius_chamber(const int16_t raw);
#endif
#if HAS_TEMP_COOLER
static celsius_float_t analog_to_celsius_cooler(const int16_t raw);
#endif
#if HAS_FAN
static uint8_t fan_speed[FAN_COUNT];
#define FANS_LOOP(I) LOOP_L_N(I, FAN_COUNT)
static void set_fan_speed(const uint8_t fan, const uint16_t speed);
#if ENABLED(REPORT_FAN_CHANGE)
static void report_fan_speed(const uint8_t fan);
#endif
#if EITHER(PROBING_FANS_OFF, ADVANCED_PAUSE_FANS_PAUSE)
static bool fans_paused;
static uint8_t saved_fan_speed[FAN_COUNT];
#endif
#if ENABLED(ADAPTIVE_FAN_SLOWING)
static uint8_t fan_speed_scaler[FAN_COUNT];
#endif
static inline uint8_t scaledFanSpeed(const uint8_t fan, const uint8_t fs) {
UNUSED(fan); // Potentially unused!
return (fs * uint16_t(TERN(ADAPTIVE_FAN_SLOWING, fan_speed_scaler[fan], 128))) >> 7;
}
static inline uint8_t scaledFanSpeed(const uint8_t fan) {
return scaledFanSpeed(fan, fan_speed[fan]);
}
static constexpr inline uint8_t pwmToPercent(const uint8_t speed) { return ui8_to_percent(speed); }
static inline uint8_t fanSpeedPercent(const uint8_t fan) { return ui8_to_percent(fan_speed[fan]); }
static inline uint8_t scaledFanSpeedPercent(const uint8_t fan) { return ui8_to_percent(scaledFanSpeed(fan)); }
#if ENABLED(EXTRA_FAN_SPEED)
typedef struct { uint8_t saved, speed; } extra_fan_t;
static extra_fan_t extra_fan_speed[FAN_COUNT];
static void set_temp_fan_speed(const uint8_t fan, const uint16_t command_or_speed);
#endif
#if EITHER(PROBING_FANS_OFF, ADVANCED_PAUSE_FANS_PAUSE)
void set_fans_paused(const bool p);
#endif
#endif // HAS_FAN
static inline void zero_fan_speeds() {
#if HAS_FAN
FANS_LOOP(i) set_fan_speed(i, 0);
#endif
}
/**
* Called from the Temperature ISR
*/
static void isr();
static void readings_ready();
/**
* Call periodically to manage heaters
*/
static void manage_heater() _O2; // Added _O2 to work around a compiler error
/**
* Preheating hotends
*/
#if MILLISECONDS_PREHEAT_TIME > 0
static inline bool is_preheating(const uint8_t E_NAME) {
return preheat_end_time[HOTEND_INDEX] && PENDING(millis(), preheat_end_time[HOTEND_INDEX]);
}
static inline void start_preheat_time(const uint8_t E_NAME) {
preheat_end_time[HOTEND_INDEX] = millis() + MILLISECONDS_PREHEAT_TIME;
}
static inline void reset_preheat_time(const uint8_t E_NAME) {
preheat_end_time[HOTEND_INDEX] = 0;
}
#else
#define is_preheating(n) (false)
#endif
//high level conversion routines, for use outside of temperature.cpp
//inline so that there is no performance decrease.
//deg=degreeCelsius
static inline celsius_float_t degHotend(const uint8_t E_NAME) {
return TERN0(HAS_HOTEND, temp_hotend[HOTEND_INDEX].celsius);
}
#if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT)
static inline celsius_float_t degHotendRedundant() { return temp_redundant.celsius; }
#endif
static inline celsius_t wholeDegHotend(const uint8_t E_NAME) {
return TERN0(HAS_HOTEND, static_cast<celsius_t>(temp_hotend[HOTEND_INDEX].celsius + 0.5f));
}
#if ENABLED(SHOW_TEMP_ADC_VALUES)
static inline int16_t rawHotendTemp(const uint8_t E_NAME) {
return TERN0(HAS_HOTEND, temp_hotend[HOTEND_INDEX].raw);
}
#if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT)
static inline int16_t rawHotendTempRedundant() { return temp_redundant.raw; }
#endif
#endif
static inline celsius_t degTargetHotend(const uint8_t E_NAME) {
return TERN0(HAS_HOTEND, temp_hotend[HOTEND_INDEX].target);
}
#if HAS_HOTEND
static void setTargetHotend(const celsius_t celsius, const uint8_t E_NAME) {
const uint8_t ee = HOTEND_INDEX;
#if MILLISECONDS_PREHEAT_TIME > 0
if (celsius == 0)
reset_preheat_time(ee);
else if (temp_hotend[ee].target == 0)
start_preheat_time(ee);
#endif
TERN_(AUTO_POWER_CONTROL, if (celsius) powerManager.power_on());
temp_hotend[ee].target = _MIN(celsius, hotend_max_target(ee));
start_watching_hotend(ee);
}
static inline bool isHeatingHotend(const uint8_t E_NAME) {
return temp_hotend[HOTEND_INDEX].target > temp_hotend[HOTEND_INDEX].celsius;
}
static inline bool isCoolingHotend(const uint8_t E_NAME) {
return temp_hotend[HOTEND_INDEX].target < temp_hotend[HOTEND_INDEX].celsius;
}
#if HAS_TEMP_HOTEND
static bool wait_for_hotend(const uint8_t target_extruder, const bool no_wait_for_cooling=true
OPTARG(G26_CLICK_CAN_CANCEL, const bool click_to_cancel=false)
);
#if ENABLED(WAIT_FOR_HOTEND)
static void wait_for_hotend_heating(const uint8_t target_extruder);
#endif
#endif
static inline bool still_heating(const uint8_t e) {
return degTargetHotend(e) > TEMP_HYSTERESIS && ABS(wholeDegHotend(e) - degTargetHotend(e)) > TEMP_HYSTERESIS;
}
static inline bool degHotendNear(const uint8_t e, const celsius_t temp) {
return ABS(wholeDegHotend(e) - temp) < (TEMP_HYSTERESIS);
}
// Start watching a Hotend to make sure it's really heating up
static inline void start_watching_hotend(const uint8_t E_NAME) {
UNUSED(HOTEND_INDEX);
#if WATCH_HOTENDS
watch_hotend[HOTEND_INDEX].restart(degHotend(HOTEND_INDEX), degTargetHotend(HOTEND_INDEX));
#endif
}
#endif // HAS_HOTEND
#if HAS_HEATED_BED
#if ENABLED(SHOW_TEMP_ADC_VALUES)
static inline int16_t rawBedTemp() { return temp_bed.raw; }
#endif
static inline celsius_float_t degBed() { return temp_bed.celsius; }
static inline celsius_t wholeDegBed() { return static_cast<celsius_t>(degBed() + 0.5f); }
static inline celsius_t degTargetBed() { return temp_bed.target; }
static inline bool isHeatingBed() { return temp_bed.target > temp_bed.celsius; }
static inline bool isCoolingBed() { return temp_bed.target < temp_bed.celsius; }
// Start watching the Bed to make sure it's really heating up
static inline void start_watching_bed() { TERN_(WATCH_BED, watch_bed.restart(degBed(), degTargetBed())); }
static void setTargetBed(const celsius_t celsius) {
TERN_(AUTO_POWER_CONTROL, if (celsius) powerManager.power_on());
temp_bed.target = _MIN(celsius, BED_MAX_TARGET);
start_watching_bed();
}
static bool wait_for_bed(const bool no_wait_for_cooling=true
OPTARG(G26_CLICK_CAN_CANCEL, const bool click_to_cancel=false)
);
static void wait_for_bed_heating();
static inline bool degBedNear(const celsius_t temp) {
return ABS(wholeDegBed() - temp) < (TEMP_BED_HYSTERESIS);
}
#endif // HAS_HEATED_BED
#if HAS_TEMP_PROBE
#if ENABLED(SHOW_TEMP_ADC_VALUES)
static inline int16_t rawProbeTemp() { return temp_probe.raw; }
#endif
static inline celsius_float_t degProbe() { return temp_probe.celsius; }
static inline celsius_t wholeDegProbe() { return static_cast<celsius_t>(degProbe() + 0.5f); }
static inline bool isProbeBelowTemp(const celsius_t target_temp) { return wholeDegProbe() < target_temp; }
static inline bool isProbeAboveTemp(const celsius_t target_temp) { return wholeDegProbe() > target_temp; }
static bool wait_for_probe(const celsius_t target_temp, bool no_wait_for_cooling=true);
#endif
#if HAS_TEMP_CHAMBER
#if ENABLED(SHOW_TEMP_ADC_VALUES)
static inline int16_t rawChamberTemp() { return temp_chamber.raw; }
#endif
static inline celsius_float_t degChamber() { return temp_chamber.celsius; }
static inline celsius_t wholeDegChamber() { return static_cast<celsius_t>(degChamber() + 0.5f); }
#if HAS_HEATED_CHAMBER
static inline celsius_t degTargetChamber() { return temp_chamber.target; }
static inline bool isHeatingChamber() { return temp_chamber.target > temp_chamber.celsius; }
static inline bool isCoolingChamber() { return temp_chamber.target < temp_chamber.celsius; }
static bool wait_for_chamber(const bool no_wait_for_cooling=true);
#endif
#endif
#if HAS_HEATED_CHAMBER
static void setTargetChamber(const celsius_t celsius) {
temp_chamber.target = _MIN(celsius, CHAMBER_MAX_TARGET);
start_watching_chamber();
}
// Start watching the Chamber to make sure it's really heating up
static inline void start_watching_chamber() { TERN_(WATCH_CHAMBER, watch_chamber.restart(degChamber(), degTargetChamber())); }
#endif
#if HAS_TEMP_COOLER
#if ENABLED(SHOW_TEMP_ADC_VALUES)
static inline int16_t rawCoolerTemp() { return temp_cooler.raw; }
#endif
static inline celsius_float_t degCooler() { return temp_cooler.celsius; }
static inline celsius_t wholeDegCooler() { return static_cast<celsius_t>(temp_cooler.celsius + 0.5f); }
#if HAS_COOLER
static inline celsius_t degTargetCooler() { return temp_cooler.target; }
static inline bool isLaserHeating() { return temp_cooler.target > temp_cooler.celsius; }
static inline bool isLaserCooling() { return temp_cooler.target < temp_cooler.celsius; }
static bool wait_for_cooler(const bool no_wait_for_cooling=true);
#endif
#endif
#if HAS_COOLER
static inline void setTargetCooler(const celsius_t celsius) {
temp_cooler.target = constrain(celsius, COOLER_MIN_TARGET, COOLER_MAX_TARGET);
start_watching_cooler();
}
// Start watching the Cooler to make sure it's really cooling down
static inline void start_watching_cooler() { TERN_(WATCH_COOLER, watch_cooler.restart(degCooler(), degTargetCooler())); }
#endif
/**
* The software PWM power for a heater
*/
static int16_t getHeaterPower(const heater_id_t heater_id);
/**
* Switch off all heaters, set all target temperatures to 0
*/
static void disable_all_heaters();
#if ENABLED(PRINTJOB_TIMER_AUTOSTART)
/**
* Methods to check if heaters are enabled, indicating an active job
*/
static bool auto_job_over_threshold();
static void auto_job_check_timer(const bool can_start, const bool can_stop);
#endif
/**
* Perform auto-tuning for hotend or bed in response to M303
*/
#if HAS_PID_HEATING
#if ANY(PID_DEBUG, PID_BED_DEBUG, PID_CHAMBER_DEBUG)
static bool pid_debug_flag;
#endif
static void PID_autotune(const celsius_t target, const heater_id_t heater_id, const int8_t ncycles, const bool set_result=false);
#if ENABLED(NO_FAN_SLOWING_IN_PID_TUNING)
static bool adaptive_fan_slowing;
#elif ENABLED(ADAPTIVE_FAN_SLOWING)
static constexpr bool adaptive_fan_slowing = true;
#endif
/**
* Update the temp manager when PID values change
*/
#if ENABLED(PIDTEMP)
static inline void updatePID() {
TERN_(PID_EXTRUSION_SCALING, last_e_position = 0);
}
#endif
#endif
#if ENABLED(PROBING_HEATERS_OFF)
static void pause_heaters(const bool p);
#endif
#if HEATER_IDLE_HANDLER
static inline void reset_hotend_idle_timer(const uint8_t E_NAME) {
heater_idle[HOTEND_INDEX].reset();
start_watching_hotend(HOTEND_INDEX);
}
#if HAS_HEATED_BED
static inline void reset_bed_idle_timer() {
heater_idle[IDLE_INDEX_BED].reset();
start_watching_bed();
}
#endif
#endif // HEATER_IDLE_HANDLER
#if HAS_TEMP_SENSOR
static void print_heater_states(const uint8_t target_extruder
OPTARG(TEMP_SENSOR_1_AS_REDUNDANT, const bool include_r=false)
);
#if ENABLED(AUTO_REPORT_TEMPERATURES)
struct AutoReportTemp { static void report(); };
static AutoReporter<AutoReportTemp> auto_reporter;
#endif
#endif
#if HAS_HOTEND && HAS_STATUS_MESSAGE
static void set_heating_message(const uint8_t e);
#else
static inline void set_heating_message(const uint8_t) {}
#endif
#if HAS_LCD_MENU && HAS_TEMPERATURE
static void lcd_preheat(const uint8_t e, const int8_t indh, const int8_t indb);
#endif
private:
// Reading raw temperatures and converting to Celsius when ready
static volatile bool raw_temps_ready;
static void update_raw_temperatures();
static void updateTemperaturesFromRawValues();
static inline bool updateTemperaturesIfReady() {
if (!raw_temps_ready) return false;
updateTemperaturesFromRawValues();
raw_temps_ready = false;
return true;
}
// MAX Thermocouples
#if HAS_MAX_TC
#define MAX_TC_COUNT 1 + BOTH(TEMP_SENSOR_0_IS_MAX_TC, TEMP_SENSOR_1_IS_MAX_TC)
#if MAX_TC_COUNT > 1
#define HAS_MULTI_MAX_TC 1
#define READ_MAX_TC(N) read_max_tc(N)
#else
#define READ_MAX_TC(N) read_max_tc()
#endif
static int read_max_tc(TERN_(HAS_MULTI_MAX_TC, const uint8_t hindex=0));
#endif
static void checkExtruderAutoFans();
#if ENABLED(HAS_HOTEND)
static float get_pid_output_hotend(const uint8_t e);
#endif
#if ENABLED(PIDTEMPBED)
static float get_pid_output_bed();
#endif
#if ENABLED(PIDTEMPCHAMBER)
static float get_pid_output_chamber();
#endif
static void _temp_error(const heater_id_t e, PGM_P const serial_msg, PGM_P const lcd_msg);
static void min_temp_error(const heater_id_t e);
static void max_temp_error(const heater_id_t e);
#define HAS_THERMAL_PROTECTION ANY(THERMAL_PROTECTION_HOTENDS, THERMAL_PROTECTION_CHAMBER, HAS_THERMALLY_PROTECTED_BED, THERMAL_PROTECTION_COOLER)
#if HAS_THERMAL_PROTECTION
// Indices and size for the tr_state_machine array. One for each protected heater.
enum RunawayIndex : int8_t {
_RI = -1
#if ENABLED(THERMAL_PROTECTION_HOTENDS)
#define _RUNAWAY_IND_E(N) ,RUNAWAY_IND_E##N
REPEAT(HOTENDS, _RUNAWAY_IND_E)
#undef _RUNAWAY_IND_E
#endif
OPTARG(HAS_THERMALLY_PROTECTED_BED, RUNAWAY_IND_BED)
OPTARG(THERMAL_PROTECTION_CHAMBER, RUNAWAY_IND_CHAMBER)
OPTARG(THERMAL_PROTECTION_COOLER, RUNAWAY_IND_COOLER)
, NR_HEATER_RUNAWAY
};
// Convert the given heater_id_t to runaway state array index
static inline RunawayIndex runaway_index_for_id(const int8_t heater_id) {
TERN_(HAS_THERMALLY_PROTECTED_CHAMBER, if (heater_id == H_CHAMBER) return RUNAWAY_IND_CHAMBER);
TERN_(HAS_THERMALLY_PROTECTED_CHAMBER, if (heater_id == H_COOLER) return RUNAWAY_IND_COOLER);
TERN_(HAS_THERMALLY_PROTECTED_BED, if (heater_id == H_BED) return RUNAWAY_IND_BED);
return (RunawayIndex)_MAX(heater_id, 0);
}
enum TRState : char { TRInactive, TRFirstHeating, TRStable, TRRunaway };
typedef struct {
millis_t timer = 0;
TRState state = TRInactive;
float running_temp;
void run(const_celsius_float_t current, const_celsius_float_t target, const heater_id_t heater_id, const uint16_t period_seconds, const celsius_t hysteresis_degc);
} tr_state_machine_t;
static tr_state_machine_t tr_state_machine[NR_HEATER_RUNAWAY];
#endif // HAS_THERMAL_PROTECTION
};
extern Temperature thermalManager;
extern PID_t auto_pid; // Auto PID value
@@ -0,0 +1,94 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
// R25 = 100 kOhm, beta25 = 4092 K, 4.7 kOhm pull-up, bed thermistor
const temp_entry_t temptable_1[] PROGMEM = {
{ OV( 18), 320 },
{ OV( 19), 315 },
{ OV( 20), 310 },
{ OV( 22), 305 },
{ OV( 23), 300 },
{ OV( 25), 295 },
{ OV( 27), 290 },
{ OV( 28), 285 },
{ OV( 31), 280 },
{ OV( 33), 275 },
{ OV( 35), 270 },
{ OV( 38), 265 },
{ OV( 41), 260 },
{ OV( 44), 255 },
{ OV( 48), 250 },
{ OV( 52), 245 },
{ OV( 56), 240 },
{ OV( 61), 235 },
{ OV( 66), 230 },
{ OV( 71), 225 },
{ OV( 78), 220 },
{ OV( 84), 215 },
{ OV( 92), 210 },
{ OV( 100), 205 },
{ OV( 109), 200 },
{ OV( 120), 195 },
{ OV( 131), 190 },
{ OV( 143), 185 },
{ OV( 156), 180 },
{ OV( 171), 175 },
{ OV( 187), 170 },
{ OV( 205), 165 },
{ OV( 224), 160 },
{ OV( 245), 155 },
{ OV( 268), 150 },
{ OV( 293), 145 },
{ OV( 320), 140 },
{ OV( 348), 135 },
{ OV( 379), 130 },
{ OV( 411), 125 },
{ OV( 445), 120 },
{ OV( 480), 115 },
{ OV( 516), 110 },
{ OV( 553), 105 },
{ OV( 591), 100 },
{ OV( 628), 95 },
{ OV( 665), 90 },
{ OV( 702), 85 },
{ OV( 737), 80 },
{ OV( 770), 75 },
{ OV( 801), 70 },
{ OV( 830), 65 },
{ OV( 857), 60 },
{ OV( 881), 55 },
{ OV( 903), 50 },
{ OV( 922), 45 },
{ OV( 939), 40 },
{ OV( 954), 35 },
{ OV( 966), 30 },
{ OV( 977), 25 },
{ OV( 985), 20 },
{ OV( 993), 15 },
{ OV( 999), 10 },
{ OV(1004), 5 },
{ OV(1008), 0 },
{ OV(1012), -5 },
{ OV(1016), -10 },
{ OV(1020), -15 }
};
@@ -0,0 +1,57 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
// R25 = 100 kOhm, beta25 = 3960 K, 4.7 kOhm pull-up, RS thermistor 198-961
const temp_entry_t temptable_10[] PROGMEM = {
{ OV( 1), 929 },
{ OV( 36), 299 },
{ OV( 71), 246 },
{ OV( 106), 217 },
{ OV( 141), 198 },
{ OV( 176), 184 },
{ OV( 211), 173 },
{ OV( 246), 163 },
{ OV( 281), 154 },
{ OV( 316), 147 },
{ OV( 351), 140 },
{ OV( 386), 134 },
{ OV( 421), 128 },
{ OV( 456), 122 },
{ OV( 491), 117 },
{ OV( 526), 112 },
{ OV( 561), 107 },
{ OV( 596), 102 },
{ OV( 631), 97 },
{ OV( 666), 91 },
{ OV( 701), 86 },
{ OV( 736), 81 },
{ OV( 771), 76 },
{ OV( 806), 70 },
{ OV( 841), 63 },
{ OV( 876), 56 },
{ OV( 911), 48 },
{ OV( 946), 38 },
{ OV( 981), 23 },
{ OV(1005), 5 },
{ OV(1016), 0 }
};
@@ -0,0 +1,41 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
#define REVERSE_TEMP_SENSOR_RANGE_1010 1
// Pt1000 with 1k0 pullup
const temp_entry_t temptable_1010[] PROGMEM = {
PtLine( 0, 1000, 1000),
PtLine( 25, 1000, 1000),
PtLine( 50, 1000, 1000),
PtLine( 75, 1000, 1000),
PtLine(100, 1000, 1000),
PtLine(125, 1000, 1000),
PtLine(150, 1000, 1000),
PtLine(175, 1000, 1000),
PtLine(200, 1000, 1000),
PtLine(225, 1000, 1000),
PtLine(250, 1000, 1000),
PtLine(275, 1000, 1000),
PtLine(300, 1000, 1000)
};
@@ -0,0 +1,40 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
#define REVERSE_TEMP_SENSOR_RANGE_1047 1
// Pt1000 with 4k7 pullup
const temp_entry_t temptable_1047[] PROGMEM = {
// only a few values are needed as the curve is very flat
PtLine( 0, 1000, 4700),
PtLine( 50, 1000, 4700),
PtLine(100, 1000, 4700),
PtLine(150, 1000, 4700),
PtLine(200, 1000, 4700),
PtLine(250, 1000, 4700),
PtLine(300, 1000, 4700),
PtLine(350, 1000, 4700),
PtLine(400, 1000, 4700),
PtLine(450, 1000, 4700),
PtLine(500, 1000, 4700)
};
@@ -0,0 +1,76 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
// R25 = 100 kOhm, beta25 = 3950 K, 4.7 kOhm pull-up, QU-BD silicone bed QWG-104F-3950 thermistor
const temp_entry_t temptable_11[] PROGMEM = {
{ OV( 1), 938 },
{ OV( 31), 314 },
{ OV( 41), 290 },
{ OV( 51), 272 },
{ OV( 61), 258 },
{ OV( 71), 247 },
{ OV( 81), 237 },
{ OV( 91), 229 },
{ OV( 101), 221 },
{ OV( 111), 215 },
{ OV( 121), 209 },
{ OV( 131), 204 },
{ OV( 141), 199 },
{ OV( 151), 195 },
{ OV( 161), 190 },
{ OV( 171), 187 },
{ OV( 181), 183 },
{ OV( 191), 179 },
{ OV( 201), 176 },
{ OV( 221), 170 },
{ OV( 241), 165 },
{ OV( 261), 160 },
{ OV( 281), 155 },
{ OV( 301), 150 },
{ OV( 331), 144 },
{ OV( 361), 139 },
{ OV( 391), 133 },
{ OV( 421), 128 },
{ OV( 451), 123 },
{ OV( 491), 117 },
{ OV( 531), 111 },
{ OV( 571), 105 },
{ OV( 611), 100 },
{ OV( 641), 95 },
{ OV( 681), 90 },
{ OV( 711), 85 },
{ OV( 751), 79 },
{ OV( 791), 72 },
{ OV( 811), 69 },
{ OV( 831), 65 },
{ OV( 871), 57 },
{ OV( 881), 55 },
{ OV( 901), 51 },
{ OV( 921), 45 },
{ OV( 941), 39 },
{ OV( 971), 28 },
{ OV( 981), 23 },
{ OV( 991), 17 },
{ OV(1001), 9 },
{ OV(1021), -27 }
};
@@ -0,0 +1,36 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
#define REVERSE_TEMP_SENSOR_RANGE_110 1
// Pt100 with 1k0 pullup
const temp_entry_t temptable_110[] PROGMEM = {
// only a few values are needed as the curve is very flat
PtLine( 0, 100, 1000),
PtLine( 50, 100, 1000),
PtLine(100, 100, 1000),
PtLine(150, 100, 1000),
PtLine(200, 100, 1000),
PtLine(250, 100, 1000),
PtLine(300, 100, 1000)
};
@@ -0,0 +1,56 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
// R25 = 100 kOhm, beta25 = 4700 K, 4.7 kOhm pull-up, (personal calibration for Makibox hot bed)
const temp_entry_t temptable_12[] PROGMEM = {
{ OV( 35), 180 }, // top rating 180C
{ OV( 211), 140 },
{ OV( 233), 135 },
{ OV( 261), 130 },
{ OV( 290), 125 },
{ OV( 328), 120 },
{ OV( 362), 115 },
{ OV( 406), 110 },
{ OV( 446), 105 },
{ OV( 496), 100 },
{ OV( 539), 95 },
{ OV( 585), 90 },
{ OV( 629), 85 },
{ OV( 675), 80 },
{ OV( 718), 75 },
{ OV( 758), 70 },
{ OV( 793), 65 },
{ OV( 822), 60 },
{ OV( 841), 55 },
{ OV( 875), 50 },
{ OV( 899), 45 },
{ OV( 926), 40 },
{ OV( 946), 35 },
{ OV( 962), 30 },
{ OV( 977), 25 },
{ OV( 987), 20 },
{ OV( 995), 15 },
{ OV(1001), 10 },
{ OV(1010), 0 },
{ OV(1023), -40 }
};
@@ -0,0 +1,49 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
// R25 = 100 kOhm, beta25 = 4100 K, 4.7 kOhm pull-up, Hisens thermistor
const temp_entry_t temptable_13[] PROGMEM = {
{ OV( 20.04), 300 },
{ OV( 23.19), 290 },
{ OV( 26.71), 280 },
{ OV( 31.23), 270 },
{ OV( 36.52), 260 },
{ OV( 42.75), 250 },
{ OV( 50.68), 240 },
{ OV( 60.22), 230 },
{ OV( 72.03), 220 },
{ OV( 86.84), 210 },
{ OV(102.79), 200 },
{ OV(124.46), 190 },
{ OV(151.02), 180 },
{ OV(182.86), 170 },
{ OV(220.72), 160 },
{ OV(316.96), 140 },
{ OV(447.17), 120 },
{ OV(590.61), 100 },
{ OV(737.31), 80 },
{ OV(857.77), 60 },
{ OV(939.52), 40 },
{ OV(986.03), 20 },
{ OV(1008.7), 0 }
};
@@ -0,0 +1,95 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
// R25 = 100 kOhm, beta25 = 4092 K, 4.7 kOhm pull-up, bed thermistor
const temp_entry_t temptable_14[] PROGMEM = {
{ OV( 16), 320 },
{ OV( 15), 315 },
{ OV( 16), 310 },
{ OV( 17), 305 },
{ OV( 18), 300 },
{ OV( 19), 295 },
{ OV( 20), 290 },
{ OV( 21), 285 },
{ OV( 22), 280 },
{ OV( 23), 275 },
{ OV( 25), 270 },
{ OV( 27), 265 },
{ OV( 28), 260 },
{ OV( 31), 255 },
{ OV( 33), 250 },
{ OV( 35), 245 },
{ OV( 38), 240 },
{ OV( 41), 235 },
{ OV( 44), 230 },
{ OV( 47), 225 },
{ OV( 52), 220 },
{ OV( 56), 215 },
{ OV( 62), 210 },
{ OV( 68), 205 },
{ OV( 74), 200 },
{ OV( 81), 195 },
{ OV( 90), 190 },
{ OV( 99), 185 },
{ OV( 108), 180 },
{ OV( 121), 175 },
{ OV( 133), 170 },
{ OV( 147), 165 },
{ OV( 162), 160 },
{ OV( 180), 155 },
{ OV( 199), 150 },
{ OV( 219), 145 },
{ OV( 243), 140 },
{ OV( 268), 135 },
{ OV( 296), 130 },
{ OV( 326), 125 },
{ OV( 358), 120 },
{ OV( 398), 115 },
{ OV( 435), 110 },
{ OV( 476), 105 },
{ OV( 510), 100 },
{ OV( 566), 95 },
{ OV( 610), 90 },
{ OV( 658), 85 },
{ OV( 703), 80 },
{ OV( 742), 75 },
{ OV( 773), 70 },
{ OV( 807), 65 },
{ OV( 841), 60 },
{ OV( 871), 55 },
{ OV( 895), 50 },
{ OV( 918), 45 },
{ OV( 937), 40 },
{ OV( 954), 35 },
{ OV( 968), 30 },
{ OV( 978), 25 },
{ OV( 985), 20 },
{ OV( 993), 15 },
{ OV( 999), 10 },
{ OV(1004), 5 },
{ OV(1008), 0 },
{ OV(1012), -5 },
{ OV(1016), -10 },
{ OV(1020), -15 }
};
@@ -0,0 +1,36 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
#define REVERSE_TEMP_SENSOR_RANGE_147 1
// Pt100 with 4k7 pullup
const temp_entry_t temptable_147[] PROGMEM = {
// only a few values are needed as the curve is very flat
PtLine( 0, 100, 4700),
PtLine( 50, 100, 4700),
PtLine(100, 100, 4700),
PtLine(150, 100, 4700),
PtLine(200, 100, 4700),
PtLine(250, 100, 4700),
PtLine(300, 100, 4700)
};
@@ -0,0 +1,65 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
// 100k bed thermistor in JGAurora A5. Calibrated by Sam Pinches 21st Jan 2018 using cheap k-type thermocouple inserted into heater block, using TM-902C meter.
const temp_entry_t temptable_15[] PROGMEM = {
{ OV( 31), 275 },
{ OV( 33), 270 },
{ OV( 35), 260 },
{ OV( 38), 253 },
{ OV( 41), 248 },
{ OV( 48), 239 },
{ OV( 56), 232 },
{ OV( 66), 222 },
{ OV( 78), 212 },
{ OV( 93), 206 },
{ OV( 106), 199 },
{ OV( 118), 191 },
{ OV( 130), 186 },
{ OV( 158), 176 },
{ OV( 187), 167 },
{ OV( 224), 158 },
{ OV( 270), 148 },
{ OV( 321), 137 },
{ OV( 379), 127 },
{ OV( 446), 117 },
{ OV( 518), 106 },
{ OV( 593), 96 },
{ OV( 668), 86 },
{ OV( 739), 76 },
{ OV( 767), 72 },
{ OV( 830), 62 },
{ OV( 902), 48 },
{ OV( 926), 45 },
{ OV( 955), 35 },
{ OV( 966), 30 },
{ OV( 977), 25 },
{ OV( 985), 20 },
{ OV( 993), 15 },
{ OV( 999), 10 },
{ OV(1004), 5 },
{ OV(1008), 0 },
{ OV(1012), -5 },
{ OV(1016), -10 },
{ OV(1020), -15 }
};
@@ -0,0 +1,78 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
// Dagoma NTC 100k white thermistor
const temp_entry_t temptable_17[] PROGMEM = {
{ OV( 16), 309 },
{ OV( 18), 307 },
{ OV( 20), 300 },
{ OV( 22), 293 },
{ OV( 26), 284 },
{ OV( 29), 272 },
{ OV( 33), 266 },
{ OV( 36), 260 },
{ OV( 42), 252 },
{ OV( 46), 247 },
{ OV( 48), 244 },
{ OV( 51), 241 },
{ OV( 62), 231 },
{ OV( 73), 222 },
{ OV( 78), 219 },
{ OV( 87), 212 },
{ OV( 98), 207 },
{ OV( 109), 201 },
{ OV( 118), 197 },
{ OV( 131), 191 },
{ OV( 145), 186 },
{ OV( 160), 181 },
{ OV( 177), 175 },
{ OV( 203), 169 },
{ OV( 222), 164 },
{ OV( 256), 156 },
{ OV( 283), 151 },
{ OV( 312), 145 },
{ OV( 343), 140 },
{ OV( 377), 131 },
{ OV( 413), 125 },
{ OV( 454), 119 },
{ OV( 496), 113 },
{ OV( 537), 108 },
{ OV( 578), 102 },
{ OV( 619), 97 },
{ OV( 658), 92 },
{ OV( 695), 87 },
{ OV( 735), 81 },
{ OV( 773), 75 },
{ OV( 808), 70 },
{ OV( 844), 64 },
{ OV( 868), 59 },
{ OV( 892), 54 },
{ OV( 914), 49 },
{ OV( 935), 42 },
{ OV( 951), 38 },
{ OV( 967), 32 },
{ OV( 975), 28 },
{ OV(1000), 20 },
{ OV(1010), 10 },
{ OV(1024), -273 } // for safety
};
@@ -0,0 +1,59 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
// ATC Semitec 204GT-2 (4.7k pullup) Dagoma.Fr - MKS_Base_DKU001327 - version (measured/tested/approved)
const temp_entry_t temptable_18[] PROGMEM = {
{ OV( 1), 713 },
{ OV( 17), 284 },
{ OV( 20), 275 },
{ OV( 23), 267 },
{ OV( 27), 257 },
{ OV( 31), 250 },
{ OV( 37), 240 },
{ OV( 43), 232 },
{ OV( 51), 222 },
{ OV( 61), 213 },
{ OV( 73), 204 },
{ OV( 87), 195 },
{ OV( 106), 185 },
{ OV( 128), 175 },
{ OV( 155), 166 },
{ OV( 189), 156 },
{ OV( 230), 146 },
{ OV( 278), 137 },
{ OV( 336), 127 },
{ OV( 402), 117 },
{ OV( 476), 107 },
{ OV( 554), 97 },
{ OV( 635), 87 },
{ OV( 713), 78 },
{ OV( 784), 68 },
{ OV( 846), 58 },
{ OV( 897), 49 },
{ OV( 937), 39 },
{ OV( 966), 30 },
{ OV( 986), 20 },
{ OV(1000), 10 },
{ OV(1010), 0 },
{ OV(1024),-273 } // for safety
};
@@ -0,0 +1,62 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
//
// R25 = 200 kOhm, beta25 = 4338 K, 4.7 kOhm pull-up, ATC Semitec 204GT-2
// Verified by linagee. Source: https://www.mouser.com/datasheet/2/362/semitec%20usa%20corporation_gtthermistor-1202937.pdf
// Calculated using 4.7kohm pullup, voltage divider math, and manufacturer provided temp/resistance
//
const temp_entry_t temptable_2[] PROGMEM = {
{ OV( 1), 848 },
{ OV( 30), 300 }, // top rating 300C
{ OV( 34), 290 },
{ OV( 39), 280 },
{ OV( 46), 270 },
{ OV( 53), 260 },
{ OV( 63), 250 },
{ OV( 74), 240 },
{ OV( 87), 230 },
{ OV( 104), 220 },
{ OV( 124), 210 },
{ OV( 148), 200 },
{ OV( 176), 190 },
{ OV( 211), 180 },
{ OV( 252), 170 },
{ OV( 301), 160 },
{ OV( 357), 150 },
{ OV( 420), 140 },
{ OV( 489), 130 },
{ OV( 562), 120 },
{ OV( 636), 110 },
{ OV( 708), 100 },
{ OV( 775), 90 },
{ OV( 835), 80 },
{ OV( 884), 70 },
{ OV( 924), 60 },
{ OV( 955), 50 },
{ OV( 977), 40 },
{ OV( 993), 30 },
{ OV(1004), 20 },
{ OV(1012), 10 },
{ OV(1016), 0 }
};
@@ -0,0 +1,77 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
#define REVERSE_TEMP_SENSOR_RANGE_20 1
// Pt100 with INA826 amp on Ultimaker v2.0 electronics
const temp_entry_t temptable_20[] PROGMEM = {
{ OV( 0), 0 },
{ OV(227), 1 },
{ OV(236), 10 },
{ OV(245), 20 },
{ OV(253), 30 },
{ OV(262), 40 },
{ OV(270), 50 },
{ OV(279), 60 },
{ OV(287), 70 },
{ OV(295), 80 },
{ OV(304), 90 },
{ OV(312), 100 },
{ OV(320), 110 },
{ OV(329), 120 },
{ OV(337), 130 },
{ OV(345), 140 },
{ OV(353), 150 },
{ OV(361), 160 },
{ OV(369), 170 },
{ OV(377), 180 },
{ OV(385), 190 },
{ OV(393), 200 },
{ OV(401), 210 },
{ OV(409), 220 },
{ OV(417), 230 },
{ OV(424), 240 },
{ OV(432), 250 },
{ OV(440), 260 },
{ OV(447), 270 },
{ OV(455), 280 },
{ OV(463), 290 },
{ OV(470), 300 },
{ OV(478), 310 },
{ OV(485), 320 },
{ OV(493), 330 },
{ OV(500), 340 },
{ OV(507), 350 },
{ OV(515), 360 },
{ OV(522), 370 },
{ OV(529), 380 },
{ OV(537), 390 },
{ OV(544), 400 },
{ OV(614), 500 },
{ OV(681), 600 },
{ OV(744), 700 },
{ OV(805), 800 },
{ OV(862), 900 },
{ OV(917), 1000 },
{ OV(968), 1100 }
};
@@ -0,0 +1,57 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
#define REVERSE_TEMP_SENSOR_RANGE_201 1
// Pt100 with LMV324 amp on Overlord v1.1 electronics
const temp_entry_t temptable_201[] PROGMEM = {
{ OV( 0), 0 },
{ OV( 8), 1 },
{ OV( 23), 6 },
{ OV( 41), 15 },
{ OV( 51), 20 },
{ OV( 68), 28 },
{ OV( 74), 30 },
{ OV( 88), 35 },
{ OV( 99), 40 },
{ OV( 123), 50 },
{ OV( 148), 60 },
{ OV( 173), 70 },
{ OV( 198), 80 },
{ OV( 221), 90 },
{ OV( 245), 100 },
{ OV( 269), 110 },
{ OV( 294), 120 },
{ OV( 316), 130 },
{ OV( 342), 140 },
{ OV( 364), 150 },
{ OV( 387), 160 },
{ OV( 412), 170 },
{ OV( 433), 180 },
{ OV( 456), 190 },
{ OV( 480), 200 },
{ OV( 500), 210 },
{ OV( 548), 224 },
{ OV( 572), 233 },
{ OV(1155), 490 }
};
@@ -0,0 +1,69 @@
//
// Unknown 200K thermistor on a Copymaster 3D hotend
// Temptable sent from dealer technologyoutlet.co.uk
//
const temp_entry_t temptable_202[] PROGMEM = {
{ OV( 1), 864 },
{ OV( 35), 300 },
{ OV( 38), 295 },
{ OV( 41), 290 },
{ OV( 44), 285 },
{ OV( 47), 280 },
{ OV( 51), 275 },
{ OV( 55), 270 },
{ OV( 60), 265 },
{ OV( 65), 260 },
{ OV( 70), 255 },
{ OV( 76), 250 },
{ OV( 83), 245 },
{ OV( 90), 240 },
{ OV( 98), 235 },
{ OV( 107), 230 },
{ OV( 116), 225 },
{ OV( 127), 220 },
{ OV( 138), 215 },
{ OV( 151), 210 },
{ OV( 164), 205 },
{ OV( 179), 200 },
{ OV( 195), 195 },
{ OV( 213), 190 },
{ OV( 232), 185 },
{ OV( 253), 180 },
{ OV( 275), 175 },
{ OV( 299), 170 },
{ OV( 325), 165 },
{ OV( 352), 160 },
{ OV( 381), 155 },
{ OV( 411), 150 },
{ OV( 443), 145 },
{ OV( 476), 140 },
{ OV( 511), 135 },
{ OV( 546), 130 },
{ OV( 581), 125 },
{ OV( 617), 120 },
{ OV( 652), 115 },
{ OV( 687), 110 },
{ OV( 720), 105 },
{ OV( 753), 100 },
{ OV( 783), 95 },
{ OV( 812), 90 },
{ OV( 839), 85 },
{ OV( 864), 80 },
{ OV( 886), 75 },
{ OV( 906), 70 },
{ OV( 924), 65 },
{ OV( 940), 60 },
{ OV( 954), 55 },
{ OV( 966), 50 },
{ OV( 976), 45 },
{ OV( 985), 40 },
{ OV( 992), 35 },
{ OV( 998), 30 },
{ OV(1003), 25 },
{ OV(1007), 20 },
{ OV(1011), 15 },
{ OV(1014), 10 },
{ OV(1016), 5 },
{ OV(1018), 0 }
};
@@ -0,0 +1,78 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
#define REVERSE_TEMP_SENSOR_RANGE_21 1
#undef OV_SCALE
#define OV_SCALE(N) (float((N) * 5) / 3.3f)
// Pt100 with INA826 amplifier board with 5v supply based on Thermistor 20, with 3v3 ADC reference on the mainboard.
// If the ADC reference and INA826 board supply voltage are identical, Thermistor 20 instead.
const temp_entry_t temptable_21[] PROGMEM = {
{ OV( 0), 0 },
{ OV(227), 1 },
{ OV(236), 10 },
{ OV(245), 20 },
{ OV(253), 30 },
{ OV(262), 40 },
{ OV(270), 50 },
{ OV(279), 60 },
{ OV(287), 70 },
{ OV(295), 80 },
{ OV(304), 90 },
{ OV(312), 100 },
{ OV(320), 110 },
{ OV(329), 120 },
{ OV(337), 130 },
{ OV(345), 140 },
{ OV(353), 150 },
{ OV(361), 160 },
{ OV(369), 170 },
{ OV(377), 180 },
{ OV(385), 190 },
{ OV(393), 200 },
{ OV(401), 210 },
{ OV(409), 220 },
{ OV(417), 230 },
{ OV(424), 240 },
{ OV(432), 250 },
{ OV(440), 260 },
{ OV(447), 270 },
{ OV(455), 280 },
{ OV(463), 290 },
{ OV(470), 300 },
{ OV(478), 310 },
{ OV(485), 320 },
{ OV(493), 330 },
{ OV(500), 340 },
{ OV(507), 350 },
{ OV(515), 360 },
{ OV(522), 370 },
{ OV(529), 380 },
{ OV(537), 390 },
{ OV(544), 400 },
{ OV(614), 500 }
};
#undef OV_SCALE
#define OV_SCALE(N) (N)
@@ -0,0 +1,72 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
// 100k hotend thermistor with 4.7k pull up to 3.3v and 220R to analog input as in GTM32 Pro vB
const temp_entry_t temptable_22[] PROGMEM = {
{ OV( 1), 352 },
{ OV( 6), 341 },
{ OV( 11), 330 },
{ OV( 16), 319 },
{ OV( 20), 307 },
{ OV( 26), 296 },
{ OV( 31), 285 },
{ OV( 40), 274 },
{ OV( 51), 263 },
{ OV( 61), 251 },
{ OV( 72), 245 },
{ OV( 77), 240 },
{ OV( 82), 237 },
{ OV( 87), 232 },
{ OV( 91), 229 },
{ OV( 94), 227 },
{ OV( 97), 225 },
{ OV( 100), 223 },
{ OV( 104), 221 },
{ OV( 108), 219 },
{ OV( 115), 214 },
{ OV( 126), 209 },
{ OV( 137), 204 },
{ OV( 147), 200 },
{ OV( 158), 193 },
{ OV( 167), 192 },
{ OV( 177), 189 },
{ OV( 197), 163 },
{ OV( 230), 174 },
{ OV( 267), 165 },
{ OV( 310), 158 },
{ OV( 336), 151 },
{ OV( 379), 143 },
{ OV( 413), 138 },
{ OV( 480), 127 },
{ OV( 580), 110 },
{ OV( 646), 100 },
{ OV( 731), 88 },
{ OV( 768), 84 },
{ OV( 861), 69 },
{ OV( 935), 50 },
{ OV( 975), 38 },
{ OV(1001), 27 },
{ OV(1011), 22 },
{ OV(1015), 13 },
{ OV(1020), 6 },
{ OV(1023), 0 }
};
@@ -0,0 +1,128 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
// 100k hotbed thermistor with 4.7k pull up to 3.3v and 220R to analog input as in GTM32 Pro vB
const temp_entry_t temptable_23[] PROGMEM = {
{ OV( 1), 938 },
{ OV( 11), 423 },
{ OV( 21), 351 },
{ OV( 31), 314 },
{ OV( 41), 290 },
{ OV( 51), 272 },
{ OV( 61), 258 },
{ OV( 71), 247 },
{ OV( 81), 237 },
{ OV( 91), 229 },
{ OV( 101), 221 },
{ OV( 111), 215 },
{ OV( 121), 209 },
{ OV( 131), 204 },
{ OV( 141), 199 },
{ OV( 151), 195 },
{ OV( 161), 190 },
{ OV( 171), 187 },
{ OV( 181), 183 },
{ OV( 191), 179 },
{ OV( 201), 176 },
{ OV( 211), 173 },
{ OV( 221), 170 },
{ OV( 231), 167 },
{ OV( 241), 165 },
{ OV( 251), 162 },
{ OV( 261), 160 },
{ OV( 271), 157 },
{ OV( 281), 155 },
{ OV( 291), 153 },
{ OV( 301), 150 },
{ OV( 311), 148 },
{ OV( 321), 146 },
{ OV( 331), 144 },
{ OV( 341), 142 },
{ OV( 351), 140 },
{ OV( 361), 139 },
{ OV( 371), 137 },
{ OV( 381), 135 },
{ OV( 391), 133 },
{ OV( 401), 131 },
{ OV( 411), 130 },
{ OV( 421), 128 },
{ OV( 431), 126 },
{ OV( 441), 125 },
{ OV( 451), 123 },
{ OV( 461), 122 },
{ OV( 471), 120 },
{ OV( 481), 119 },
{ OV( 491), 117 },
{ OV( 501), 116 },
{ OV( 511), 114 },
{ OV( 521), 113 },
{ OV( 531), 111 },
{ OV( 541), 110 },
{ OV( 551), 108 },
{ OV( 561), 107 },
{ OV( 571), 105 },
{ OV( 581), 104 },
{ OV( 591), 102 },
{ OV( 601), 101 },
{ OV( 611), 100 },
{ OV( 621), 98 },
{ OV( 631), 97 },
{ OV( 641), 95 },
{ OV( 651), 94 },
{ OV( 661), 92 },
{ OV( 671), 91 },
{ OV( 681), 90 },
{ OV( 691), 88 },
{ OV( 701), 87 },
{ OV( 711), 85 },
{ OV( 721), 84 },
{ OV( 731), 82 },
{ OV( 741), 81 },
{ OV( 751), 79 },
{ OV( 761), 77 },
{ OV( 771), 76 },
{ OV( 781), 74 },
{ OV( 791), 72 },
{ OV( 801), 71 },
{ OV( 811), 69 },
{ OV( 821), 67 },
{ OV( 831), 65 },
{ OV( 841), 63 },
{ OV( 851), 62 },
{ OV( 861), 60 },
{ OV( 871), 57 },
{ OV( 881), 55 },
{ OV( 891), 53 },
{ OV( 901), 51 },
{ OV( 911), 48 },
{ OV( 921), 45 },
{ OV( 931), 42 },
{ OV( 941), 39 },
{ OV( 951), 36 },
{ OV( 961), 32 },
{ OV( 971), 28 },
{ OV( 981), 25 },
{ OV( 991), 23 },
{ OV(1001), 21 },
{ OV(1011), 19 },
{ OV(1021), 5 }
};
@@ -0,0 +1,54 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
// R25 = 100 kOhm, beta25 = 4120 K, 4.7 kOhm pull-up, mendel-parts
const temp_entry_t temptable_3[] PROGMEM = {
{ OV( 1), 864 },
{ OV( 21), 300 },
{ OV( 25), 290 },
{ OV( 29), 280 },
{ OV( 33), 270 },
{ OV( 39), 260 },
{ OV( 46), 250 },
{ OV( 54), 240 },
{ OV( 64), 230 },
{ OV( 75), 220 },
{ OV( 90), 210 },
{ OV( 107), 200 },
{ OV( 128), 190 },
{ OV( 154), 180 },
{ OV( 184), 170 },
{ OV( 221), 160 },
{ OV( 265), 150 },
{ OV( 316), 140 },
{ OV( 375), 130 },
{ OV( 441), 120 },
{ OV( 513), 110 },
{ OV( 588), 100 },
{ OV( 734), 80 },
{ OV( 856), 60 },
{ OV( 938), 40 },
{ OV( 986), 20 },
{ OV(1008), 0 },
{ OV(1018), -20 }
};
@@ -0,0 +1,66 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
// R25 = 100 kOhm, beta25 = 3950 K, 4.7 kOhm pull-up
// Resistance 100k Ohms at 25deg. C
// Resistance Tolerance + / -1%
// B Value 3950K at 25/50 deg. C
// B Value Tolerance + / - 1%
// Kis3d Silicone Heater 24V 200W/300W with 6mm Precision cast plate (EN AW 5083)
// Temperature setting time 10 min to determine the 12Bit ADC value on the surface. (le3tspeak)
const temp_entry_t temptable_30[] PROGMEM = {
{ OV( 1), 938 },
{ OV( 298), 125 }, // 1193 - 125°
{ OV( 321), 121 }, // 1285 - 121°
{ OV( 348), 117 }, // 1392 - 117°
{ OV( 387), 113 }, // 1550 - 113°
{ OV( 411), 110 }, // 1644 - 110°
{ OV( 445), 106 }, // 1780 - 106°
{ OV( 480), 101 }, // 1920 - 101°
{ OV( 516), 97 }, // 2064 - 97°
{ OV( 553), 92 }, // 2212 - 92°
{ OV( 591), 88 }, // 2364 - 88°
{ OV( 628), 84 }, // 2512 - 84°
{ OV( 665), 79 }, // 2660 - 79°
{ OV( 702), 75 }, // 2808 - 75°
{ OV( 736), 71 }, // 2945 - 71°
{ OV( 770), 67 }, // 3080 - 67°
{ OV( 801), 63 }, // 3204 - 63°
{ OV( 830), 59 }, // 3320 - 59°
{ OV( 857), 55 }, // 3428 - 55°
{ OV( 881), 51 }, // 3524 - 51°
{ OV( 902), 47 }, // 3611 - 47°
{ OV( 922), 42 }, // 3688 - 42°
{ OV( 938), 38 }, // 3754 - 38°
{ OV( 952), 34 }, // 3811 - 34°
{ OV( 964), 29 }, // 3857 - 29°
{ OV( 975), 25 }, // 3900 - 25°
{ OV( 980), 23 }, // 3920 - 23°
{ OV( 991), 17 }, // 3964 - 17°
{ OV(1001), 9 }, // Calculated
{ OV(1004), 5 }, // Calculated
{ OV(1008), 0 }, // Calculated
{ OV(1012), -5 }, // Calculated
{ OV(1016), -10 }, // Calculated
{ OV(1020), -15 } // Calculated
};
@@ -0,0 +1,92 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
#define OVM(V) OV((V)*(0.327/0.5))
// R25 = 100 kOhm, beta25 = 4092 K, 4.7 kOhm pull-up, bed thermistor
const temp_entry_t temptable_331[] PROGMEM = {
{ OVM( 23), 300 },
{ OVM( 25), 295 },
{ OVM( 27), 290 },
{ OVM( 28), 285 },
{ OVM( 31), 280 },
{ OVM( 33), 275 },
{ OVM( 35), 270 },
{ OVM( 38), 265 },
{ OVM( 41), 260 },
{ OVM( 44), 255 },
{ OVM( 48), 250 },
{ OVM( 52), 245 },
{ OVM( 56), 240 },
{ OVM( 61), 235 },
{ OVM( 66), 230 },
{ OVM( 71), 225 },
{ OVM( 78), 220 },
{ OVM( 84), 215 },
{ OVM( 92), 210 },
{ OVM( 100), 205 },
{ OVM( 109), 200 },
{ OVM( 120), 195 },
{ OVM( 131), 190 },
{ OVM( 143), 185 },
{ OVM( 156), 180 },
{ OVM( 171), 175 },
{ OVM( 187), 170 },
{ OVM( 205), 165 },
{ OVM( 224), 160 },
{ OVM( 245), 155 },
{ OVM( 268), 150 },
{ OVM( 293), 145 },
{ OVM( 320), 140 },
{ OVM( 348), 135 },
{ OVM( 379), 130 },
{ OVM( 411), 125 },
{ OVM( 445), 120 },
{ OVM( 480), 115 },
{ OVM( 516), 110 },
{ OVM( 553), 105 },
{ OVM( 591), 100 },
{ OVM( 628), 95 },
{ OVM( 665), 90 },
{ OVM( 702), 85 },
{ OVM( 737), 80 },
{ OVM( 770), 75 },
{ OVM( 801), 70 },
{ OVM( 830), 65 },
{ OVM( 857), 60 },
{ OVM( 881), 55 },
{ OVM( 903), 50 },
{ OVM( 922), 45 },
{ OVM( 939), 40 },
{ OVM( 954), 35 },
{ OVM( 966), 30 },
{ OVM( 977), 25 },
{ OVM( 985), 20 },
{ OVM( 993), 15 },
{ OVM( 999), 10 },
{ OVM(1004), 5 },
{ OVM(1008), 0 },
{ OVM(1012), -5 },
{ OVM(1016), -10 },
{ OVM(1020), -15 }
};
@@ -0,0 +1,50 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
#define OVM(V) OV((V)*(0.327/0.327))
// R25 = 100 kOhm, beta25 = 4092 K, 4.7 kOhm pull-up, bed thermistor
const temp_entry_t temptable_332[] PROGMEM = {
{ OVM( 268), 150 },
{ OVM( 293), 145 },
{ OVM( 320), 141 },
{ OVM( 379), 133 },
{ OVM( 445), 122 },
{ OVM( 516), 108 },
{ OVM( 591), 98 },
{ OVM( 665), 88 },
{ OVM( 737), 79 },
{ OVM( 801), 70 },
{ OVM( 857), 55 },
{ OVM( 903), 46 },
{ OVM( 939), 39 },
{ OVM( 954), 33 },
{ OVM( 966), 27 },
{ OVM( 977), 22 },
{ OVM( 999), 15 },
{ OVM(1004), 5 },
{ OVM(1008), 0 },
{ OVM(1012), -5 },
{ OVM(1016), -10 },
{ OVM(1020), -15 }
};
@@ -0,0 +1,46 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
// R25 = 10 kOhm, beta25 = 3950 K, 4.7 kOhm pull-up, Generic 10k thermistor
const temp_entry_t temptable_4[] PROGMEM = {
{ OV( 1), 430 },
{ OV( 54), 137 },
{ OV( 107), 107 },
{ OV( 160), 91 },
{ OV( 213), 80 },
{ OV( 266), 71 },
{ OV( 319), 64 },
{ OV( 372), 57 },
{ OV( 425), 51 },
{ OV( 478), 46 },
{ OV( 531), 41 },
{ OV( 584), 35 },
{ OV( 637), 30 },
{ OV( 690), 25 },
{ OV( 743), 20 },
{ OV( 796), 14 },
{ OV( 849), 7 },
{ OV( 902), 0 },
{ OV( 955), -11 },
{ OV(1008), -35 }
};
@@ -0,0 +1,62 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
// R25 = 100 kOhm, beta25 = 4267 K, 4.7 kOhm pull-up
// 100k ParCan thermistor (104GT-2)
// ATC Semitec 104GT-2/104NT-4-R025H42G (Used in ParCan)
// Verified by linagee. Source: https://www.mouser.com/datasheet/2/362/semitec%20usa%20corporation_gtthermistor-1202937.pdf
// Calculated using 4.7kohm pullup, voltage divider math, and manufacturer provided temp/resistance
const temp_entry_t temptable_5[] PROGMEM = {
{ OV( 1), 713 },
{ OV( 17), 300 }, // top rating 300C
{ OV( 20), 290 },
{ OV( 23), 280 },
{ OV( 27), 270 },
{ OV( 31), 260 },
{ OV( 37), 250 },
{ OV( 43), 240 },
{ OV( 51), 230 },
{ OV( 61), 220 },
{ OV( 73), 210 },
{ OV( 87), 200 },
{ OV( 106), 190 },
{ OV( 128), 180 },
{ OV( 155), 170 },
{ OV( 189), 160 },
{ OV( 230), 150 },
{ OV( 278), 140 },
{ OV( 336), 130 },
{ OV( 402), 120 },
{ OV( 476), 110 },
{ OV( 554), 100 },
{ OV( 635), 90 },
{ OV( 713), 80 },
{ OV( 784), 70 },
{ OV( 846), 60 },
{ OV( 897), 50 },
{ OV( 937), 40 },
{ OV( 966), 30 },
{ OV( 986), 20 },
{ OV(1000), 10 },
{ OV(1010), 0 }
};
@@ -0,0 +1,58 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
// 100k Zonestar thermistor. Adjusted By Hally
const temp_entry_t temptable_501[] PROGMEM = {
{ OV( 1), 713 },
{ OV( 14), 300 }, // Top rating 300C
{ OV( 16), 290 },
{ OV( 19), 280 },
{ OV( 23), 270 },
{ OV( 27), 260 },
{ OV( 31), 250 },
{ OV( 37), 240 },
{ OV( 47), 230 },
{ OV( 57), 220 },
{ OV( 68), 210 },
{ OV( 84), 200 },
{ OV( 100), 190 },
{ OV( 128), 180 },
{ OV( 155), 170 },
{ OV( 189), 160 },
{ OV( 230), 150 },
{ OV( 278), 140 },
{ OV( 336), 130 },
{ OV( 402), 120 },
{ OV( 476), 110 },
{ OV( 554), 100 },
{ OV( 635), 90 },
{ OV( 713), 80 },
{ OV( 784), 70 },
{ OV( 846), 60 },
{ OV( 897), 50 },
{ OV( 937), 40 },
{ OV( 966), 30 },
{ OV( 986), 20 },
{ OV(1000), 10 },
{ OV(1010), 0 }
};
@@ -0,0 +1,60 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
// Unknown thermistor for the Zonestar P802M hot bed. Adjusted By Nerseth
// These were the shipped settings from Zonestar in original firmware: P802M_8_Repetier_V1.6_Zonestar.zip
const temp_entry_t temptable_502[] PROGMEM = {
{ OV( 56.0 / 4), 300 },
{ OV( 187.0 / 4), 250 },
{ OV( 615.0 / 4), 190 },
{ OV( 690.0 / 4), 185 },
{ OV( 750.0 / 4), 180 },
{ OV( 830.0 / 4), 175 },
{ OV( 920.0 / 4), 170 },
{ OV(1010.0 / 4), 165 },
{ OV(1118.0 / 4), 160 },
{ OV(1215.0 / 4), 155 },
{ OV(1330.0 / 4), 145 },
{ OV(1460.0 / 4), 140 },
{ OV(1594.0 / 4), 135 },
{ OV(1752.0 / 4), 130 },
{ OV(1900.0 / 4), 125 },
{ OV(2040.0 / 4), 120 },
{ OV(2200.0 / 4), 115 },
{ OV(2350.0 / 4), 110 },
{ OV(2516.0 / 4), 105 },
{ OV(2671.0 / 4), 98 },
{ OV(2831.0 / 4), 92 },
{ OV(2975.0 / 4), 85 },
{ OV(3115.0 / 4), 76 },
{ OV(3251.0 / 4), 72 },
{ OV(3480.0 / 4), 62 },
{ OV(3580.0 / 4), 52 },
{ OV(3660.0 / 4), 46 },
{ OV(3740.0 / 4), 40 },
{ OV(3869.0 / 4), 30 },
{ OV(3912.0 / 4), 25 },
{ OV(3948.0 / 4), 20 },
{ OV(4077.0 / 4), -20 },
{ OV(4094.0 / 4), -55 }
};
@@ -0,0 +1,57 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
// Zonestar (Z8XM2) Heated Bed thermistor. Added By AvanOsch
// These are taken from the Zonestar settings in original Repetier firmware: Z8XM2_ZRIB_LCD12864_V51.zip
const temp_entry_t temptable_503[] PROGMEM = {
{ OV( 12), 300 },
{ OV( 27), 270 },
{ OV( 47), 250 },
{ OV( 68), 230 },
{ OV( 99), 210 },
{ OV( 120), 200 },
{ OV( 141), 190 },
{ OV( 171), 180 },
{ OV( 201), 170 },
{ OV( 261), 160 },
{ OV( 321), 150 },
{ OV( 401), 140 },
{ OV( 451), 130 },
{ OV( 551), 120 },
{ OV( 596), 110 },
{ OV( 626), 105 },
{ OV( 666), 100 },
{ OV( 697), 90 },
{ OV( 717), 85 },
{ OV( 798), 69 },
{ OV( 819), 65 },
{ OV( 870), 55 },
{ OV( 891), 51 },
{ OV( 922), 39 },
{ OV( 968), 28 },
{ OV( 980), 23 },
{ OV( 991), 17 },
{ OV( 1001), 9 },
{ OV(1021), -27 },
{ OV(1023), -200}
};
@@ -0,0 +1,83 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
// R25 = 100 kOhm, beta25 = 4092 K, 1 kOhm pull-up,
// 100k EPCOS (WITH 1kohm RESISTOR FOR PULLUP, R9 ON SANGUINOLOLU! NOT FOR 4.7kohm PULLUP! THIS IS NOT NORMAL!)
// Verified by linagee.
// Calculated using 1kohm pullup, voltage divider math, and manufacturer provided temp/resistance
// Advantage: Twice the resolution and better linearity from 150C to 200C
const temp_entry_t temptable_51[] PROGMEM = {
{ OV( 1), 350 },
{ OV( 190), 250 }, // top rating 250C
{ OV( 203), 245 },
{ OV( 217), 240 },
{ OV( 232), 235 },
{ OV( 248), 230 },
{ OV( 265), 225 },
{ OV( 283), 220 },
{ OV( 302), 215 },
{ OV( 322), 210 },
{ OV( 344), 205 },
{ OV( 366), 200 },
{ OV( 390), 195 },
{ OV( 415), 190 },
{ OV( 440), 185 },
{ OV( 467), 180 },
{ OV( 494), 175 },
{ OV( 522), 170 },
{ OV( 551), 165 },
{ OV( 580), 160 },
{ OV( 609), 155 },
{ OV( 638), 150 },
{ OV( 666), 145 },
{ OV( 695), 140 },
{ OV( 722), 135 },
{ OV( 749), 130 },
{ OV( 775), 125 },
{ OV( 800), 120 },
{ OV( 823), 115 },
{ OV( 845), 110 },
{ OV( 865), 105 },
{ OV( 884), 100 },
{ OV( 901), 95 },
{ OV( 917), 90 },
{ OV( 932), 85 },
{ OV( 944), 80 },
{ OV( 956), 75 },
{ OV( 966), 70 },
{ OV( 975), 65 },
{ OV( 982), 60 },
{ OV( 989), 55 },
{ OV( 995), 50 },
{ OV(1000), 45 },
{ OV(1004), 40 },
{ OV(1007), 35 },
{ OV(1010), 30 },
{ OV(1013), 25 },
{ OV(1015), 20 },
{ OV(1017), 15 },
{ OV(1018), 10 },
{ OV(1019), 5 },
{ OV(1020), 0 },
{ OV(1021), -5 }
};
@@ -0,0 +1,87 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
// 100k thermistor supplied with RPW-Ultra hotend, 4.7k pullup
const temp_entry_t temptable_512[] PROGMEM = {
{ OV(26), 300 },
{ OV(28), 295 },
{ OV(30), 290 },
{ OV(32), 285 },
{ OV(34), 280 },
{ OV(37), 275 },
{ OV(39), 270 },
{ OV(42), 265 },
{ OV(46), 260 },
{ OV(49), 255 },
{ OV(53), 250 }, // 256.5
{ OV(57), 245 },
{ OV(62), 240 },
{ OV(67), 235 },
{ OV(73), 230 },
{ OV(79), 225 },
{ OV(86), 220 },
{ OV(94), 215 },
{ OV(103), 210 },
{ OV(112), 205 },
{ OV(123), 200 },
{ OV(135), 195 },
{ OV(148), 190 },
{ OV(162), 185 },
{ OV(178), 180 },
{ OV(195), 175 },
{ OV(215), 170 },
{ OV(235), 165 },
{ OV(258), 160 },
{ OV(283), 155 },
{ OV(310), 150 }, // 2040.6
{ OV(338), 145 },
{ OV(369), 140 },
{ OV(401), 135 },
{ OV(435), 130 },
{ OV(470), 125 },
{ OV(505), 120 },
{ OV(542), 115 },
{ OV(579), 110 },
{ OV(615), 105 },
{ OV(651), 100 },
{ OV(686), 95 },
{ OV(720), 90 },
{ OV(751), 85 },
{ OV(781), 80 },
{ OV(809), 75 },
{ OV(835), 70 },
{ OV(858), 65 },
{ OV(880), 60 },
{ OV(899), 55 },
{ OV(915), 50 },
{ OV(930), 45 },
{ OV(944), 40 },
{ OV(955), 35 },
{ OV(965), 30 }, // 78279.3
{ OV(974), 25 },
{ OV(981), 20 },
{ OV(988), 15 },
{ OV(993), 10 },
{ OV(998), 5 },
{ OV(1002), 0 },
};
@@ -0,0 +1,62 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
// R25 = 200 kOhm, beta25 = 4338 K, 1 kOhm pull-up,
// 200k ATC Semitec 204GT-2 (WITH 1kohm RESISTOR FOR PULLUP, R9 ON SANGUINOLOLU! NOT FOR 4.7kohm PULLUP! THIS IS NOT NORMAL!)
// Verified by linagee. Source: https://www.mouser.com/datasheet/2/362/semitec%20usa%20corporation_gtthermistor-1202937.pdf
// Calculated using 1kohm pullup, voltage divider math, and manufacturer provided temp/resistance
// Advantage: More resolution and better linearity from 150C to 200C
const temp_entry_t temptable_52[] PROGMEM = {
{ OV( 1), 500 },
{ OV( 125), 300 }, // top rating 300C
{ OV( 142), 290 },
{ OV( 162), 280 },
{ OV( 185), 270 },
{ OV( 211), 260 },
{ OV( 240), 250 },
{ OV( 274), 240 },
{ OV( 312), 230 },
{ OV( 355), 220 },
{ OV( 401), 210 },
{ OV( 452), 200 },
{ OV( 506), 190 },
{ OV( 563), 180 },
{ OV( 620), 170 },
{ OV( 677), 160 },
{ OV( 732), 150 },
{ OV( 783), 140 },
{ OV( 830), 130 },
{ OV( 871), 120 },
{ OV( 906), 110 },
{ OV( 935), 100 },
{ OV( 958), 90 },
{ OV( 976), 80 },
{ OV( 990), 70 },
{ OV(1000), 60 },
{ OV(1008), 50 },
{ OV(1013), 40 },
{ OV(1017), 30 },
{ OV(1019), 20 },
{ OV(1021), 10 },
{ OV(1022), 0 }
};
@@ -0,0 +1,62 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
// R25 = 100 kOhm, beta25 = 4267 K, 1 kOhm pull-up,
// 100k ATC Semitec 104GT-2 (Used on ParCan) (WITH 1kohm RESISTOR FOR PULLUP, R9 ON SANGUINOLOLU! NOT FOR 4.7kohm PULLUP! THIS IS NOT NORMAL!)
// Verified by linagee. Source: https://www.mouser.com/datasheet/2/362/semitec%20usa%20corporation_gtthermistor-1202937.pdf
// Calculated using 1kohm pullup, voltage divider math, and manufacturer provided temp/resistance
// Advantage: More resolution and better linearity from 150C to 200C
const temp_entry_t temptable_55[] PROGMEM = {
{ OV( 1), 500 },
{ OV( 76), 300 },
{ OV( 87), 290 },
{ OV( 100), 280 },
{ OV( 114), 270 },
{ OV( 131), 260 },
{ OV( 152), 250 },
{ OV( 175), 240 },
{ OV( 202), 230 },
{ OV( 234), 220 },
{ OV( 271), 210 },
{ OV( 312), 200 },
{ OV( 359), 190 },
{ OV( 411), 180 },
{ OV( 467), 170 },
{ OV( 527), 160 },
{ OV( 590), 150 },
{ OV( 652), 140 },
{ OV( 713), 130 },
{ OV( 770), 120 },
{ OV( 822), 110 },
{ OV( 867), 100 },
{ OV( 905), 90 },
{ OV( 936), 80 },
{ OV( 961), 70 },
{ OV( 979), 60 },
{ OV( 993), 50 },
{ OV(1003), 40 },
{ OV(1010), 30 },
{ OV(1015), 20 },
{ OV(1018), 10 },
{ OV(1020), 0 }
};
@@ -0,0 +1,64 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
// R25 = 100 kOhm, beta25 = 4092 K, 8.2 kOhm pull-up, 100k Epcos (?) thermistor
const temp_entry_t temptable_6[] PROGMEM = {
{ OV( 1), 350 },
{ OV( 28), 250 }, // top rating 250C
{ OV( 31), 245 },
{ OV( 35), 240 },
{ OV( 39), 235 },
{ OV( 42), 230 },
{ OV( 44), 225 },
{ OV( 49), 220 },
{ OV( 53), 215 },
{ OV( 62), 210 },
{ OV( 71), 205 }, // fitted graphically
{ OV( 78), 200 }, // fitted graphically
{ OV( 94), 190 },
{ OV( 102), 185 },
{ OV( 116), 170 },
{ OV( 143), 160 },
{ OV( 183), 150 },
{ OV( 223), 140 },
{ OV( 270), 130 },
{ OV( 318), 120 },
{ OV( 383), 110 },
{ OV( 413), 105 },
{ OV( 439), 100 },
{ OV( 484), 95 },
{ OV( 513), 90 },
{ OV( 607), 80 },
{ OV( 664), 70 },
{ OV( 781), 60 },
{ OV( 810), 55 },
{ OV( 849), 50 },
{ OV( 914), 45 },
{ OV( 914), 40 },
{ OV( 935), 35 },
{ OV( 954), 30 },
{ OV( 970), 25 },
{ OV( 978), 22 },
{ OV(1008), 3 },
{ OV(1023), 0 } // to allow internal 0 degrees C
};
@@ -0,0 +1,107 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
// R25 = 100 kOhm, beta25 = 3950 K, 4.7 kOhm pull-up,
// Maker's Tool Works Kapton Bed Thermistor
// ./createTemperatureLookup.py --r0=100000 --t0=25 --r1=0 --r2=4700 --beta=3950
// r0: 100000
// t0: 25
// r1: 0 (parallel with rTherm)
// r2: 4700 (series with rTherm)
// beta: 3950
// min adc: 1 at 0.0048828125 V
// max adc: 1023 at 4.9951171875 V
const temp_entry_t temptable_60[] PROGMEM = {
{ OV( 51), 272 },
{ OV( 61), 258 },
{ OV( 71), 247 },
{ OV( 81), 237 },
{ OV( 91), 229 },
{ OV( 101), 221 },
{ OV( 131), 204 },
{ OV( 161), 190 },
{ OV( 191), 179 },
{ OV( 231), 167 },
{ OV( 271), 157 },
{ OV( 311), 148 },
{ OV( 351), 140 },
{ OV( 381), 135 },
{ OV( 411), 130 },
{ OV( 441), 125 },
{ OV( 451), 123 },
{ OV( 461), 122 },
{ OV( 471), 120 },
{ OV( 481), 119 },
{ OV( 491), 117 },
{ OV( 501), 116 },
{ OV( 511), 114 },
{ OV( 521), 113 },
{ OV( 531), 111 },
{ OV( 541), 110 },
{ OV( 551), 108 },
{ OV( 561), 107 },
{ OV( 571), 105 },
{ OV( 581), 104 },
{ OV( 591), 102 },
{ OV( 601), 101 },
{ OV( 611), 100 },
{ OV( 621), 98 },
{ OV( 631), 97 },
{ OV( 641), 95 },
{ OV( 651), 94 },
{ OV( 661), 92 },
{ OV( 671), 91 },
{ OV( 681), 90 },
{ OV( 691), 88 },
{ OV( 701), 87 },
{ OV( 711), 85 },
{ OV( 721), 84 },
{ OV( 731), 82 },
{ OV( 741), 81 },
{ OV( 751), 79 },
{ OV( 761), 77 },
{ OV( 771), 76 },
{ OV( 781), 74 },
{ OV( 791), 72 },
{ OV( 801), 71 },
{ OV( 811), 69 },
{ OV( 821), 67 },
{ OV( 831), 65 },
{ OV( 841), 63 },
{ OV( 851), 62 },
{ OV( 861), 60 },
{ OV( 871), 57 },
{ OV( 881), 55 },
{ OV( 891), 53 },
{ OV( 901), 51 },
{ OV( 911), 48 },
{ OV( 921), 45 },
{ OV( 931), 42 },
{ OV( 941), 39 },
{ OV( 951), 36 },
{ OV( 961), 32 },
{ OV( 981), 23 },
{ OV( 991), 17 },
{ OV(1001), 9 },
{ OV(1008), 0 }
};
@@ -0,0 +1,116 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
// R25 = 100 kOhm, beta25 = 3950 K, 4.7 kOhm pull-up,
// Formbot / Vivedino high temp 100k thermistor
// 100KR13950181203
// Generated with modified version of https://www.thingiverse.com/thing:103668
// Using table 1 with datasheet values
// Resistance 100k Ohms at 25deg. C
// Resistance Tolerance + / -1%
// B Value 3950K at 25/50 deg. C
// B Value Tolerance + / - 1%
const temp_entry_t temptable_61[] PROGMEM = {
{ OV( 2.00), 420 }, // Guestimate to ensure we dont lose a reading and drop temps to -50 when over
{ OV( 12.07), 350 },
{ OV( 12.79), 345 },
{ OV( 13.59), 340 },
{ OV( 14.44), 335 },
{ OV( 15.37), 330 },
{ OV( 16.38), 325 },
{ OV( 17.46), 320 },
{ OV( 18.63), 315 },
{ OV( 19.91), 310 },
{ OV( 21.29), 305 },
{ OV( 22.79), 300 },
{ OV( 24.43), 295 },
{ OV( 26.21), 290 },
{ OV( 28.15), 285 },
{ OV( 30.27), 280 },
{ OV( 32.58), 275 },
{ OV( 35.10), 270 },
{ OV( 38.44), 265 },
{ OV( 40.89), 260 },
{ OV( 44.19), 255 },
{ OV( 47.83), 250 },
{ OV( 51.80), 245 },
{ OV( 56.20), 240 },
{ OV( 61.00), 235 },
{ OV( 66.30), 230 },
{ OV( 72.11), 225 },
{ OV( 78.51), 220 },
{ OV( 85.57), 215 },
{ OV( 93.34), 210 },
{ OV( 101.91), 205 },
{ OV( 111.34), 200 },
{ OV( 121.73), 195 },
{ OV( 133.17), 190 },
{ OV( 145.74), 185 },
{ OV( 159.57), 180 },
{ OV( 174.73), 175 },
{ OV( 191.35), 170 },
{ OV( 209.53), 165 },
{ OV( 229.35), 160 },
{ OV( 250.90), 155 },
{ OV( 274.25), 150 },
{ OV( 299.46), 145 },
{ OV( 326.52), 140 },
{ OV( 355.44), 135 },
{ OV( 386.15), 130 },
{ OV( 418.53), 125 },
{ OV( 452.43), 120 },
{ OV( 487.62), 115 },
{ OV( 523.82), 110 },
{ OV( 560.70), 105 },
{ OV( 597.88), 100 },
{ OV( 634.97), 95 },
{ OV( 671.55), 90 },
{ OV( 707.21), 85 },
{ OV( 741.54), 80 },
{ OV( 779.65), 75 },
{ OV( 809.57), 70 },
{ OV( 833.40), 65 },
{ OV( 859.55), 60 },
{ OV( 883.27), 55 },
{ OV( 904.53), 50 },
{ OV( 923.38), 45 },
{ OV( 939.91), 40 },
{ OV( 954.26), 35 },
{ OV( 966.59), 30 },
{ OV( 977.08), 25 },
{ OV( 985.92), 20 },
{ OV( 993.39), 15 },
{ OV( 999.42), 10 },
{ OV(1004.43), 5 },
{ OV(1008.51), 0 },
{ OV(1011.79), -5 },
{ OV(1014.40), -10 },
{ OV(1016.48), -15 },
{ OV(1018.10), -20 },
{ OV(1019.35), -25 },
{ OV(1020.32), -30 },
{ OV(1021.05), -35 },
{ OV(1021.60), -40 },
{ OV(1022.01), -45 },
{ OV(1022.31), -50 }
};
@@ -0,0 +1,53 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
// R25 = 2.5 MOhm, beta25 = 4500 K, 4.7 kOhm pull-up, DyzeDesign 500 °C Thermistor
const temp_entry_t temptable_66[] PROGMEM = {
{ OV( 17.5), 850 },
{ OV( 17.9), 500 },
{ OV( 21.7), 480 },
{ OV( 26.6), 460 },
{ OV( 33.1), 440 },
{ OV( 41.0), 420 },
{ OV( 52.3), 400 },
{ OV( 67.7), 380 },
{ OV( 86.5), 360 },
{ OV( 112.0), 340 },
{ OV( 147.2), 320 },
{ OV( 194.0), 300 },
{ OV( 254.3), 280 },
{ OV( 330.2), 260 },
{ OV( 427.9), 240 },
{ OV( 533.4), 220 },
{ OV( 646.5), 200 },
{ OV( 754.4), 180 },
{ OV( 844.3), 160 },
{ OV( 911.7), 140 },
{ OV( 958.6), 120 },
{ OV( 988.8), 100 },
{ OV(1006.6), 80 },
{ OV(1015.8), 60 },
{ OV(1021.3), 30 },
{ OV( 1022), 25 },
{ OV( 1023), 20 }
};
@@ -0,0 +1,98 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* This file was generated by tltgen on Thu Jul 5 15:46:43 2018.
* tltgen was created by Pieter Agten (pieter.agten@gmail.com).
*/
//#include "output_table.h"
/*
* Parameters:
* A: -0.000480634
* B: 0.00031362
* C: -2.03978e-07
*/
const temp_entry_t temptable_666[] PROGMEM = {
{ OV( 1), 794 },
{ OV( 18), 288 },
{ OV( 35), 234 },
{ OV( 52), 207 },
{ OV( 69), 189 },
{ OV( 86), 176 },
{ OV(103), 166 },
{ OV(120), 157 },
{ OV(137) ,150 },
{ OV(154), 144 },
{ OV(172), 138 },
{ OV(189), 134 },
{ OV(206), 129 },
{ OV(223), 125 },
{ OV(240), 121 },
{ OV(257), 118 },
{ OV(274), 115 },
{ OV(291), 112 },
{ OV(308), 109 },
{ OV(325), 106 },
{ OV(342), 103 },
{ OV(359), 101 },
{ OV(376), 99 },
{ OV(393), 96 },
{ OV(410), 94 },
{ OV(427), 92 },
{ OV(444), 90 },
{ OV(461), 88 },
{ OV(478), 86 },
{ OV(495), 84 },
{ OV(512), 82 },
{ OV(530), 80 },
{ OV(547), 78 },
{ OV(564), 76 },
{ OV(581), 74 },
{ OV(598), 72 },
{ OV(615), 70 },
{ OV(632), 68 },
{ OV(649), 67 },
{ OV(666), 65 },
{ OV(683), 63 },
{ OV(700), 61 },
{ OV(717), 59 },
{ OV(734), 57 },
{ OV(751), 55 },
{ OV(768), 53 },
{ OV(785), 51 },
{ OV(802), 49 },
{ OV(819), 47 },
{ OV(836), 44 },
{ OV(853), 42 },
{ OV(871), 39 },
{ OV(888), 37 },
{ OV(905), 34 },
{ OV(922), 30 },
{ OV(939), 27 },
{ OV(956), 23 },
{ OV(973), 18 },
{ OV(990), 11 },
{ OV(1007), 2 },
{ OV(1023),-25 }
};
@@ -0,0 +1,81 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
// R25 = 500 KOhm, beta25 = 3800 K, 4.7 kOhm pull-up, SliceEngineering 450 °C Thermistor
const temp_entry_t temptable_67[] PROGMEM = {
{ OV( 22 ), 500 },
{ OV( 23 ), 490 },
{ OV( 25 ), 480 },
{ OV( 27 ), 470 },
{ OV( 29 ), 460 },
{ OV( 32 ), 450 },
{ OV( 35 ), 440 },
{ OV( 38 ), 430 },
{ OV( 41 ), 420 },
{ OV( 45 ), 410 },
{ OV( 50 ), 400 },
{ OV( 55 ), 390 },
{ OV( 60 ), 380 },
{ OV( 67 ), 370 },
{ OV( 74 ), 360 },
{ OV( 82 ), 350 },
{ OV( 91 ), 340 },
{ OV( 102 ), 330 },
{ OV( 114 ), 320 },
{ OV( 127 ), 310 },
{ OV( 143 ), 300 },
{ OV( 161 ), 290 },
{ OV( 181 ), 280 },
{ OV( 204 ), 270 },
{ OV( 229 ), 260 },
{ OV( 259 ), 250 },
{ OV( 290 ), 240 },
{ OV( 325 ), 230 },
{ OV( 364 ), 220 },
{ OV( 407 ), 210 },
{ OV( 453 ), 200 },
{ OV( 501 ), 190 },
{ OV( 551 ), 180 },
{ OV( 603 ), 170 },
{ OV( 655 ), 160 },
{ OV( 706 ), 150 },
{ OV( 755 ), 140 },
{ OV( 801 ), 130 },
{ OV( 842 ), 120 },
{ OV( 879 ), 110 },
{ OV( 910 ), 100 },
{ OV( 936 ), 90 },
{ OV( 948 ), 85 },
{ OV( 958 ), 80 },
{ OV( 975 ), 70 },
{ OV( 988 ), 60 },
{ OV( 998 ), 50 },
{ OV(1006 ), 40 },
{ OV(1011 ), 30 },
{ OV(1013 ), 25 },
{ OV(1015 ), 20 },
{ OV(1018 ), 10 },
{ OV(1020 ), 0 },
{ OV(1021 ), -10 },
{ OV(1022 ), -20 }
};
@@ -0,0 +1,84 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
// R25 = 100 kOhm, beta25 = 3974 K, 4.7 kOhm pull-up, Honeywell 135-104LAG-J01
const temp_entry_t temptable_7[] PROGMEM = {
{ OV( 1), 941 },
{ OV( 19), 362 },
{ OV( 37), 299 }, // top rating 300C
{ OV( 55), 266 },
{ OV( 73), 245 },
{ OV( 91), 229 },
{ OV( 109), 216 },
{ OV( 127), 206 },
{ OV( 145), 197 },
{ OV( 163), 190 },
{ OV( 181), 183 },
{ OV( 199), 177 },
{ OV( 217), 171 },
{ OV( 235), 166 },
{ OV( 253), 162 },
{ OV( 271), 157 },
{ OV( 289), 153 },
{ OV( 307), 149 },
{ OV( 325), 146 },
{ OV( 343), 142 },
{ OV( 361), 139 },
{ OV( 379), 135 },
{ OV( 397), 132 },
{ OV( 415), 129 },
{ OV( 433), 126 },
{ OV( 451), 123 },
{ OV( 469), 121 },
{ OV( 487), 118 },
{ OV( 505), 115 },
{ OV( 523), 112 },
{ OV( 541), 110 },
{ OV( 559), 107 },
{ OV( 577), 105 },
{ OV( 595), 102 },
{ OV( 613), 99 },
{ OV( 631), 97 },
{ OV( 649), 94 },
{ OV( 667), 92 },
{ OV( 685), 89 },
{ OV( 703), 86 },
{ OV( 721), 84 },
{ OV( 739), 81 },
{ OV( 757), 78 },
{ OV( 775), 75 },
{ OV( 793), 72 },
{ OV( 811), 69 },
{ OV( 829), 66 },
{ OV( 847), 62 },
{ OV( 865), 59 },
{ OV( 883), 55 },
{ OV( 901), 51 },
{ OV( 919), 46 },
{ OV( 937), 41 },
{ OV( 955), 35 },
{ OV( 973), 27 },
{ OV( 991), 17 },
{ OV(1009), 1 },
{ OV(1023), 0 } // to allow internal 0 degrees C
};
@@ -0,0 +1,46 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
// Stock BQ Hephestos 2 100k thermistor.
// Created on 29/12/2017 with an ambient temperature of 20C.
// ANENG AN8009 DMM with a K-type probe used for measurements.
// R25 = 100 kOhm, beta25 = 4100 K, 4.7 kOhm pull-up, bqh2 stock thermistor
const temp_entry_t temptable_70[] PROGMEM = {
{ OV( 18), 270 },
{ OV( 27), 248 },
{ OV( 34), 234 },
{ OV( 45), 220 },
{ OV( 61), 205 },
{ OV( 86), 188 },
{ OV( 123), 172 },
{ OV( 420), 110 },
{ OV( 590), 90 },
{ OV( 845), 56 },
{ OV( 970), 25 },
{ OV( 986), 20 },
{ OV( 994), 15 },
{ OV(1000), 10 },
{ OV(1005), 5 },
{ OV(1009), 0 } // safety
};
@@ -0,0 +1,94 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
// R25 = 100 kOhm, beta25 = 3974 K, 4.7 kOhm pull-up, Honeywell 135-104LAF-J01
// R0 = 100000 Ohm
// T0 = 25 °C
// Beta = 3974
// R1 = 0 Ohm
// R2 = 4700 Ohm
const temp_entry_t temptable_71[] PROGMEM = {
{ OV( 35), 300 },
{ OV( 51), 269 },
{ OV( 59), 258 },
{ OV( 64), 252 },
{ OV( 71), 244 },
{ OV( 81), 235 },
{ OV( 87), 230 },
{ OV( 92), 226 },
{ OV( 102), 219 },
{ OV( 110), 214 },
{ OV( 115), 211 },
{ OV( 126), 205 },
{ OV( 128), 204 },
{ OV( 130), 203 },
{ OV( 132), 202 },
{ OV( 134), 201 },
{ OV( 136), 200 },
{ OV( 147), 195 },
{ OV( 154), 192 },
{ OV( 159), 190 },
{ OV( 164), 188 },
{ OV( 172), 185 },
{ OV( 175), 184 },
{ OV( 178), 183 },
{ OV( 181), 182 },
{ OV( 184), 181 },
{ OV( 187), 180 },
{ OV( 190), 179 },
{ OV( 193), 178 },
{ OV( 196), 177 },
{ OV( 199), 176 },
{ OV( 202), 175 },
{ OV( 205), 174 },
{ OV( 208), 173 },
{ OV( 215), 171 },
{ OV( 237), 165 },
{ OV( 256), 160 },
{ OV( 300), 150 },
{ OV( 351), 140 },
{ OV( 470), 120 },
{ OV( 504), 115 },
{ OV( 538), 110 },
{ OV( 745), 80 },
{ OV( 770), 76 },
{ OV( 806), 70 },
{ OV( 829), 66 },
{ OV( 860), 60 },
{ OV( 879), 56 },
{ OV( 888), 54 },
{ OV( 905), 50 },
{ OV( 924), 45 },
{ OV( 940), 40 },
{ OV( 955), 35 },
{ OV( 972), 28 },
{ OV( 974), 27 },
{ OV( 976), 26 },
{ OV( 978), 25 },
{ OV( 980), 24 },
{ OV( 987), 20 },
{ OV( 995), 15 },
{ OV(1001), 10 },
{ OV(1006), 5 },
{ OV(1010), 0 }
};
@@ -0,0 +1,80 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* R25 = 100 kOhm, beta25 = 4100 K, 4.7 kOhm pull-up,
* Generic Silicon Heat Pad with NTC 100K thermistor
*
* Many generic silicone heat pads use the MGB18-104F39050L32 thermistor, applicable to various
* wattages and voltages. This table is correct if this part is used. It's been optimized
* to provide good granularity in the 60-110C range, good for PLA and ABS. For higher temperature
* filament (e.g., nylon) uncomment HIGH_TEMP_RANGE_75 for increased accuracy. If higher
* temperatures aren't used it can improve performance slightly to leave it commented out.
*/
//#define HIGH_TEMP_RANGE_75
const temp_entry_t temptable_75[] PROGMEM = { // Generic Silicon Heat Pad with NTC 100K MGB18-104F39050L32 thermistor
{ OV(111.06), 200 }, // v=0.542 r=571.747 res=0.501 degC/count
#ifdef HIGH_TEMP_RANGE_75
{ OV(174.87), 175 }, // v=0.854 r=967.950 res=0.311 degC/count These values are valid. But they serve no
{ OV(191.64), 170 }, // v=0.936 r=1082.139 res=0.284 degC/count purpose. It is better to delete them so
{ OV(209.99), 165 }, // v=1.025 r=1212.472 res=0.260 degC/count the search is quicker and get to the meaningful
{ OV(230.02), 160 }, // v=1.123 r=1361.590 res=0.239 degC/count part of the table sooner.
{ OV(251.80), 155 }, // v=1.230 r=1532.621 res=0.220 degC/count
#endif
{ OV(275.43), 150 }, // v=1.345 r=1729.283 res=0.203 degC/count
#ifdef HIGH_TEMP_RANGE_75
{ OV(300.92), 145 }, // v=1.469 r=1956.004 res=0.189 degC/coun
#endif
{ OV( 328.32), 140 }, // v=1.603 r=2218.081 res=0.176 degC/count
{ OV( 388.65), 130 }, // v=1.898 r=2874.980 res=0.156 degC/count
{ OV( 421.39), 125 }, // v=2.058 r=3286.644 res=0.149 degC/count
{ OV( 455.65), 120 }, // v=2.225 r=3768.002 res=0.143 degC/count
{ OV( 491.17), 115 }, // v=2.398 r=4332.590 res=0.139 degC/count
{ OV( 527.68), 110 }, // v=2.577 r=4996.905 res=0.136 degC/count
{ OV( 564.81), 105 }, // v=2.758 r=5781.120 res=0.134 degC/count
{ OV( 602.19), 100 }, // v=2.940 r=6710.000 res=0.134 degC/count
{ OV( 676.03), 90 }, // v=3.301 r=9131.018 res=0.138 degC/count
{ OV( 745.85), 80 }, // v=3.642 r=12602.693 res=0.150 degC/count
{ OV( 778.31), 75 }, // v=3.800 r=14889.001 res=0.159 degC/count
{ OV( 808.75), 70 }, // v=3.949 r=17658.700 res=0.171 degC/count
{ OV( 836.94), 65 }, // v=4.087 r=21028.040 res=0.185 degC/count
{ OV( 862.74), 60 }, // v=4.213 r=25144.568 res=0.204 degC/count
{ OV( 886.08), 55 }, // v=4.327 r=30196.449 res=0.227 degC/count
{ OV( 906.97), 50 }, // v=4.429 r=36424.838 res=0.255 degC/count
{ OV( 941.65), 40 }, // v=4.598 r=53745.337 res=0.333 degC/count
{ OV( 967.76), 30 }, // v=4.725 r=80880.630 res=0.452 degC/count
{ OV( 978.03), 25 }, // v=4.776 r=100000.000 res=0.535 degC/count
{ OV( 981.68), 23 }, // v=4.793 r=109024.395 res=0.573 degC/count
{ OV( 983.41), 22 }, // v=4.802 r=113875.430 res=0.594 degC/count
{ OV( 985.08), 21 }, // v=4.810 r=118968.955 res=0.616 degC/count
{ OV( 986.70), 20 }, // v=4.818 r=124318.354 res=0.638 degC/count
{ OV( 993.94), 15 }, // v=4.853 r=155431.302 res=0.768 degC/count
{ OV( 999.96), 10 }, // v=4.883 r=195480.023 res=0.934 degC/count
{ OV(1008.95), 0 } // v=4.926 r=314997.575 res=1.418 degC/count
};
@@ -0,0 +1,46 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
// R25 = 100 kOhm, beta25 = 3950 K, 10 kOhm pull-up, NTCS0603E3104FHT
const temp_entry_t temptable_8[] PROGMEM = {
{ OV( 1), 704 },
{ OV( 54), 216 },
{ OV( 107), 175 },
{ OV( 160), 152 },
{ OV( 213), 137 },
{ OV( 266), 125 },
{ OV( 319), 115 },
{ OV( 372), 106 },
{ OV( 425), 99 },
{ OV( 478), 91 },
{ OV( 531), 85 },
{ OV( 584), 78 },
{ OV( 637), 71 },
{ OV( 690), 65 },
{ OV( 743), 58 },
{ OV( 796), 50 },
{ OV( 849), 42 },
{ OV( 902), 31 },
{ OV( 955), 17 },
{ OV(1008), 0 }
};
@@ -0,0 +1,57 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
// R25 = 100 kOhm, beta25 = 3960 K, 4.7 kOhm pull-up, GE Sensing AL03006-58.2K-97-G1
const temp_entry_t temptable_9[] PROGMEM = {
{ OV( 1), 936 },
{ OV( 36), 300 },
{ OV( 71), 246 },
{ OV( 106), 218 },
{ OV( 141), 199 },
{ OV( 176), 185 },
{ OV( 211), 173 },
{ OV( 246), 163 },
{ OV( 281), 155 },
{ OV( 316), 147 },
{ OV( 351), 140 },
{ OV( 386), 134 },
{ OV( 421), 128 },
{ OV( 456), 122 },
{ OV( 491), 117 },
{ OV( 526), 112 },
{ OV( 561), 107 },
{ OV( 596), 102 },
{ OV( 631), 97 },
{ OV( 666), 92 },
{ OV( 701), 87 },
{ OV( 736), 81 },
{ OV( 771), 76 },
{ OV( 806), 70 },
{ OV( 841), 63 },
{ OV( 876), 56 },
{ OV( 911), 48 },
{ OV( 946), 38 },
{ OV( 981), 23 },
{ OV(1005), 5 },
{ OV(1016), 0 }
};
@@ -0,0 +1,64 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
// 100k bed thermistor with a 10K pull-up resistor - made by $ buildroot/share/scripts/createTemperatureLookupMarlin.py --rp=10000
const temp_entry_t temptable_99[] PROGMEM = {
{ OV( 5.81), 350 }, // v=0.028 r= 57.081 res=13.433 degC/count
{ OV( 6.54), 340 }, // v=0.032 r= 64.248 res=11.711 degC/count
{ OV( 7.38), 330 }, // v=0.036 r= 72.588 res=10.161 degC/count
{ OV( 8.36), 320 }, // v=0.041 r= 82.336 res= 8.772 degC/count
{ OV( 9.51), 310 }, // v=0.046 r= 93.780 res= 7.535 degC/count
{ OV( 10.87), 300 }, // v=0.053 r= 107.281 res= 6.439 degC/count
{ OV( 12.47), 290 }, // v=0.061 r= 123.286 res= 5.473 degC/count
{ OV( 14.37), 280 }, // v=0.070 r= 142.360 res= 4.627 degC/count
{ OV( 16.64), 270 }, // v=0.081 r= 165.215 res= 3.891 degC/count
{ OV( 19.37), 260 }, // v=0.095 r= 192.758 res= 3.253 degC/count
{ OV( 22.65), 250 }, // v=0.111 r= 226.150 res= 2.705 degC/count
{ OV( 26.62), 240 }, // v=0.130 r= 266.891 res= 2.236 degC/count
{ OV( 31.46), 230 }, // v=0.154 r= 316.931 res= 1.839 degC/count
{ OV( 37.38), 220 }, // v=0.182 r= 378.822 res= 1.504 degC/count
{ OV( 44.65), 210 }, // v=0.218 r= 455.939 res= 1.224 degC/count
{ OV( 53.64), 200 }, // v=0.262 r= 552.778 res= 0.991 degC/count
{ OV( 64.78), 190 }, // v=0.316 r= 675.386 res= 0.799 degC/count
{ OV( 78.65), 180 }, // v=0.384 r= 831.973 res= 0.643 degC/count
{ OV( 95.94), 170 }, // v=0.468 r= 1033.801 res= 0.516 degC/count
{ OV(117.52), 160 }, // v=0.574 r= 1296.481 res= 0.414 degC/count
{ OV(144.42), 150 }, // v=0.705 r= 1641.900 res= 0.333 degC/count
{ OV(177.80), 140 }, // v=0.868 r= 2101.110 res= 0.269 degC/count
{ OV(218.89), 130 }, // v=1.069 r= 2718.725 res= 0.220 degC/count
{ OV(268.82), 120 }, // v=1.313 r= 3559.702 res= 0.183 degC/count
{ OV(328.35), 110 }, // v=1.603 r= 4719.968 res= 0.155 degC/count
{ OV(397.44), 100 }, // v=1.941 r= 6343.323 res= 0.136 degC/count
{ OV(474.90), 90 }, // v=2.319 r= 8648.807 res= 0.124 degC/count
{ OV(558.03), 80 }, // v=2.725 r= 11975.779 res= 0.118 degC/count
{ OV(642.76), 70 }, // v=3.138 r= 16859.622 res= 0.119 degC/count
{ OV(724.25), 60 }, // v=3.536 r= 24161.472 res= 0.128 degC/count
{ OV(797.93), 50 }, // v=3.896 r= 35295.361 res= 0.146 degC/count
{ OV(860.51), 40 }, // v=4.202 r= 52635.209 res= 0.178 degC/count
{ OV(910.55), 30 }, // v=4.446 r= 80262.251 res= 0.229 degC/count
{ OV(948.36), 20 }, // v=4.631 r=125374.433 res= 0.313 degC/count
{ OV(975.47), 10 }, // v=4.763 r=201020.458 res= 0.449 degC/count
{ OV(994.02), 0 } // v=4.854 r=331567.870 res= 0.676 degC/count
};
@@ -0,0 +1,33 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
// User-defined table 1
// Dummy Thermistor table.. It will ALWAYS read a fixed value.
#ifndef DUMMY_THERMISTOR_998_VALUE
#define DUMMY_THERMISTOR_998_VALUE 25
#endif
const temp_entry_t temptable_998[] PROGMEM = {
{ OV( 1), DUMMY_THERMISTOR_998_VALUE },
{ OV(1023), DUMMY_THERMISTOR_998_VALUE }
};
@@ -0,0 +1,33 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
// User-defined table 2
// Dummy Thermistor table.. It will ALWAYS read a fixed value.
#ifndef DUMMY_THERMISTOR_999_VALUE
#define DUMMY_THERMISTOR_999_VALUE 25
#endif
const temp_entry_t temptable_999[] PROGMEM = {
{ OV( 1), DUMMY_THERMISTOR_999_VALUE },
{ OV(1023), DUMMY_THERMISTOR_999_VALUE }
};
+533
View File
@@ -0,0 +1,533 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
#include "../../inc/MarlinConfig.h"
#define THERMISTOR_TABLE_ADC_RESOLUTION 10
#define THERMISTOR_TABLE_SCALE (HAL_ADC_RANGE / _BV(THERMISTOR_TABLE_ADC_RESOLUTION))
#if ENABLED(HAL_ADC_FILTERED)
#define OVERSAMPLENR 1
#elif HAL_ADC_RESOLUTION > 10
#define OVERSAMPLENR (20 - HAL_ADC_RESOLUTION)
#else
#define OVERSAMPLENR 16
#endif
#define MAX_RAW_THERMISTOR_VALUE (HAL_ADC_RANGE * (OVERSAMPLENR) - 1)
// Currently Marlin stores all oversampled ADC values as int16_t, make sure the HAL settings do not overflow 15bit
#if MAX_RAW_THERMISTOR_VALUE > ((1 << 15) - 1)
#error "MAX_RAW_THERMISTOR_VALUE is too large for int16_t. Reduce OVERSAMPLENR or HAL_ADC_RESOLUTION."
#endif
#define OV_SCALE(N) (N)
#define OV(N) int16_t(OV_SCALE(N) * (OVERSAMPLENR) * (THERMISTOR_TABLE_SCALE))
#define ANY_THERMISTOR_IS(n) (TEMP_SENSOR_0_THERMISTOR_ID == n || TEMP_SENSOR_1_THERMISTOR_ID == n || TEMP_SENSOR_2_THERMISTOR_ID == n || TEMP_SENSOR_3_THERMISTOR_ID == n || TEMP_SENSOR_4_THERMISTOR_ID == n || TEMP_SENSOR_5_THERMISTOR_ID == n || TEMP_SENSOR_6_THERMISTOR_ID == n || TEMP_SENSOR_7_THERMISTOR_ID == n || TEMP_SENSOR_BED_THERMISTOR_ID == n || TEMP_SENSOR_CHAMBER_THERMISTOR_ID == n || TEMP_SENSOR_COOLER_THERMISTOR_ID == n || TEMP_SENSOR_PROBE_THERMISTOR_ID == n)
typedef struct { int16_t value; celsius_t celsius; } temp_entry_t;
// Pt1000 and Pt100 handling
//
// Rt=R0*(1+a*T+b*T*T) [for T>0]
// a=3.9083E-3, b=-5.775E-7
#define PtA 3.9083E-3
#define PtB -5.775E-7
#define PtRt(T,R0) ((R0) * (1.0 + (PtA) * (T) + (PtB) * (T) * (T)))
#define PtAdVal(T,R0,Rup) (short)(1024 / (Rup / PtRt(T, R0) + 1))
#define PtLine(T,R0,Rup) { OV(PtAdVal(T, R0, Rup)), T }
#if ANY_THERMISTOR_IS(1) // beta25 = 4092 K, R25 = 100 kOhm, Pull-up = 4.7 kOhm, "EPCOS"
#include "thermistor_1.h"
#endif
#if ANY_THERMISTOR_IS(2) // 4338 K, R25 = 200 kOhm, Pull-up = 4.7 kOhm, "ATC Semitec 204GT-2"
#include "thermistor_2.h"
#endif
#if ANY_THERMISTOR_IS(3) // beta25 = 4120 K, R25 = 100 kOhm, Pull-up = 4.7 kOhm, "Mendel-parts"
#include "thermistor_3.h"
#endif
#if ANY_THERMISTOR_IS(4) // beta25 = 3950 K, R25 = 10 kOhm, Pull-up = 4.7 kOhm, "Generic"
#include "thermistor_4.h"
#endif
#if ANY_THERMISTOR_IS(5) // beta25 = 4267 K, R25 = 100 kOhm, Pull-up = 4.7 kOhm, "ParCan, ATC 104GT-2"
#include "thermistor_5.h"
#endif
#if ANY_THERMISTOR_IS(501) // 100K Zonestar thermistor
#include "thermistor_501.h"
#endif
#if ANY_THERMISTOR_IS(502) // Unknown thermistor used by the Zonestar Průša P802M hot bed
#include "thermistor_502.h"
#endif
#if ANY_THERMISTOR_IS(503) // Zonestar (Z8XM2) Heated Bed thermistor
#include "thermistor_503.h"
#endif
#if ANY_THERMISTOR_IS(512) // 100k thermistor in RPW-Ultra hotend, Pull-up = 4.7 kOhm, "unknown model"
#include "thermistor_512.h"
#endif
#if ANY_THERMISTOR_IS(6) // beta25 = 4092 K, R25 = 100 kOhm, Pull-up = 8.2 kOhm, "EPCOS ?"
#include "thermistor_6.h"
#endif
#if ANY_THERMISTOR_IS(7) // beta25 = 3974 K, R25 = 100 kOhm, Pull-up = 4.7 kOhm, "Honeywell 135-104LAG-J01"
#include "thermistor_7.h"
#endif
#if ANY_THERMISTOR_IS(71) // beta25 = 3974 K, R25 = 100 kOhm, Pull-up = 4.7 kOhm, "Honeywell 135-104LAF-J01"
#include "thermistor_71.h"
#endif
#if ANY_THERMISTOR_IS(8) // beta25 = 3950 K, R25 = 100 kOhm, Pull-up = 10 kOhm, "Vishay E3104FHT"
#include "thermistor_8.h"
#endif
#if ANY_THERMISTOR_IS(9) // beta25 = 3960 K, R25 = 100 kOhm, Pull-up = 4.7 kOhm, "GE Sensing AL03006-58.2K-97-G1"
#include "thermistor_9.h"
#endif
#if ANY_THERMISTOR_IS(10) // beta25 = 3960 K, R25 = 100 kOhm, Pull-up = 4.7 kOhm, "RS 198-961"
#include "thermistor_10.h"
#endif
#if ANY_THERMISTOR_IS(11) // beta25 = 3950 K, R25 = 100 kOhm, Pull-up = 4.7 kOhm, "QU-BD silicone bed, QWG-104F-3950"
#include "thermistor_11.h"
#endif
#if ANY_THERMISTOR_IS(13) // beta25 = 4100 K, R25 = 100 kOhm, Pull-up = 4.7 kOhm, "Hisens"
#include "thermistor_13.h"
#endif
#if ANY_THERMISTOR_IS(14) // beta25 = 4092 K, R25 = 100 kOhm, Pull-up = 4.7 kOhm, "EPCOS" for hot bed
#include "thermistor_14.h"
#endif
#if ANY_THERMISTOR_IS(15) // JGAurora A5 thermistor calibration
#include "thermistor_15.h"
#endif
#if ANY_THERMISTOR_IS(17) // Dagoma NTC 100k white thermistor
#include "thermistor_17.h"
#endif
#if ANY_THERMISTOR_IS(18) // ATC Semitec 204GT-2 (4.7k pullup) Dagoma.Fr - MKS_Base_DKU001327
#include "thermistor_18.h"
#endif
#if ANY_THERMISTOR_IS(20) // Pt100 with INA826 amp on Ultimaker v2.0 electronics
#include "thermistor_20.h"
#endif
#if ANY_THERMISTOR_IS(21) // Pt100 with INA826 amp with 3.3v excitation based on "Pt100 with INA826 amp on Ultimaker v2.0 electronics"
#include "thermistor_21.h"
#endif
#if ANY_THERMISTOR_IS(22) // Thermistor in a Rostock 301 hot end, calibrated with a multimeter
#include "thermistor_22.h"
#endif
#if ANY_THERMISTOR_IS(23) // By AluOne #12622. Formerly 22 above. May need calibration/checking.
#include "thermistor_23.h"
#endif
#if ANY_THERMISTOR_IS(30) // Kis3d Silicone mat 24V 200W/300W with 6mm Precision cast plate (EN AW 5083)
#include "thermistor_30.h"
#endif
#if ANY_THERMISTOR_IS(51) // beta25 = 4092 K, R25 = 100 kOhm, Pull-up = 1 kOhm, "EPCOS"
#include "thermistor_51.h"
#endif
#if ANY_THERMISTOR_IS(52) // beta25 = 4338 K, R25 = 200 kOhm, Pull-up = 1 kOhm, "ATC Semitec 204GT-2"
#include "thermistor_52.h"
#endif
#if ANY_THERMISTOR_IS(55) // beta25 = 4267 K, R25 = 100 kOhm, Pull-up = 1 kOhm, "ATC Semitec 104GT-2 (Used on ParCan)"
#include "thermistor_55.h"
#endif
#if ANY_THERMISTOR_IS(60) // beta25 = 3950 K, R25 = 100 kOhm, Pull-up = 4.7 kOhm, "Maker's Tool Works Kapton Bed"
#include "thermistor_60.h"
#endif
#if ANY_THERMISTOR_IS(61) // beta25 = 3950 K, R25 = 100 kOhm, Pull-up = 4.7 kOhm, "Formbot 350°C Thermistor"
#include "thermistor_61.h"
#endif
#if ANY_THERMISTOR_IS(66) // beta25 = 4500 K, R25 = 2.5 MOhm, Pull-up = 4.7 kOhm, "DyzeDesign 500 °C Thermistor"
#include "thermistor_66.h"
#endif
#if ANY_THERMISTOR_IS(67) // R25 = 500 KOhm, beta25 = 3800 K, 4.7 kOhm pull-up, SliceEngineering 450 °C Thermistor
#include "thermistor_67.h"
#endif
#if ANY_THERMISTOR_IS(12) // beta25 = 4700 K, R25 = 100 kOhm, Pull-up = 4.7 kOhm, "Personal calibration for Makibox hot bed"
#include "thermistor_12.h"
#endif
#if ANY_THERMISTOR_IS(70) // beta25 = 4100 K, R25 = 100 kOhm, Pull-up = 4.7 kOhm, "Hephestos 2, bqh2 stock thermistor"
#include "thermistor_70.h"
#endif
#if ANY_THERMISTOR_IS(75) // beta25 = 4100 K, R25 = 100 kOhm, Pull-up = 4.7 kOhm, "MGB18-104F39050L32 thermistor"
#include "thermistor_75.h"
#endif
#if ANY_THERMISTOR_IS(99) // 100k bed thermistor with a 10K pull-up resistor (on some Wanhao i3 models)
#include "thermistor_99.h"
#endif
#if ANY_THERMISTOR_IS(110) // Pt100 with 1k0 pullup
#include "thermistor_110.h"
#endif
#if ANY_THERMISTOR_IS(147) // Pt100 with 4k7 pullup
#include "thermistor_147.h"
#endif
#if ANY_THERMISTOR_IS(201) // Pt100 with LMV324 Overlord
#include "thermistor_201.h"
#endif
#if ANY_THERMISTOR_IS(202) // 200K thermistor in Copymaker3D hotend
#include "thermistor_202.h"
#endif
#if ANY_THERMISTOR_IS(331) // Like table 1, but with 3V3 as input voltage for MEGA
#include "thermistor_331.h"
#endif
#if ANY_THERMISTOR_IS(332) // Like table 1, but with 3V3 as input voltage for DUE
#include "thermistor_332.h"
#endif
#if ANY_THERMISTOR_IS(666) // beta25 = UNK, R25 = 200K, Pull-up = 10 kOhm, "Unidentified 200K NTC thermistor (Einstart S)"
#include "thermistor_666.h"
#endif
#if ANY_THERMISTOR_IS(1010) // Pt1000 with 1k0 pullup
#include "thermistor_1010.h"
#endif
#if ANY_THERMISTOR_IS(1047) // Pt1000 with 4k7 pullup
#include "thermistor_1047.h"
#endif
#if ANY_THERMISTOR_IS(998) // User-defined table 1
#include "thermistor_998.h"
#endif
#if ANY_THERMISTOR_IS(999) // User-defined table 2
#include "thermistor_999.h"
#endif
#if ANY_THERMISTOR_IS(1000) // Custom
const temp_entry_t temptable_1000[] PROGMEM = { { 0, 0 } };
#endif
#define _TT_NAME(_N) temptable_ ## _N
#define TT_NAME(_N) _TT_NAME(_N)
#if TEMP_SENSOR_0_THERMISTOR_ID
#define TEMPTABLE_0 TT_NAME(TEMP_SENSOR_0_THERMISTOR_ID)
#define TEMPTABLE_0_LEN COUNT(TEMPTABLE_0)
#elif TEMP_SENSOR_0_IS_THERMISTOR
#error "No heater 0 thermistor table specified"
#else
#define TEMPTABLE_0 nullptr
#define TEMPTABLE_0_LEN 0
#endif
#if TEMP_SENSOR_1_THERMISTOR_ID
#define TEMPTABLE_1 TT_NAME(TEMP_SENSOR_1_THERMISTOR_ID)
#define TEMPTABLE_1_LEN COUNT(TEMPTABLE_1)
#elif TEMP_SENSOR_1_IS_THERMISTOR
#error "No heater 1 thermistor table specified"
#else
#define TEMPTABLE_1 nullptr
#define TEMPTABLE_1_LEN 0
#endif
#if TEMP_SENSOR_2_THERMISTOR_ID
#define TEMPTABLE_2 TT_NAME(TEMP_SENSOR_2_THERMISTOR_ID)
#define TEMPTABLE_2_LEN COUNT(TEMPTABLE_2)
#elif TEMP_SENSOR_2_IS_THERMISTOR
#error "No heater 2 thermistor table specified"
#else
#define TEMPTABLE_2 nullptr
#define TEMPTABLE_2_LEN 0
#endif
#if TEMP_SENSOR_3_THERMISTOR_ID
#define TEMPTABLE_3 TT_NAME(TEMP_SENSOR_3_THERMISTOR_ID)
#define TEMPTABLE_3_LEN COUNT(TEMPTABLE_3)
#elif TEMP_SENSOR_3_IS_THERMISTOR
#error "No heater 3 thermistor table specified"
#else
#define TEMPTABLE_3 nullptr
#define TEMPTABLE_3_LEN 0
#endif
#if TEMP_SENSOR_4_THERMISTOR_ID
#define TEMPTABLE_4 TT_NAME(TEMP_SENSOR_4_THERMISTOR_ID)
#define TEMPTABLE_4_LEN COUNT(TEMPTABLE_4)
#elif TEMP_SENSOR_4_IS_THERMISTOR
#error "No heater 4 thermistor table specified"
#else
#define TEMPTABLE_4 nullptr
#define TEMPTABLE_4_LEN 0
#endif
#if TEMP_SENSOR_5_THERMISTOR_ID
#define TEMPTABLE_5 TT_NAME(TEMP_SENSOR_5_THERMISTOR_ID)
#define TEMPTABLE_5_LEN COUNT(TEMPTABLE_5)
#elif TEMP_SENSOR_5_IS_THERMISTOR
#error "No heater 5 thermistor table specified"
#else
#define TEMPTABLE_5 nullptr
#define TEMPTABLE_5_LEN 0
#endif
#if TEMP_SENSOR_6_THERMISTOR_ID
#define TEMPTABLE_6 TT_NAME(TEMP_SENSOR_6_THERMISTOR_ID)
#define TEMPTABLE_6_LEN COUNT(TEMPTABLE_6)
#elif TEMP_SENSOR_6_IS_THERMISTOR
#error "No heater 6 thermistor table specified"
#else
#define TEMPTABLE_6 nullptr
#define TEMPTABLE_6_LEN 0
#endif
#if TEMP_SENSOR_7_THERMISTOR_ID
#define TEMPTABLE_7 TT_NAME(TEMP_SENSOR_7_THERMISTOR_ID)
#define TEMPTABLE_7_LEN COUNT(TEMPTABLE_7)
#elif TEMP_SENSOR_7_IS_THERMISTOR
#error "No heater 7 thermistor table specified"
#else
#define TEMPTABLE_7 nullptr
#define TEMPTABLE_7_LEN 0
#endif
#ifdef TEMP_SENSOR_BED_THERMISTOR_ID
#define TEMPTABLE_BED TT_NAME(TEMP_SENSOR_BED_THERMISTOR_ID)
#define TEMPTABLE_BED_LEN COUNT(TEMPTABLE_BED)
#elif TEMP_SENSOR_BED_IS_THERMISTOR
#error "No bed thermistor table specified"
#else
#define TEMPTABLE_BED_LEN 0
#endif
#ifdef TEMP_SENSOR_CHAMBER_THERMISTOR_ID
#define TEMPTABLE_CHAMBER TT_NAME(TEMP_SENSOR_CHAMBER_THERMISTOR_ID)
#define TEMPTABLE_CHAMBER_LEN COUNT(TEMPTABLE_CHAMBER)
#elif TEMP_SENSOR_CHAMBER_IS_THERMISTOR
#error "No chamber thermistor table specified"
#else
#define TEMPTABLE_CHAMBER_LEN 0
#endif
#ifdef TEMP_SENSOR_COOLER_THERMISTOR_ID
#define TEMPTABLE_COOLER TT_NAME(TEMP_SENSOR_COOLER_THERMISTOR_ID)
#define TEMPTABLE_COOLER_LEN COUNT(TEMPTABLE_COOLER)
#elif TEMP_SENSOR_COOLER_IS_THERMISTOR
#error "No cooler thermistor table specified"
#else
#define TEMPTABLE_COOLER_LEN 0
#endif
#ifdef TEMP_SENSOR_PROBE_THERMISTOR_ID
#define TEMPTABLE_PROBE TT_NAME(TEMP_SENSOR_PROBE_THERMISTOR_ID)
#define TEMPTABLE_PROBE_LEN COUNT(TEMPTABLE_PROBE)
#elif TEMP_SENSOR_PROBE_IS_THERMISTOR
#error "No probe thermistor table specified"
#else
#define TEMPTABLE_PROBE_LEN 0
#endif
// The SCAN_THERMISTOR_TABLE macro needs alteration?
static_assert(
TEMPTABLE_0_LEN < 256 && TEMPTABLE_1_LEN < 256
&& TEMPTABLE_2_LEN < 256 && TEMPTABLE_3_LEN < 256
&& TEMPTABLE_4_LEN < 256 && TEMPTABLE_5_LEN < 256
&& TEMPTABLE_6_LEN < 256 && TEMPTABLE_7_LEN < 256
&& TEMPTABLE_BED_LEN < 256 && TEMPTABLE_CHAMBER_LEN < 256
&& TEMPTABLE_COOLER_LEN < 256 && TEMPTABLE_PROBE_LEN < 256,
"Temperature conversion tables over 255 entries need special consideration."
);
// Set the high and low raw values for the heaters
// For thermistors the highest temperature results in the lowest ADC value
// For thermocouples the highest temperature results in the highest ADC value
#define __TT_REV(N) REVERSE_TEMP_SENSOR_RANGE_##N
#define _TT_REV(N) __TT_REV(N)
#define TT_REV(N) _TT_REV(TEMP_SENSOR_##N##_THERMISTOR_ID)
#define _TT_REVRAW(N) !TEMP_SENSOR_##N##_IS_THERMISTOR
#define TT_REVRAW(N) (TT_REV(N) || _TT_REVRAW(N))
#ifdef TEMPTABLE_0
#if TT_REV(0)
#define TEMP_SENSOR_0_MINTEMP_IND 0
#define TEMP_SENSOR_0_MAXTEMP_IND TEMPTABLE_0_LEN - 1
#else
#define TEMP_SENSOR_0_MINTEMP_IND TEMPTABLE_0_LEN - 1
#define TEMP_SENSOR_0_MAXTEMP_IND 0
#endif
#endif
#ifdef TEMPTABLE_1
#if TT_REV(1)
#define TEMP_SENSOR_1_MINTEMP_IND 0
#define TEMP_SENSOR_1_MAXTEMP_IND TEMPTABLE_1_LEN - 1
#else
#define TEMP_SENSOR_1_MINTEMP_IND TEMPTABLE_1_LEN - 1
#define TEMP_SENSOR_1_MAXTEMP_IND 0
#endif
#endif
#ifdef TEMPTABLE_2
#if TT_REV(2)
#define TEMP_SENSOR_2_MINTEMP_IND 0
#define TEMP_SENSOR_2_MAXTEMP_IND TEMPTABLE_2_LEN - 1
#else
#define TEMP_SENSOR_2_MINTEMP_IND TEMPTABLE_2_LEN - 1
#define TEMP_SENSOR_2_MAXTEMP_IND 0
#endif
#endif
#ifdef TEMPTABLE_3
#if TT_REV(3)
#define TEMP_SENSOR_3_MINTEMP_IND 0
#define TEMP_SENSOR_3_MAXTEMP_IND TEMPTABLE_3_LEN - 1
#else
#define TEMP_SENSOR_3_MINTEMP_IND TEMPTABLE_3_LEN - 1
#define TEMP_SENSOR_3_MAXTEMP_IND 0
#endif
#endif
#ifdef TEMPTABLE_4
#if TT_REV(4)
#define TEMP_SENSOR_4_MINTEMP_IND 0
#define TEMP_SENSOR_4_MAXTEMP_IND TEMPTABLE_4_LEN - 1
#else
#define TEMP_SENSOR_4_MINTEMP_IND TEMPTABLE_4_LEN - 1
#define TEMP_SENSOR_4_MAXTEMP_IND 0
#endif
#endif
#ifdef TEMPTABLE_5
#if TT_REV(5)
#define TEMP_SENSOR_5_MINTEMP_IND 0
#define TEMP_SENSOR_5_MAXTEMP_IND TEMPTABLE_5_LEN - 1
#else
#define TEMP_SENSOR_5_MINTEMP_IND TEMPTABLE_5_LEN - 1
#define TEMP_SENSOR_5_MAXTEMP_IND 0
#endif
#endif
#ifdef TEMPTABLE_6
#if TT_REV(6)
#define TEMP_SENSOR_6_MINTEMP_IND 0
#define TEMP_SENSOR_6_MAXTEMP_IND TEMPTABLE_6_LEN - 1
#else
#define TEMP_SENSOR_6_MINTEMP_IND TEMPTABLE_6_LEN - 1
#define TEMP_SENSOR_6_MAXTEMP_IND 0
#endif
#endif
#ifdef TEMPTABLE_7
#if TT_REV(7)
#define TEMP_SENSOR_7_MINTEMP_IND 0
#define TEMP_SENSOR_7_MAXTEMP_IND TEMPTABLE_7_LEN - 1
#else
#define TEMP_SENSOR_7_MINTEMP_IND TEMPTABLE_7_LEN - 1
#define TEMP_SENSOR_7_MAXTEMP_IND 0
#endif
#endif
#ifndef TEMP_SENSOR_0_RAW_HI_TEMP
#if TT_REVRAW(0)
#define TEMP_SENSOR_0_RAW_HI_TEMP MAX_RAW_THERMISTOR_VALUE
#define TEMP_SENSOR_0_RAW_LO_TEMP 0
#else
#define TEMP_SENSOR_0_RAW_HI_TEMP 0
#define TEMP_SENSOR_0_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE
#endif
#endif
#ifndef TEMP_SENSOR_1_RAW_HI_TEMP
#if TT_REVRAW(1)
#define TEMP_SENSOR_1_RAW_HI_TEMP MAX_RAW_THERMISTOR_VALUE
#define TEMP_SENSOR_1_RAW_LO_TEMP 0
#else
#define TEMP_SENSOR_1_RAW_HI_TEMP 0
#define TEMP_SENSOR_1_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE
#endif
#endif
#ifndef TEMP_SENSOR_2_RAW_HI_TEMP
#if TT_REVRAW(2)
#define TEMP_SENSOR_2_RAW_HI_TEMP MAX_RAW_THERMISTOR_VALUE
#define TEMP_SENSOR_2_RAW_LO_TEMP 0
#else
#define TEMP_SENSOR_2_RAW_HI_TEMP 0
#define TEMP_SENSOR_2_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE
#endif
#endif
#ifndef TEMP_SENSOR_3_RAW_HI_TEMP
#if TT_REVRAW(3)
#define TEMP_SENSOR_3_RAW_HI_TEMP MAX_RAW_THERMISTOR_VALUE
#define TEMP_SENSOR_3_RAW_LO_TEMP 0
#else
#define TEMP_SENSOR_3_RAW_HI_TEMP 0
#define TEMP_SENSOR_3_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE
#endif
#endif
#ifndef TEMP_SENSOR_4_RAW_HI_TEMP
#if TT_REVRAW(4)
#define TEMP_SENSOR_4_RAW_HI_TEMP MAX_RAW_THERMISTOR_VALUE
#define TEMP_SENSOR_4_RAW_LO_TEMP 0
#else
#define TEMP_SENSOR_4_RAW_HI_TEMP 0
#define TEMP_SENSOR_4_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE
#endif
#endif
#ifndef TEMP_SENSOR_5_RAW_HI_TEMP
#if TT_REVRAW(5)
#define TEMP_SENSOR_5_RAW_HI_TEMP MAX_RAW_THERMISTOR_VALUE
#define TEMP_SENSOR_5_RAW_LO_TEMP 0
#else
#define TEMP_SENSOR_5_RAW_HI_TEMP 0
#define TEMP_SENSOR_5_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE
#endif
#endif
#ifndef TEMP_SENSOR_6_RAW_HI_TEMP
#if TT_REVRAW(6)
#define TEMP_SENSOR_6_RAW_HI_TEMP MAX_RAW_THERMISTOR_VALUE
#define TEMP_SENSOR_6_RAW_LO_TEMP 0
#else
#define TEMP_SENSOR_6_RAW_HI_TEMP 0
#define TEMP_SENSOR_6_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE
#endif
#endif
#ifndef TEMP_SENSOR_7_RAW_HI_TEMP
#if TT_REVRAW(7)
#define TEMP_SENSOR_7_RAW_HI_TEMP MAX_RAW_THERMISTOR_VALUE
#define TEMP_SENSOR_7_RAW_LO_TEMP 0
#else
#define TEMP_SENSOR_7_RAW_HI_TEMP 0
#define TEMP_SENSOR_7_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE
#endif
#endif
#ifndef TEMP_SENSOR_BED_RAW_HI_TEMP
#if TT_REVRAW(BED)
#define TEMP_SENSOR_BED_RAW_HI_TEMP MAX_RAW_THERMISTOR_VALUE
#define TEMP_SENSOR_BED_RAW_LO_TEMP 0
#else
#define TEMP_SENSOR_BED_RAW_HI_TEMP 0
#define TEMP_SENSOR_BED_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE
#endif
#endif
#ifndef TEMP_SENSOR_CHAMBER_RAW_HI_TEMP
#if TT_REVRAW(CHAMBER)
#define TEMP_SENSOR_CHAMBER_RAW_HI_TEMP MAX_RAW_THERMISTOR_VALUE
#define TEMP_SENSOR_CHAMBER_RAW_LO_TEMP 0
#else
#define TEMP_SENSOR_CHAMBER_RAW_HI_TEMP 0
#define TEMP_SENSOR_CHAMBER_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE
#endif
#endif
#ifndef TEMP_SENSOR_COOLER_RAW_HI_TEMP
#if TT_REVRAW(COOLER)
#define TEMP_SENSOR_COOLER_RAW_HI_TEMP MAX_RAW_THERMISTOR_VALUE
#define TEMP_SENSOR_COOLER_RAW_LO_TEMP 0
#else
#define TEMP_SENSOR_COOLER_RAW_HI_TEMP 0
#define TEMP_SENSOR_COOLER_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE
#endif
#endif
#ifndef TEMP_SENSOR_PROBE_RAW_HI_TEMP
#if TT_REVRAW(PROBE)
#define TEMP_SENSOR_PROBE_RAW_HI_TEMP MAX_RAW_THERMISTOR_VALUE
#define TEMP_SENSOR_PROBE_RAW_LO_TEMP 0
#else
#define TEMP_SENSOR_PROBE_RAW_HI_TEMP 0
#define TEMP_SENSOR_PROBE_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE
#endif
#endif
#undef __TT_REV
#undef _TT_REV
#undef TT_REV
#undef _TT_REVRAW
#undef TT_REVRAW
File diff suppressed because it is too large Load Diff
+127
View File
@@ -0,0 +1,127 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
#include "../inc/MarlinConfig.h"
//#define DEBUG_TOOLCHANGE_MIGRATION_FEATURE
#if HAS_MULTI_EXTRUDER
typedef struct {
#if ENABLED(TOOLCHANGE_FILAMENT_SWAP)
float swap_length, extra_prime, extra_resume;
int16_t prime_speed, retract_speed, unretract_speed, fan, fan_speed, fan_time;
#endif
#if ENABLED(TOOLCHANGE_PARK)
bool enable_park;
xy_pos_t change_point;
#endif
float z_raise;
} toolchange_settings_t;
extern toolchange_settings_t toolchange_settings;
#if ENABLED(TOOLCHANGE_FILAMENT_SWAP)
void tool_change_prime();
#endif
#if ENABLED(TOOLCHANGE_FS_PRIME_FIRST_USED)
extern bool enable_first_prime;
#endif
#if ENABLED(TOOLCHANGE_FS_INIT_BEFORE_SWAP)
extern bool toolchange_extruder_ready[EXTRUDERS];
#endif
#if ENABLED(TOOLCHANGE_MIGRATION_FEATURE)
typedef struct {
uint8_t target, last;
bool automode, in_progress;
} migration_settings_t;
constexpr migration_settings_t migration_defaults = { 0, 0, false, false };
extern migration_settings_t migration;
bool extruder_migration();
#endif
#endif
#if DO_SWITCH_EXTRUDER
void move_extruder_servo(const uint8_t e);
#endif
#if ENABLED(SWITCHING_NOZZLE)
#if SWITCHING_NOZZLE_TWO_SERVOS
void lower_nozzle(const uint8_t e);
void raise_nozzle(const uint8_t e);
#else
void move_nozzle_servo(const uint8_t angle_index);
#endif
#endif
#if ENABLED(PARKING_EXTRUDER)
void pe_solenoid_set_pin_state(const uint8_t extruder_num, const uint8_t state);
#define PE_MAGNET_ON_STATE TERN_(PARKING_EXTRUDER_SOLENOIDS_INVERT, !)PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE
inline void pe_solenoid_magnet_on(const uint8_t extruder_num) { pe_solenoid_set_pin_state(extruder_num, PE_MAGNET_ON_STATE); }
inline void pe_solenoid_magnet_off(const uint8_t extruder_num) { pe_solenoid_set_pin_state(extruder_num, !PE_MAGNET_ON_STATE); }
void pe_solenoid_init();
extern bool extruder_parked;
inline void parking_extruder_set_parked(const bool parked) { extruder_parked = parked; }
bool parking_extruder_unpark_after_homing(const uint8_t final_tool, bool homed_towards_final_tool);
#elif ENABLED(MAGNETIC_PARKING_EXTRUDER)
typedef struct MPESettings {
float parking_xpos[2], // M951 L R
grab_distance; // M951 I
feedRate_t slow_feedrate, // M951 J
fast_feedrate; // M951 H
float travel_distance, // M951 D
compensation_factor; // M951 C
} mpe_settings_t;
extern mpe_settings_t mpe_settings;
void mpe_settings_init();
#endif
#if ENABLED(ELECTROMAGNETIC_SWITCHING_TOOLHEAD)
void est_init();
#elif ENABLED(SWITCHING_TOOLHEAD)
void swt_init();
#endif
#if ENABLED(TOOL_SENSOR)
uint8_t check_tool_sensor_stats(const uint8_t active_tool, const bool kill_on_error=false, const bool disable=false);
#else
inline uint8_t check_tool_sensor_stats(const uint8_t, const bool=false, const bool=false) { return 0; }
#endif
/**
* Perform a tool-change, which may result in moving the
* previous tool out of the way and the new tool into place.
*/
void tool_change(const uint8_t tmp_extruder, bool no_move=false);