diff --git a/README.md b/README.md index b09748bd8..af62998bc 100644 --- a/README.md +++ b/README.md @@ -157,7 +157,7 @@ NOTES: µCNC with a configuration similar to Grbl is be able to keep up to 30KHz step rate for a 3 axis machine on an Arduino Uno at 16Mhz. (the stated rate depends on the length of the segments too, since many short length segments don't allow full speed to be achieved). For this specific type of use (like in laser engraving) a 16-bit version of stepping algorithm is possible pushing the theoretical step rate limit to 40KHz on a single UNO board. -### Current µCNC supported hardware +### µCNC current supported hardware µCNC initial development was done both around Arduino UNO board just like GRBL. But µCNC can also be installed in other AVR boards like Arduino Mega (for Ramps), or similar boards (like Rambo). Other MCU's have and will be integrated in µCNC: @@ -173,6 +173,16 @@ It can run on: - NXP LPC1768 - v1.5.x (eeprom emulation and analog still being developed) - Windows PC (used for simulation/debugging only - ISR on Windows doesn't allow to use it as a real alternative) +### µCNC current supported kinematics + +µCNC is designed to be support both linear and non-linear kinematics and can be extended to support other types of kinematics. +Currently µCNC supports the following kinematics: + +- Cartesian +- CoreXY +- Linear delta robot +- Rotary delta robot + ### µCNC roadmap A couple of changes were introduced with version 1.2.0 of µCNC to prepare for future and easier expansions. diff --git a/makefiles/virtual/uCNC.dev b/makefiles/virtual/uCNC.dev index 35f39637a..553ad60f7 100644 --- a/makefiles/virtual/uCNC.dev +++ b/makefiles/virtual/uCNC.dev @@ -29,7 +29,7 @@ IncludeVersionInfo=0 SupportXPThemes=0 CompilerSet=1 CompilerSettings=000000e0a0000000001000000 -UnitCount=70 +UnitCount=73 [VersionInfo] Major=1 @@ -511,7 +511,7 @@ OverrideBuildCmd=0 BuildCmd= [Unit47] -FileName=..\..\uCNC\src\hal\kinematics\kinematic_delta.c +FileName=..\..\uCNC\src\hal\kinematics\kinematic_linear_delta.c CompileCpp=0 Folder= Compile=1 @@ -571,7 +571,7 @@ OverrideBuildCmd=0 BuildCmd= [Unit48] -FileName=..\..\uCNC\src\hal\kinematics\kinematic_delta.h +FileName=..\..\uCNC\src\hal\kinematics\kinematic_linear_delta.h CompileCpp=0 Folder= Compile=1 @@ -751,7 +751,27 @@ OverrideBuildCmd=0 BuildCmd= [Unit71] -FileName=..\..\uCNC\src\hal\tools\tools\laser_ppi.c +FileName=..\..\uCNC\src\hal\kinematics\kinematic_delta.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit72] +FileName=..\..\uCNC\src\hal\kinematics\kinematic_delta.h +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit73] +FileName=..\..\uCNC\src\utils.h CompileCpp=0 Folder= Compile=1 diff --git a/uCNC/src/cnc_hal_config_helper.h b/uCNC/src/cnc_hal_config_helper.h index d7b64ceed..3436f4c3c 100644 --- a/uCNC/src/cnc_hal_config_helper.h +++ b/uCNC/src/cnc_hal_config_helper.h @@ -2077,7 +2077,7 @@ typedef uint16_t step_t; #endif #endif -#if (KINEMATIC == KINEMATIC_DELTA) +#if (defined(KINEMATICS_MOTION_BY_SEGMENTS)) #ifdef ENABLE_DUAL_DRIVE_AXIS #error "Delta does not support dual drive axis" #endif diff --git a/uCNC/src/core/interpolator.c b/uCNC/src/core/interpolator.c index 40e179553..d783b5a04 100644 --- a/uCNC/src/core/interpolator.c +++ b/uCNC/src/core/interpolator.c @@ -107,7 +107,7 @@ static uint8_t prev_dss; static int16_t prev_spindle; // pointer to the segment being executed static itp_segment_t *itp_rt_sgm; -#if (defined(ENABLE_DUAL_DRIVE_AXIS) || (KINEMATIC == KINEMATIC_DELTA)) +#if (defined(ENABLE_DUAL_DRIVE_AXIS) || defined(IS_DELTA_KINEMATICS)) static volatile uint8_t itp_step_lock; #endif @@ -218,7 +218,7 @@ void itp_init(void) memset(itp_blk_data, 0, sizeof(itp_blk_data)); memset(itp_sgm_data, 0, sizeof(itp_sgm_data)); itp_rt_sgm = NULL; -#if (defined(ENABLE_DUAL_DRIVE_AXIS) || (KINEMATIC == KINEMATIC_DELTA)) +#if (defined(ENABLE_DUAL_DRIVE_AXIS) || defined(IS_DELTA_KINEMATICS)) itp_step_lock = 0; #endif #endif @@ -280,7 +280,7 @@ void itp_run(void) // overwrites previous values #ifdef ENABLE_BACKLASH_COMPENSATION - itp_blk_data[itp_blk_data_write].backlash_comp = itp_cur_plan_block->backlash_comp; + itp_blk_data[itp_blk_data_write].backlash_comp = itp_cur_plan_block->planner_flags.bit.backlash_comp; #endif itp_blk_data[itp_blk_data_write].dirbits = itp_cur_plan_block->dirbits; @@ -292,11 +292,10 @@ void itp_run(void) itp_blk_data[itp_blk_data_write].dirbits |= CHECKFLAG(itp_blk_data[itp_blk_data_write].dirbits, STEP_DUAL1) ? STEP_DUAL1_MASK : 0; #endif #endif - itp_blk_data[itp_blk_data_write].total_steps = itp_cur_plan_block->total_steps << 1; + step_t total_steps = itp_cur_plan_block->steps[itp_cur_plan_block->main_stepper]; + itp_blk_data[itp_blk_data_write].total_steps = total_steps << 1; - float total_step_inv = 1.0f / (float)itp_cur_plan_block->total_steps; - feed_convert = 60.f / (float)g_settings.step_per_mm[itp_cur_plan_block->main_stepper]; - float sqr_step_speed = 0; + feed_convert = itp_cur_plan_block->feed_conversion; #ifdef STEP_ISR_SKIP_IDLE itp_blk_data[itp_blk_data_write].idle_axis = 0; @@ -306,8 +305,7 @@ void itp_run(void) #endif for (uint8_t i = 0; i < STEPPER_COUNT; i++) { - sqr_step_speed += fast_flt_pow2((float)itp_cur_plan_block->steps[i]); - itp_blk_data[itp_blk_data_write].errors[i] = itp_cur_plan_block->total_steps; + itp_blk_data[itp_blk_data_write].errors[i] = total_steps; itp_blk_data[itp_blk_data_write].steps[i] = itp_cur_plan_block->steps[i] << 1; #ifdef STEP_ISR_SKIP_IDLE if (!itp_cur_plan_block->steps[i]) @@ -317,14 +315,11 @@ void itp_run(void) #endif } - sqr_step_speed *= fast_flt_pow2(total_step_inv); - feed_convert *= fast_flt_sqrt(sqr_step_speed); - // flags block for recalculation of speeds itp_needs_update = true; } - uint32_t remaining_steps = itp_cur_plan_block->total_steps; + uint32_t remaining_steps = itp_cur_plan_block->steps[itp_cur_plan_block->main_stepper]; sgm = &itp_sgm_data[itp_sgm_data_write]; @@ -509,7 +504,7 @@ void itp_run(void) } // computes how many steps it will perform at this speed and frame window - segm_steps = (uint16_t)roundf(partial_distance); + segm_steps = (uint16_t)lroundf(partial_distance); } while (segm_steps == 0); avg_speed = fast_flt_div2(current_speed + initial_speed); @@ -620,9 +615,9 @@ void itp_run(void) } itp_cur_plan_block->entry_feed_sqr = fast_flt_pow2(current_speed); - itp_cur_plan_block->total_steps = remaining_steps; + itp_cur_plan_block->steps[itp_cur_plan_block->main_stepper] = remaining_steps; - if (itp_cur_plan_block->total_steps == 0) + if (remaining_steps == 0) { itp_blk_buffer_write(); itp_cur_plan_block = NULL; @@ -694,7 +689,7 @@ void itp_run(void) // overwrites previous values #ifdef ENABLE_BACKLASH_COMPENSATION - itp_blk_data[itp_blk_data_write].backlash_comp = itp_cur_plan_block->flags_u.flags_t.backlash_comp; + itp_blk_data[itp_blk_data_write].backlash_comp = itp_cur_plan_block->planner_flags.bit.backlash_comp; #endif itp_blk_data[itp_blk_data_write].dirbits = itp_cur_plan_block->dirbits; #ifdef ENABLE_DUAL_DRIVE_AXIS @@ -705,11 +700,10 @@ void itp_run(void) itp_blk_data[itp_blk_data_write].dirbits |= CHECKFLAG(itp_blk_data[itp_blk_data_write].dirbits, STEP_DUAL1) ? STEP_DUAL1_MASK : 0; #endif #endif - itp_blk_data[itp_blk_data_write].total_steps = itp_cur_plan_block->total_steps << 1; + step_t total_steps = itp_cur_plan_block->steps[itp_cur_plan_block->main_stepper]; + itp_blk_data[itp_blk_data_write].total_steps = total_steps << 1; - float total_step_inv = 1.0f / (float)itp_cur_plan_block->total_steps; - feed_convert = 60.f / (float)g_settings.step_per_mm[itp_cur_plan_block->main_stepper]; - float sqr_step_speed = 0; + feed_convert = itp_cur_plan_block->feed_conversion; #ifdef STEP_ISR_SKIP_IDLE itp_blk_data[itp_blk_data_write].idle_axis = 0; @@ -719,12 +713,7 @@ void itp_run(void) #endif for (uint8_t i = 0; i < STEPPER_COUNT; i++) { -#ifdef ENABLE_LASER_PPI - sqr_step_speed += (i != (STEPPER_COUNT - 1)) ? (fast_flt_pow2((float)itp_cur_plan_block->steps[i])) : 0; -#else - sqr_step_speed += fast_flt_pow2((float)itp_cur_plan_block->steps[i]); -#endif - itp_blk_data[itp_blk_data_write].errors[i] = itp_cur_plan_block->total_steps; + itp_blk_data[itp_blk_data_write].errors[i] = total_steps; itp_blk_data[itp_blk_data_write].steps[i] = itp_cur_plan_block->steps[i] << 1; #ifdef STEP_ISR_SKIP_IDLE if (!itp_cur_plan_block->steps[i]) @@ -734,9 +723,6 @@ void itp_run(void) #endif } - sqr_step_speed *= fast_flt_pow2(total_step_inv); - feed_convert *= fast_flt_sqrt(sqr_step_speed); - // flags block for recalculation of speeds itp_needs_update = true; // in every new block speed update is needed @@ -746,7 +732,7 @@ void itp_run(void) half_speed_change = fast_flt_div2(half_speed_change); } - uint32_t remaining_steps = itp_cur_plan_block->total_steps; + uint32_t remaining_steps = itp_cur_plan_block->steps[itp_cur_plan_block->main_stepper]; sgm = &itp_sgm_data[itp_sgm_data_write]; @@ -969,9 +955,9 @@ void itp_run(void) itp_cur_plan_block->entry_feed_sqr = junction_speed_sqr; } - itp_cur_plan_block->total_steps = remaining_steps; + itp_cur_plan_block->steps[itp_cur_plan_block->main_stepper] = remaining_steps; - if (itp_cur_plan_block->total_steps == 0) + if (remaining_steps == 0) { itp_blk_buffer_write(); itp_cur_plan_block = NULL; @@ -1078,16 +1064,14 @@ int32_t itp_get_rt_position_index(int8_t index) void itp_reset_rt_position(float *origin) { - if (g_settings.homing_enabled) - { - kinematics_apply_inverse(origin, itp_rt_step_pos); - } - else + if (!g_settings.homing_enabled) { - memset(itp_rt_step_pos, 0, sizeof(itp_rt_step_pos)); memset(origin, 0, (sizeof(float) * AXIS_COUNT)); } + // sync origin and steppers position + kinematics_apply_inverse(origin, itp_rt_step_pos); + #if STEPPERS_ENCODERS_MASK != 0 encoders_itp_reset_rt_position(origin); #endif @@ -1136,7 +1120,7 @@ void itp_sync_spindle(void) #endif } -#if (defined(ENABLE_DUAL_DRIVE_AXIS) || (KINEMATIC == KINEMATIC_DELTA)) +#if (defined(ENABLE_DUAL_DRIVE_AXIS) || defined(IS_DELTA_KINEMATICS)) void itp_lock_stepper(uint8_t lockmask) { itp_step_lock = lockmask; @@ -1619,7 +1603,7 @@ MCU_CALLBACK void mcu_step_cb(void) mcu_disable_global_isr(); // lock isr before clearin busy flag itp_busy = false; -#if (defined(ENABLE_DUAL_DRIVE_AXIS) || (KINEMATIC == KINEMATIC_DELTA)) +#if (defined(ENABLE_DUAL_DRIVE_AXIS) || defined(IS_DELTA_KINEMATICS)) stepbits &= ~itp_step_lock; #endif } diff --git a/uCNC/src/core/interpolator.h b/uCNC/src/core/interpolator.h index 274037d01..0c0f788f6 100644 --- a/uCNC/src/core/interpolator.h +++ b/uCNC/src/core/interpolator.h @@ -41,7 +41,7 @@ extern "C" float itp_get_rt_feed(void); uint8_t itp_sync(void); void itp_sync_spindle(void); -#if (defined(ENABLE_DUAL_DRIVE_AXIS) || (KINEMATIC == KINEMATIC_DELTA)) +#if (defined(ENABLE_DUAL_DRIVE_AXIS) || defined(KINEMATICS_MOTION_BY_SEGMENTS)) void itp_lock_stepper(uint8_t lockmask); #endif #ifdef GCODE_PROCESS_LINE_NUMBERS diff --git a/uCNC/src/core/io_control.c b/uCNC/src/core/io_control.c index 773a94c06..f28aedcf9 100644 --- a/uCNC/src/core/io_control.c +++ b/uCNC/src/core/io_control.c @@ -110,7 +110,7 @@ MCU_IO_CALLBACK void mcu_limits_changed_cb(void) #endif if (limit_combined) { -#if (defined(DUAL_DRIVE0_ENABLE_SELFSQUARING) || defined(DUAL_DRIVE1_ENABLE_SELFSQUARING) || (KINEMATIC == KINEMATIC_DELTA)) +#if (defined(DUAL_DRIVE0_ENABLE_SELFSQUARING) || defined(DUAL_DRIVE1_ENABLE_SELFSQUARING) || defined(IS_DELTA_KINEMATICS)) if (cnc_get_exec_state((EXEC_RUN | EXEC_HOMING)) == (EXEC_RUN | EXEC_HOMING) && (io_lock_limits_mask & limit_combined)) { // if homing and dual drive axis are enabled @@ -137,7 +137,7 @@ MCU_IO_CALLBACK void mcu_limits_changed_cb(void) } } #endif -#if (KINEMATIC == KINEMATIC_DELTA) +#if (defined(IS_DELTA_KINEMATICS)) if ((limit_combined & LIMITS_DELTA_MASK)) { if (limit_combined != LIMITS_DELTA_MASK) @@ -154,7 +154,7 @@ MCU_IO_CALLBACK void mcu_limits_changed_cb(void) } #endif -#if (defined(DUAL_DRIVE0_ENABLE_SELFSQUARING) || defined(DUAL_DRIVE1_ENABLE_SELFSQUARING) || (KINEMATIC == KINEMATIC_DELTA)) +#if (defined(DUAL_DRIVE0_ENABLE_SELFSQUARING) || defined(DUAL_DRIVE1_ENABLE_SELFSQUARING) || defined(IS_DELTA_KINEMATICS)) itp_lock_stepper(0); // unlocks axis #endif itp_stop(); diff --git a/uCNC/src/core/motion_control.c b/uCNC/src/core/motion_control.c index 4f35fab2f..8cb37f80b 100644 --- a/uCNC/src/core/motion_control.c +++ b/uCNC/src/core/motion_control.c @@ -20,6 +20,15 @@ #include #include +// default segment length for non linear kinematics +#ifdef KINEMATICS_MOTION_BY_SEGMENTS +#ifndef KINEMATICS_MOTION_SEGMENT_SIZE +#define KINEMATICS_MOTION_SEGMENT_SIZE 1.0f +#endif +#endif + +#define KINEMATICS_MOTION_SEGMENT_INV_SIZE (1.0f / KINEMATICS_MOTION_SEGMENT_SIZE) + static bool mc_checkmode; static int32_t mc_last_step_pos[STEPPER_COUNT]; static float mc_last_target[AXIS_COUNT]; @@ -66,10 +75,11 @@ static uint8_t mc_line_segment(int32_t *step_new_pos, motion_data_t *block_data) #ifdef ENABLE_LINACT_PLANNER block_data->full_steps = 0; #endif - block_data->total_steps = 0; -#if KINEMATIC == KINEMATIC_DELTA +#if defined(KINEMATICS_MOTION_BY_SEGMENTS) block_data->dirbits = 0; #endif + uint32_t max_steps = 0; + for (uint8_t i = STEPPER_COUNT; i != 0;) { i--; @@ -77,7 +87,7 @@ static uint8_t mc_line_segment(int32_t *step_new_pos, motion_data_t *block_data) uint32_t steps = (uint32_t)ABS(s); block_data->steps[i] = (step_t)steps; -#if KINEMATIC == KINEMATIC_DELTA +#if defined(KINEMATICS_MOTION_BY_SEGMENTS) // with the delta dir bits need to be rechecked if (s < 0) { @@ -88,10 +98,11 @@ static uint8_t mc_line_segment(int32_t *step_new_pos, motion_data_t *block_data) #ifdef ENABLE_LINACT_PLANNER block_data->full_steps += steps; #endif - if (block_data->total_steps < steps) + + if (max_steps < steps) { - block_data->total_steps = steps; -#if KINEMATIC == KINEMATIC_DELTA + max_steps = steps; +#if defined(KINEMATICS_MOTION_BY_SEGMENTS) // with the delta main stepper need to be rechecked block_data->main_stepper = i; #endif @@ -99,7 +110,7 @@ static uint8_t mc_line_segment(int32_t *step_new_pos, motion_data_t *block_data) } // no significant motion will take place. don't send any thing to the planner - if (!(block_data->total_steps)) + if (!max_steps) { return STATUS_OK; } @@ -118,14 +129,13 @@ static uint8_t mc_line_segment(int32_t *step_new_pos, motion_data_t *block_data) memcpy(&backlash_block_data, block_data, sizeof(motion_data_t)); memset(backlash_block_data.steps, 0, sizeof(backlash_block_data.steps)); // resets accumulator vars - backlash_block_data.total_steps = 0; #ifdef ENABLE_LINACT_PLANNER backlash_block_data.full_steps = 0; #endif - backlash_block_data.feed = FLT_MAX; // max feedrate possible (same as rapid move) + backlash_block_data.feed = backlash_block_data.max_feed; // max feedrate possible (same as rapid move) SETFLAG(backlash_block_data.motion_mode, MOTIONCONTROL_MODE_BACKLASH_COMPENSATION); - + max_steps = 0; for (uint8_t i = STEPPER_COUNT; i != 0;) { i--; @@ -135,9 +145,9 @@ static uint8_t mc_line_segment(int32_t *step_new_pos, motion_data_t *block_data) #ifdef ENABLE_LINACT_PLANNER backlash_block_data.full_steps += backlash_block_data.steps[i]; #endif - if (backlash_block_data.total_steps < backlash_block_data.steps[i]) + if (max_steps < backlash_block_data.steps[i]) { - backlash_block_data.total_steps = backlash_block_data.steps[i]; + max_steps = backlash_block_data.steps[i]; backlash_block_data.main_stepper = i; } } @@ -189,6 +199,10 @@ static uint8_t mc_line_segment(int32_t *step_new_pos, motion_data_t *block_data) uint8_t mc_line(float *target, motion_data_t *block_data) { float prev_target[AXIS_COUNT]; +#ifndef ENABLE_LINACT_PLANNER + static float last_dir_vect[AXIS_COUNT]; +#endif + float dir_vect[AXIS_COUNT]; block_data->dirbits = 0; // reset dirbits (this prevents odd behaviour generated by long arcs) // In homing mode no kinematics modifications is applied to prevent unwanted axis movements @@ -209,10 +223,31 @@ uint8_t mc_line(float *target, motion_data_t *block_data) } uint8_t error = STATUS_OK; + + // gets the previous machine position (transformed to calculate the direction vector and travelled distance) + memcpy(prev_target, mc_last_target, sizeof(mc_last_target)); + + // calculates the travelled distance + float line_dist = 0; + float motion_segment[AXIS_COUNT]; + for (uint8_t i = AXIS_COUNT; i != 0;) + { + i--; + motion_segment[i] = target[i] - prev_target[i]; + dir_vect[i] = motion_segment[i]; + line_dist += fast_flt_pow2(dir_vect[i]); + } + + // no motion. bail out. + if (line_dist == 0) + { + return STATUS_OK; + } + int32_t step_new_pos[STEPPER_COUNT]; // converts transformed target to stepper position kinematics_apply_inverse(target, step_new_pos); - // calculates the amount of stepper motion for this motion + // calculates the amount of steps performed for this motion uint32_t max_steps = 0; block_data->main_stepper = 255; @@ -239,45 +274,36 @@ uint8_t mc_line(float *target, motion_data_t *block_data) return STATUS_OK; } - // checks the amount of steps that this motion translates to - // if the amount of steps is higher than the limit for the 16bit bresenham algorithm - // splits the line into smaller segments - - // gets the previous machine position (transformed to calculate the direction vector and travelled distance) - memcpy(prev_target, mc_last_target, sizeof(mc_last_target)); - - // calculates the aproximation of the inverted travelled distance - float inv_dist = 0; - float motion_segment[AXIS_COUNT]; - for (uint8_t i = AXIS_COUNT; i != 0;) - { - i--; - motion_segment[i] = target[i] - prev_target[i]; - block_data->dir_vect[i] = motion_segment[i]; - inv_dist += fast_flt_pow2(block_data->dir_vect[i]); - } - - // no motion. bail out. - if (inv_dist == 0) - { - return STATUS_OK; - } - -#if ((KINEMATIC == KINEMATIC_DELTA) || defined(ENABLE_LASER_PPI)) - float line_dist = fast_flt_sqrt(inv_dist); - inv_dist = 1.0f / line_dist; -#else - inv_dist = fast_flt_invsqrt(inv_dist); -#endif + // calculates the linear distance travelled + line_dist = fast_flt_sqrt(line_dist); + float inv_dist = 1.0f / line_dist; + // feed values + float max_feed = FLT_MAX; + float max_accel = FLT_MAX; + float feed = block_data->feed; + // angle between motion lines + block_data->cos_theta = 0; // calculates max junction speed factor in (axis driven). Else the cos_theta is calculated in the planner (linear actuator driven) -#ifndef ENABLE_LINACT_PLANNER for (uint8_t i = AXIS_COUNT; i != 0;) { i--; - block_data->dir_vect[i] *= inv_dist; - } + // calculates the normalized vector + float normal_vect = dir_vect[i] * inv_dist; +#ifndef ENABLE_LINACT_PLANNER + block_data->cos_theta += normal_vect * last_dir_vect[i]; + last_dir_vect[i] = normal_vect; #endif + dir_vect[i] = normal_vect; + normal_vect = ABS(normal_vect); + // denormalize max feed rate for each axis + float denorm_param = g_settings.max_feed_rate[i] / normal_vect; + max_feed = MIN(max_feed, denorm_param); + denorm_param = g_settings.acceleration[i] / normal_vect; + max_accel = MIN(max_accel, denorm_param); + } + max_feed *= inv_dist; + max_accel *= inv_dist; #ifdef ENABLE_LASER_PPI mc_last_step_pos[STEPPER_COUNT - 1] = 0; @@ -299,43 +325,57 @@ uint8_t mc_line(float *target, motion_data_t *block_data) } laser_pulses_per_mm *= line_dist; + // adjust max feed rate to ppi settings + max_feed = MIN(max_feed, g_settings.max_feed_rate[STEPPER_COUNT - 1] * inv_dist); } step_new_pos[STEPPER_COUNT - 1] = laser_pulses_per_mm; - max_steps = MAX(max_steps, step_new_pos[STEPPER_COUNT - 1]); + if (step_new_pos[STEPPER_COUNT - 1] > max_steps) + { + max_steps = MAX(max_steps, step_new_pos[STEPPER_COUNT - 1]); + block_data->main_stepper = STEPPER_COUNT - 1; + } #endif - // calculated the total motion execution time @ the given rate - float feed = block_data->feed; - float inv_delta = (!CHECKFLAG(block_data->motion_mode, MOTIONCONTROL_MODE_INVERSEFEED) ? (block_data->feed * inv_dist) : block_data->feed); - block_data->feed = (float)max_steps * inv_delta; - -#if ((KINEMATIC == KINEMATIC_DELTA) || defined(BRESENHAM_16BIT)) + // calculated amount ot time @ the given feed rate + float step_feed = (!CHECKFLAG(block_data->motion_mode, MOTIONCONTROL_MODE_INVERSEFEED) ? (block_data->feed * inv_dist) : block_data->feed); + float feed_convert_to_steps_per_sec = (float)max_steps; + // convert accel already in steps/s + block_data->max_accel = feed_convert_to_steps_per_sec * max_accel; + // convert feed from steps/min to steps/s + feed_convert_to_steps_per_sec *= MIN_SEC_MULT; + step_feed *= feed_convert_to_steps_per_sec; + max_feed *= feed_convert_to_steps_per_sec; + block_data->feed = MIN(max_feed, step_feed); + block_data->max_feed = max_feed; + + block_data->feed_conversion = line_dist / feed_convert_to_steps_per_sec; + +#if (defined(KINEMATICS_MOTION_BY_SEGMENTS) || defined(BRESENHAM_16BIT)) // this contains a motion. Any tool update will be done here uint32_t line_segments = 1; -#if (KINEMATIC == KINEMATIC_DELTA) - line_segments = (uint32_t)ceilf(line_dist * DELTA_MOTION_SEGMENT_FACTOR); +#ifdef KINEMATICS_MOTION_BY_SEGMENTS + line_segments = MAX((uint32_t)ceilf(line_dist * KINEMATICS_MOTION_SEGMENT_INV_SIZE), line_segments); +#endif +#ifdef BRESENHAM_16BIT + // checks the amount of steps that this motion translates to + // if the amount of steps is higher than the limit for the 16bit bresenham algorithm + // splits the line into smaller segments + if (max_steps > MAX_STEPS_PER_LINE) + { + line_segments = MAX((max_steps >> MAX_STEPS_PER_LINE_BITS) + 1, line_segments); + } +#endif + float m_inv = 1.0f / (float)line_segments; for (uint8_t i = AXIS_COUNT; i != 0;) { i--; motion_segment[i] *= m_inv; } -#else - if (max_steps > MAX_STEPS_PER_LINE) - { - line_segments += (max_steps >> MAX_STEPS_PER_LINE_BITS); - float m_inv = 1.0f / (float)line_segments; - for (uint8_t i = AXIS_COUNT; i != 0;) - { - i--; - motion_segment[i] *= m_inv; - } - } -#endif + bool is_subsegment = false; while (--line_segments) { - block_data->motion_flags.bit.is_subsegment = 1; for (uint8_t i = AXIS_COUNT; i != 0;) { i--; @@ -350,9 +390,13 @@ uint8_t mc_line(float *target, motion_data_t *block_data) block_data->feed = feed; return error; } + + // after the first segment all following segments are inline + block_data->cos_theta = 1; + is_subsegment = true; } - if (block_data->motion_flags.bit.is_subsegment) + if (is_subsegment) { kinematics_apply_inverse(target, step_new_pos); } @@ -361,7 +405,6 @@ uint8_t mc_line(float *target, motion_data_t *block_data) // stores the new position for the next motion memcpy(mc_last_target, target, sizeof(mc_last_target)); block_data->feed = feed; - block_data->motion_flags.bit.is_subsegment = 0; return error; } @@ -570,9 +613,8 @@ uint8_t mc_home_axis(uint8_t axis, uint8_t axis_limit) mc_get_position(target); target[axis] += max_home_dist; // initializes planner block data - block_data.total_steps = ABS(max_home_dist); - memset(block_data.steps, 0, sizeof(block_data.steps)); - block_data.steps[axis] = max_home_dist; + // memset(block_data.steps, 0, sizeof(block_data.steps)); + // block_data.steps[axis] = max_home_dist; block_data.feed = g_settings.homing_fast_feed_rate; block_data.spindle = 0; block_data.dwell = 0; @@ -617,8 +659,7 @@ uint8_t mc_home_axis(uint8_t axis, uint8_t axis_limit) target[axis] += max_home_dist; block_data.feed = g_settings.homing_slow_feed_rate; - block_data.total_steps = ABS(max_home_dist); - block_data.steps[axis] = max_home_dist; + // block_data.steps[axis] = max_home_dist; // unlocks the machine for next motion (this will clear the EXEC_HALT flag // temporary inverts the limit mask to trigger ISR on switch release io_invert_limits(axis_limit); diff --git a/uCNC/src/core/motion_control.h b/uCNC/src/core/motion_control.h index 8f7316db6..a83271a88 100644 --- a/uCNC/src/core/motion_control.h +++ b/uCNC/src/core/motion_control.h @@ -48,10 +48,10 @@ extern "C" uint8_t spindle_running : 2; uint8_t coolant : 2; uint8_t coolant_override : 2; + uint8_t : 1; // unused #else - uint8_t : 6; // unused + uint8_t : 7; // unused #endif - uint8_t is_subsegment : 1; } bit; } motion_flags_t; @@ -61,13 +61,15 @@ extern "C" uint32_t line; #endif step_t steps[STEPPER_COUNT]; - float dir_vect[AXIS_COUNT]; uint8_t dirbits; - #ifdef ENABLE_LINACT_PLANNER +#ifdef ENABLE_LINACT_PLANNER uint32_t full_steps; // number of steps of all linear actuators - #endif - step_t total_steps; // the number of pulses needed to generate all steps (maximum of all linear actuators) +#endif float feed; + float max_feed; + float max_accel; + float feed_conversion; + float cos_theta; //angle between current and previous motion uint8_t main_stepper; uint16_t spindle; uint16_t dwell; diff --git a/uCNC/src/core/parser.c b/uCNC/src/core/parser.c index 40c389668..b8d3a08bd 100644 --- a/uCNC/src/core/parser.c +++ b/uCNC/src/core/parser.c @@ -708,7 +708,7 @@ static uint8_t parser_fetch_command(parser_state_t *new_state, parser_words_t *w } uint8_t code = (uint8_t)floorf(value); // check mantissa - uint8_t mantissa = (uint8_t)roundf((value - code) * 100.0f); + uint8_t mantissa = (uint8_t)lroundf((value - code) * 100.0f); switch (word) { @@ -1117,12 +1117,11 @@ uint8_t parser_exec_command(parser_state_t *new_state, parser_words_t *words, pa break; case M127: g_settings.step_per_mm[STEPPER_COUNT - 1] = words->p * MM_INCH_MULT; - g_settings.max_feed_rate[STEPPER_COUNT - 1] = (60000000.0f / (g_settings.laser_ppi_uswidth + (2000000.0f / g_settings.max_step_rate))) / g_settings.step_per_mm[STEPPER_COUNT - 1]; + parser_config_ppi(); break; case M128: g_settings.laser_ppi_uswidth = (uint16_t)words->p; - g_settings.max_feed_rate[STEPPER_COUNT - 1] = (60000000.0f / (words->p + (2000000.0f / g_settings.max_step_rate))) / g_settings.step_per_mm[STEPPER_COUNT - 1]; - mcu_config_timeout(&laser_ppi_turnoff_cb, (uint16_t)words->p); + parser_config_ppi(); break; #endif default: @@ -1188,7 +1187,7 @@ uint8_t parser_exec_command(parser_state_t *new_state, parser_words_t *words, pa { mc_update_tools(&block_data); #if (DELAY_ON_SPINDLE_SPEED_CHANGE > 0) - block_data.dwell = (uint16_t)roundf(DELAY_ON_SPINDLE_SPEED_CHANGE * 1000); + block_data.dwell = (uint16_t)lroundf(DELAY_ON_SPINDLE_SPEED_CHANGE * 1000); #endif #if (defined(TOOL_WAIT_FOR_SPEED) && (TOOL_WAIT_FOR_SPEED_MAX_ERROR != 100)) float tool_speed_error = 0; @@ -1218,7 +1217,7 @@ uint8_t parser_exec_command(parser_state_t *new_state, parser_words_t *words, pa if (new_state->groups.nonmodal == G4) { // calc dwell in milliseconds - block_data.dwell = MAX(block_data.dwell, (uint16_t)roundf(MIN(words->p * 1000.f, 65535))); + block_data.dwell = MAX(block_data.dwell, (uint16_t)lroundf(MIN(words->p * 1000.0f, 65535))); new_state->groups.nonmodal = 0; } @@ -2932,8 +2931,12 @@ void parser_config_ppi(void) g_settings.acceleration[STEPPER_COUNT - 1] = FLT_MAX; if (g_settings.laser_mode & (LASER_PPI_MODE | LASER_PPI_VARPOWER_MODE)) { - g_settings.step_per_mm[STEPPER_COUNT - 1] = g_settings.laser_ppi * MM_INCH_MULT; - g_settings.max_feed_rate[STEPPER_COUNT - 1] = (60000000.0f / (g_settings.laser_ppi_uswidth + (2000000.0f / g_settings.max_step_rate))) / (g_settings.laser_ppi * MM_INCH_MULT); + // if previously disabled, reload default value + if (!g_settings.step_per_mm[STEPPER_COUNT - 1]) + { + g_settings.step_per_mm[STEPPER_COUNT - 1] = g_settings.laser_ppi * MM_INCH_MULT; + } + g_settings.max_feed_rate[STEPPER_COUNT - 1] = (60000000.0f / (g_settings.laser_ppi_uswidth * g_settings.step_per_mm[STEPPER_COUNT - 1])); mcu_config_timeout(&laser_ppi_turnoff_cb, g_settings.laser_ppi_uswidth); } else diff --git a/uCNC/src/core/planner.c b/uCNC/src/core/planner.c index b85c3c930..4f54874e8 100644 --- a/uCNC/src/core/planner.c +++ b/uCNC/src/core/planner.c @@ -63,12 +63,16 @@ FORCEINLINE static void planner_buffer_clear(void); */ void planner_add_line(motion_data_t *block_data) { +#ifdef ENABLE_LINACT_PLANNER static float last_dir_vect[STEPPER_COUNT]; +#endif // clear the planner block uint8_t index = planner_data_write; + float cos_theta = block_data->cos_theta; memset(&planner_data[index], 0, sizeof(planner_block_t)); planner_data[index].dirbits = block_data->dirbits; + planner_data[index].feed_conversion = block_data->feed_conversion; planner_data[index].main_stepper = block_data->main_stepper; planner_data[index].planner_flags.reg &= ~STATE_COPY_FLAG_MASK; planner_data[index].planner_flags.reg |= (block_data->motion_flags.reg & STATE_COPY_FLAG_MASK); // copies the motion flags relative to coolant spindle running and feed_override @@ -84,73 +88,39 @@ void planner_add_line(motion_data_t *block_data) #ifdef ENABLE_BACKLASH_COMPENSATION if (CHECKFLAG(block_data->motion_mode, MOTIONCONTROL_MODE_BACKLASH_COMPENSATION)) { - planner_data[index].flags_u.flags_t.backlash_comp = true; + planner_data[index].planner_flags.bit.backlash_comp = true; } #endif memcpy(planner_data[index].steps, block_data->steps, sizeof(planner_data[index].steps)); - planner_data[index].total_steps = block_data->total_steps; // calculates the normalized vector with the amount of motion in any linear actuator // also calculates the maximum feedrate and acceleration for each linear actuator #ifdef ENABLE_LINACT_PLANNER float inv_total_steps = 1.0f / (float)(block_data->full_steps); -#endif -#ifdef ENABLE_LINACT_COLD_START - bool coldstart = false; -#endif - float cos_theta = 0; - float rapid_feed = FLT_MAX; - planner_data[index].acceleration = FLT_MAX; - -#ifdef ENABLE_LINACT_PLANNER float dir_vect[STEPPER_COUNT]; memset(dir_vect, 0, sizeof(dir_vect)); -#else - - if (!block_data->motion_flags.bit.is_subsegment) - { - for (uint8_t i = AXIS_COUNT; i != 0;) - { - i--; - cos_theta += block_data->dir_vect[i] * last_dir_vect[i]; - last_dir_vect[i] = block_data->dir_vect[i]; - } - } - else - { - cos_theta = 1; - } - -#endif for (uint8_t i = STEPPER_COUNT; i != 0;) { i--; if (planner_data[index].steps[i] != 0) { -#ifdef ENABLE_LINACT_PLANNER dir_vect[i] = inv_total_steps * (float)planner_data[index].steps[i]; if (!planner_buffer_is_empty()) { cos_theta += last_dir_vect[i] * dir_vect[i]; #ifdef ENABLE_LINACT_COLD_START - if (last_dir_vect[i] == 0) // tests if actuator is starting from a full stop + if (last_dir_vect[i] == 0) // checks if actuator is starting from a full stop { - coldstart = true; + // then forces a full start and stop motion + cos_theta = -100; } #endif } last_dir_vect[i] = dir_vect[i]; -#endif - // calculate (per linear actuator) the minimum inverted time of travel (1/min) an acceleration (1/s^2) - float step_ratio = g_settings.step_per_mm[i] / (float)planner_data[index].steps[i]; - float stepper_feed = g_settings.max_feed_rate[i] * step_ratio; - rapid_feed = MIN(rapid_feed, stepper_feed); - float stepper_accel = g_settings.acceleration[i] * step_ratio; - planner_data[index].acceleration = MIN(planner_data[index].acceleration, stepper_accel); } else { @@ -158,20 +128,11 @@ void planner_add_line(motion_data_t *block_data) } } - // converts to steps per second (st/s) - float feed = block_data->feed * MIN_SEC_MULT; - rapid_feed *= MIN_SEC_MULT; - rapid_feed *= (float)block_data->total_steps; - // converts to steps per second^2 (st/s^2) - planner_data[index].acceleration *= (float)block_data->total_steps; - - if (feed > rapid_feed) - { - feed = rapid_feed; - } +#endif - planner_data[index].feed_sqr = fast_flt_pow2(feed); - planner_data[index].rapid_feed_sqr = fast_flt_pow2(rapid_feed); + planner_data[index].feed_sqr = fast_flt_pow2(block_data->feed); + planner_data[index].rapid_feed_sqr = fast_flt_pow2(block_data->max_feed); + planner_data[index].acceleration = block_data->max_accel; // consider initial angle factor of 1 (90 degree angle corner or more) float angle_factor = 1.0f; @@ -197,7 +158,7 @@ void planner_add_line(motion_data_t *block_data) // if more than one move stored cals juntion speeds and recalculates speed profiles if (cos_theta != 0 && !CHECKFLAG(block_data->motion_mode, PLANNER_MOTION_EXACT_STOP | MOTIONCONTROL_MODE_BACKLASH_COMPENSATION)) { - if (!block_data->motion_flags.bit.is_subsegment) + if (cos_theta != 1.0f) { // calculates the junction angle with previous if (cos_theta > 0) @@ -418,7 +379,7 @@ float planner_get_block_top_speed(float exit_speed_sqr) uint8_t index = planner_data_read; float speed_delta = exit_speed_sqr - planner_data[index].entry_feed_sqr; // caclculates the speed increase/decrease for the given distance - float junction_speed_sqr = planner_data[index].acceleration * (float)(planner_data[index].total_steps); + float junction_speed_sqr = planner_data[index].acceleration * (float)(planner_data[index].steps[planner_data[index].main_stepper]); junction_speed_sqr = fast_flt_mul2(junction_speed_sqr); // if there is enough space to accelerate computes the junction speed if (junction_speed_sqr >= speed_delta) @@ -526,7 +487,7 @@ static void planner_recalculate(void) // found optimal break; } - speedchange = ((float)(planner_data[block].total_steps << 1)) * planner_data[block].acceleration; + speedchange = ((float)(planner_data[block].steps[planner_data[block].main_stepper] << 1)) * planner_data[block].acceleration; speedchange += (block != last) ? planner_data[next].entry_feed_sqr : 0; planner_data[block].entry_feed_sqr = MIN(planner_data[block].entry_max_feed_sqr, speedchange); @@ -540,7 +501,7 @@ static void planner_recalculate(void) // next block is moving at a faster speed if (planner_data[block].entry_feed_sqr < planner_data[next].entry_feed_sqr) { - speedchange = ((float)(planner_data[block].total_steps << 1)) * planner_data[block].acceleration; + speedchange = ((float)(planner_data[block].steps[planner_data[block].main_stepper] << 1)) * planner_data[block].acceleration; // check if the next block entry speed can be achieved speedchange += planner_data[block].entry_feed_sqr; if (speedchange < planner_data[next].entry_feed_sqr) diff --git a/uCNC/src/core/planner.h b/uCNC/src/core/planner.h index 65ca5b314..ae83318e7 100644 --- a/uCNC/src/core/planner.h +++ b/uCNC/src/core/planner.h @@ -62,9 +62,8 @@ typedef union #endif uint8_t dirbits; step_t steps[STEPPER_COUNT]; - step_t total_steps; uint8_t main_stepper; - + float feed_conversion; float entry_feed_sqr; float entry_max_feed_sqr; float feed_sqr; diff --git a/uCNC/src/hal/kinematics/README.md b/uCNC/src/hal/kinematics/README.md new file mode 100644 index 000000000..54ea22b2c --- /dev/null +++ b/uCNC/src/hal/kinematics/README.md @@ -0,0 +1,53 @@ +

+ +

+ + +# µCNC +µCNC - Universal CNC firmware for microcontrollers + +## Kinematics +Currently µCNC support the following kinematics + +### Cartesian +Cartesian kinematics is the standard supported kinematics and one of the most common type of kinematics used. +The settings to configure this type of kinematics are similar to Grbl and can be checked at the [Configuration page](https://github.com/Paciente8159/uCNC/wiki/Basic-user-guide#%C2%B5CNC-configurations) + +Additionaly this type of kinematics support skew compensation feature that uses the following settings: + +| Setting | Description | +| --- | --- | +| $37 | [XY skew compensation](https://github.com/Paciente8159/uCNC/wiki/Basic-user-guide#37-to-39---axis-skew-compensation) | +| $38 | [XZ skew compensation](https://github.com/Paciente8159/uCNC/wiki/Basic-user-guide#37-to-39---axis-skew-compensation) | +| $39 | [YZ skew compensation](https://github.com/Paciente8159/uCNC/wiki/Basic-user-guide#37-to-39---axis-skew-compensation) | + +### CoreXY +CoreXY kinematics is supported. +The settings to configure this type of kinematics are similar to Grbl and can be checked at the [Configuration page](https://github.com/Paciente8159/uCNC/wiki/Basic-user-guide#%C2%B5CNC-configurations) + +### Linear Delta +Linear Delta robot kinematics is supported. +The settings to configure this type of kinematics can be checked at the [Configuration page](https://github.com/Paciente8159/uCNC/wiki/Basic-user-guide#%C2%B5CNC-configurations) + +In addition to the standard configurations you need to set 2 extra settings: + +| Setting | Description | +| --- | --- | +| $106 | [Linear delta kinematic arm length, mm](https://github.com/Paciente8159/uCNC/wiki/Basic-user-guide#106---linear-delta-kinematic-arm-length-mm) | +| $107 | [Linear delta kinematic radial difference between the arm's tower joints and the effector joints, mm](https://github.com/Paciente8159/uCNC/wiki/Basic-user-guide#107---linear-delta-kinematic-radial-difference-between-the-arms-tower-joints-and-the-effector-joints-mm) | + +### Delta +Delta robot (rotary) kinematics is supported. +The settings to configure this type of kinematics can be checked at the [Configuration page](https://github.com/Paciente8159/uCNC/wiki/Basic-user-guide#%C2%B5CNC-configurations) + +In addition to the standard configurations you need to set 5 extra settings: + +| Setting | Description | +| --- | --- | +| $28 | [Delta homing bicep angle, degrees](https://github.com/Paciente8159/uCNC/wiki/Basic-user-guide#27---delta-homing-biceps-angle-degrees) | +| $106 | [Delta base radius, mm](https://github.com/Paciente8159/uCNC/wiki/Basic-user-guide#106---delta-base-radius-mm) | +| $107 | [Delta effector radius, mm](https://github.com/Paciente8159/uCNC/wiki/Basic-user-guide#107---delta-effector-radius-mm) | +| $108 | [Delta bicep length, mm](https://github.com/Paciente8159/uCNC/wiki/Basic-user-guide#108---delta-bicep-length-mm) | +| $109 | [Delta forearm length, mm](https://github.com/Paciente8159/uCNC/wiki/Basic-user-guide#109---delta-forearm-length-mm) | + +For more information please head to the [µCNC wiki page](https://github.com/Paciente8159/uCNC/wiki) diff --git a/uCNC/src/hal/kinematics/kinematic_cartesian.h b/uCNC/src/hal/kinematics/kinematic_cartesian.h index d24a492a3..27d6c7c73 100644 --- a/uCNC/src/hal/kinematics/kinematic_cartesian.h +++ b/uCNC/src/hal/kinematics/kinematic_cartesian.h @@ -24,6 +24,8 @@ extern "C" { #endif +#define KINEMATIC_TYPE_STR "C" + #ifdef __cplusplus } #endif diff --git a/uCNC/src/hal/kinematics/kinematic_corexy.h b/uCNC/src/hal/kinematics/kinematic_corexy.h index 8cbb4542d..83e0eaa00 100644 --- a/uCNC/src/hal/kinematics/kinematic_corexy.h +++ b/uCNC/src/hal/kinematics/kinematic_corexy.h @@ -24,7 +24,7 @@ extern "C" { #endif -// define extra kynematics +#define KINEMATIC_TYPE_STR "XY" #ifdef __cplusplus } diff --git a/uCNC/src/hal/kinematics/kinematic_delta.c b/uCNC/src/hal/kinematics/kinematic_delta.c index 8c7a82e2f..5585b9417 100644 --- a/uCNC/src/hal/kinematics/kinematic_delta.c +++ b/uCNC/src/hal/kinematics/kinematic_delta.c @@ -1,11 +1,11 @@ /* - Name: kinematic_delta.c + Name: KINEMATIC_LINEAR_DELTA.c Description: Implements all kinematics math equations to translate the motion of a delta machine. Also implements the homing motion for this type of machine. Copyright: Copyright (c) João Martins Author: João Martins - Date: 19/01/2022 + Date: 03/11/2022 µCNC is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by @@ -21,119 +21,297 @@ #if (KINEMATIC == KINEMATIC_DELTA) #include +#include #include -#define STEPPER0_FACTX (cos(STEPPER0_ANGLE * DEG_RAD_MULT)); -#define STEPPER0_FACTY (sin(STEPPER0_ANGLE * DEG_RAD_MULT)); -#define STEPPER1_FACTX (cos(STEPPER1_ANGLE * DEG_RAD_MULT)); -#define STEPPER1_FACTY (sin(STEPPER1_ANGLE * DEG_RAD_MULT)); -#define STEPPER2_FACTX (cos(STEPPER2_ANGLE * DEG_RAD_MULT)); -#define STEPPER2_FACTY (sin(STEPPER2_ANGLE * DEG_RAD_MULT)); +#define COS120 -0.5f +#define SIN120 0.8660254037844386468f +#define SQRT3 1.7320508075688772935f +#define SIN30 0.5f +#define HALF_TAN30 0.2886751345948128823f +#define TAN60 1.7320508075688772935f +#define FULL_TURN_INV 0.0027777777777777778f + +static float delta_base_half_f_tg30; +static float delta_effector_half_f_tg30; +static float delta_base_effector_half_f_tg30; +static float steps_per_angle[3]; +static float delta_cuboid_xy; +static float delta_cuboid_z_min; +static float delta_cuboid_z_max; +static float delta_cuboid_z_home; + +static void delta_home_angle_to_steps(int32_t *steps) +{ + memset(steps, 0, STEPPER_COUNT * sizeof(int32_t)); + + float angle = g_settings.delta_bicep_homing_angle; + steps[0] = (int32_t)lroundf(angle * steps_per_angle[0]); + steps[1] = (int32_t)lroundf(angle * steps_per_angle[1]); + steps[2] = (int32_t)lroundf(angle * steps_per_angle[2]); +} + +static void delta_calc_bounds(void) +{ + float maxx = -g_settings.delta_effector_radius - g_settings.delta_base_radius - g_settings.delta_forearm_length - g_settings.delta_bicep_length; + float maxz = maxx; + float minz = -maxx; + float s = MAX(g_settings.step_per_mm[0], MAX(g_settings.step_per_mm[1], g_settings.step_per_mm[2])); + float axis[AXIS_COUNT]; + int32_t steps[STEPPER_COUNT]; + int32_t r[8][STEPPER_COUNT]; + + // reset home offset + delta_cuboid_z_home = 0; + + memset(axis, 0, sizeof(axis)); + delta_home_angle_to_steps(steps); + kinematics_apply_forward(steps, axis); + +#if (defined(SET_ORIGIN_AT_HOME_POS) || defined(DELTA_HOME_LIMITS_MAXZ)) + float homez = axis[AXIS_Z]; +#endif -static float delta_arm_sqr; -static float delta_base_height; -static float delta_base_max_travel; -static float delta_x[3]; -static float delta_y[3]; + // find extents + for (int32_t z = 0; z < s; ++z) + { + steps[0] = z; + steps[1] = z; + steps[2] = z; + kinematics_apply_forward(steps, axis); + if (axis[0] != NAN) + { + if (minz > axis[2]) + minz = axis[2]; + if (maxz < axis[2]) + maxz = axis[2]; + } + } + +#ifdef DELTA_HOME_LIMITS_MAXZ + float btf = homez - g_settings.max_distance[AXIS_Z]; + if (minz < btf) + minz = btf; + if (maxz < homez) + maxz = homez; +#else + float btf = maxz - g_settings.max_distance[AXIS_Z]; + if (minz < btf) + minz = btf; +#endif + + float middlez = (maxz + minz) * 0.5; + // $('#output').append("

("+maxz+","+minz+","+middlez+")

"); + float original_dist = (maxz - middlez); + float dist = original_dist * 0.5; + float sum = 0; + float mint1 = g_settings.step_per_mm[0]; + float maxt1 = -g_settings.step_per_mm[0]; + float mint2 = g_settings.step_per_mm[1]; + float maxt2 = -g_settings.step_per_mm[1]; + float mint3 = g_settings.step_per_mm[2]; + float maxt3 = -g_settings.step_per_mm[2]; + + do + { + sum += dist; + axis[AXIS_X] = sum; + axis[AXIS_Y] = sum; + axis[AXIS_Z] = middlez + sum; + kinematics_apply_inverse(axis, r[0]); + axis[AXIS_X] = sum; + axis[AXIS_Y] = -sum; + axis[AXIS_Z] = middlez + sum; + kinematics_apply_inverse(axis, r[1]); + axis[AXIS_X] = -sum; + axis[AXIS_Y] = -sum; + axis[AXIS_Z] = middlez + sum; + kinematics_apply_inverse(axis, r[2]); + axis[AXIS_X] = -sum; + axis[AXIS_Y] = sum; + axis[AXIS_Z] = middlez + sum; + kinematics_apply_inverse(axis, r[3]); + axis[AXIS_X] = sum; + axis[AXIS_Y] = sum; + axis[AXIS_Z] = middlez - sum; + kinematics_apply_inverse(axis, r[4]); + axis[AXIS_X] = sum; + axis[AXIS_Y] = -sum; + axis[AXIS_Z] = middlez - sum; + kinematics_apply_inverse(axis, r[5]); + axis[AXIS_X] = -sum; + axis[AXIS_Y] = -sum; + axis[AXIS_Z] = middlez - sum; + kinematics_apply_inverse(axis, r[6]); + axis[AXIS_X] = -sum; + axis[AXIS_Y] = sum; + axis[AXIS_Z] = middlez - sum; + kinematics_apply_inverse(axis, r[7]); + if (r[0][0] == INT32_MAX || r[1][0] == INT32_MAX || r[2][0] == INT32_MAX || r[3][0] == INT32_MAX || + r[4][0] == INT32_MAX || r[5][0] == INT32_MAX || r[6][0] == INT32_MAX || r[7][0] == INT32_MAX) + { + sum -= dist; + dist *= 0.5; + } + else + { + for (uint8_t i = 0; i < 8; ++i) + { + if (mint1 > r[i][0]) + mint1 = r[i][0]; + if (maxt1 < r[i][0]) + maxt1 = r[i][0]; + if (mint2 > r[i][1]) + mint2 = r[i][1]; + if (maxt2 < r[i][1]) + maxt2 = r[i][1]; + if (mint3 > r[i][2]) + mint3 = r[i][2]; + if (maxt3 < r[i][2]) + maxt3 = r[i][2]; + } + } + } while (original_dist > sum && dist > 0.1); + + delta_cuboid_xy = sum; + delta_cuboid_z_min = minz; + delta_cuboid_z_max = maxz; +#ifdef SET_ORIGIN_AT_HOME_POS + delta_cuboid_z_home = homez; +#else + delta_cuboid_z_home = minz; +#endif +} void kinematics_init(void) { - float delta_triang_base = g_settings.delta_armbase_radius; - delta_arm_sqr = g_settings.delta_arm_length * g_settings.delta_arm_length; - delta_x[0] = delta_triang_base * STEPPER0_FACTX; - delta_x[1] = delta_triang_base * STEPPER1_FACTX; - delta_x[2] = delta_triang_base * STEPPER2_FACTX; - delta_y[0] = delta_triang_base * STEPPER0_FACTY; - delta_y[1] = delta_triang_base * STEPPER1_FACTY; - delta_y[2] = delta_triang_base * STEPPER2_FACTY; - delta_base_height = sqrtf(delta_arm_sqr - delta_x[0] * delta_x[0] - delta_y[0] * delta_y[0]); - float min_travel = (g_settings.delta_arm_length * cos(DELTA_ARM_MIN_ANGLE * DEG_RAD_MULT)) - delta_triang_base; - float max_travel = (g_settings.delta_arm_length * cos(DELTA_ARM_MAX_ANGLE * DEG_RAD_MULT)) - delta_triang_base; - min_travel = ABS(min_travel); - max_travel = ABS(max_travel); - delta_base_max_travel = MIN(min_travel, max_travel); + // reset home offset + delta_cuboid_z_home = 0; + delta_base_half_f_tg30 = HALF_TAN30 * g_settings.delta_base_radius; + delta_effector_half_f_tg30 = HALF_TAN30 * g_settings.delta_effector_radius; + delta_base_effector_half_f_tg30 = HALF_TAN30 * (g_settings.delta_base_radius - g_settings.delta_effector_radius); + steps_per_angle[0] = g_settings.step_per_mm[0] * FULL_TURN_INV; + steps_per_angle[1] = g_settings.step_per_mm[1] * FULL_TURN_INV; + steps_per_angle[2] = g_settings.step_per_mm[2] * FULL_TURN_INV; + delta_calc_bounds(); +} + +// inverse kinematics +// helper functions, calculates angle theta1 (for YZ-pane) +int8_t delta_calcAngleYZ(float x0, float y0, float z0, float *theta) +{ + float re = g_settings.delta_forearm_length; + float rf = g_settings.delta_bicep_length; + float y1 = -delta_base_half_f_tg30; // f/2 * tg 30 + y0 -= delta_effector_half_f_tg30; // shift center to edge + // z = a + b*y + float a = fast_flt_div2((x0 * x0 + y0 * y0 + z0 * z0 + rf * rf - re * re - y1 * y1)) / z0; + float b = (y1 - y0) / z0; + // discriminant + float d = -(a + b * y1) * (a + b * y1) + rf * (b * b * rf + rf); + if (d < 0) + { + *theta = NAN; + return -1; + } + // non-existing point + float yj = (y1 - a * b - sqrt(d)) / (b * b + 1); // choosing outer point + float zj = a + b * yj; + // original code + // *theta = 180.0f * atan(-zj / (y1 - yj)) * M_PI_INV + ((yj > y1) ? 180.0f : 0); + *theta = 180.0f * atan2(-zj, (y1 - yj)) * M_PI_INV; + return 0; } void kinematics_apply_inverse(float *axis, int32_t *steps) { - float x = axis[AXIS_X] - delta_x[0]; - float y = axis[AXIS_Y] - delta_y[0]; - float z = axis[AXIS_Z] - delta_base_height; - float steps_mm = sqrt(delta_arm_sqr - (x * x) - (y * y)) + z; - steps[0] = (int32_t)lroundf(g_settings.step_per_mm[0] * steps_mm); - x = delta_x[1] - axis[AXIS_X]; - y = delta_y[1] - axis[AXIS_Y]; - steps_mm = sqrt(delta_arm_sqr - (x * x) - (y * y)) + z; - steps[1] = (int32_t)lroundf(g_settings.step_per_mm[1] * steps_mm); - x = delta_x[2] - axis[AXIS_X]; - y = delta_y[2] - axis[AXIS_Y]; - steps_mm = sqrt(delta_arm_sqr - (x * x) - (y * y)) + z; - steps[2] = (int32_t)lroundf(g_settings.step_per_mm[2] * steps_mm); + float theta1, theta2, theta3; + float z_offset = axis[AXIS_Z] + delta_cuboid_z_home; #if AXIS_COUNT > 3 for (uint8_t i = 3; i < AXIS_COUNT; i++) { steps[i] = (int32_t)lroundf(g_settings.step_mm[i] * axis[i]); } #endif + + if (!delta_calcAngleYZ(axis[AXIS_X], axis[AXIS_Y], z_offset, &theta1)) + { + if (!delta_calcAngleYZ(axis[AXIS_X] * COS120 + axis[AXIS_Y] * SIN120, axis[AXIS_Y] * COS120 - axis[AXIS_X] * SIN120, z_offset, &theta2)) + { + if (!delta_calcAngleYZ(axis[AXIS_X] * COS120 - axis[AXIS_Y] * SIN120, axis[AXIS_Y] * COS120 + axis[AXIS_X] * SIN120, z_offset, &theta3)) + { + // converts angle to steps + steps[0] = steps_per_angle[0] * theta1; + steps[1] = steps_per_angle[1] * theta2; + steps[2] = steps_per_angle[2] * theta3; + return; + } + } + } + + steps[0] = INT32_MAX; + steps[1] = INT32_MAX; + steps[2] = INT32_MAX; } void kinematics_apply_forward(int32_t *steps, float *axis) { - // using trialteration (similar to marlin) - float z0 = (steps[0] / g_settings.step_per_mm[0]); - float z1 = (steps[1] / g_settings.step_per_mm[1]); - float z2 = (steps[2] / g_settings.step_per_mm[2]); - float p01[3] = {delta_x[1] - delta_x[0], delta_y[1] - delta_y[0], z1 - z0}; - - // Get the reciprocal of Magnitude of vector. - float d2 = (p01[0] * p01[0]) + (p01[1] * p01[1]) + (p01[2] * p01[2]); - float inv_d = 1.0f / sqrtf(d2); - - // Create unit vector by multiplying by the inverse of the magnitude. - float ex[3] = {p01[0] * inv_d, p01[1] * inv_d, p01[2] * inv_d}; - - // Get the vector from the origin of the new system to the third point. - float p02[3] = {delta_x[2] - delta_x[0], delta_y[2] - delta_y[0], z2 - z0}; - - // Use the dot product to find the component of this vector on the X axis. - float i = ex[0] * p02[0] + ex[1] * p02[1] + ex[2] * p02[2]; - - // Create a vector along the x axis that represents the x component of p02. - float 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] = {p02[0] - iex[0], p02[1] - iex[1], p02[2] - iex[2]}; - - // The magnitude and the inverse of the magnitude of Y component - float j2 = (ey[0] * ey[0]) + (ey[1] * ey[1]) + (ey[2] * ey[2]); - float inv_j = 1.0f / sqrtf(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); - 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 - float Xnew = d2 * inv_d * 0.5; - float Ynew = ((i * i + j2) * 0.5 - i * Xnew) * inv_j; - float Znew = sqrtf(delta_arm_sqr - (Xnew * Xnew + Ynew * 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. - axis[0] = delta_x[0] + ex[0] * Xnew + ey[0] * Ynew - ez[0] * Znew; - axis[1] = delta_y[0] + ex[1] * Xnew + ey[1] * Ynew - ez[1] * Znew; - axis[2] = z0 + ex[2] * Xnew + ey[2] * Ynew - ez[2] * Znew + delta_base_height; + float rf = g_settings.delta_bicep_length; + float re = g_settings.delta_forearm_length; + + float t = delta_base_effector_half_f_tg30; + // float dtr = pi / (float)180.0; + + float theta1 = (float)steps[0] * DEG_RAD_MULT / steps_per_angle[0]; + float theta2 = (float)steps[1] * DEG_RAD_MULT / steps_per_angle[1]; + float theta3 = (float)steps[2] * DEG_RAD_MULT / steps_per_angle[2]; + + float y1 = -(t + rf * cos(theta1)); + float z1 = -rf * sin(theta1); + + float y2 = (t + rf * cos(theta2)) * SIN30; + float x2 = y2 * TAN60; + float z2 = -rf * sin(theta2); + + float y3 = (t + rf * cos(theta3)) * SIN30; + float x3 = -y3 * TAN60; + float z3 = -rf * sin(theta3); + + float dnm = (y2 - y1) * x3 - (y3 - y1) * x2; + + float w1 = y1 * y1 + z1 * z1; + float w2 = x2 * x2 + y2 * y2 + z2 * z2; + float w3 = x3 * x3 + y3 * y3 + z3 * z3; + + // x = (a1*z + b1)/dnm + float a1 = (z2 - z1) * (y3 - y1) - (z3 - z1) * (y2 - y1); + float b1 = -fast_flt_div2((w2 - w1) * (y3 - y1) - (w3 - w1) * (y2 - y1)); + + // y = (a2*z + b2)/dnm; + float a2 = -(z2 - z1) * x3 + (z3 - z1) * x2; + float b2 = fast_flt_div2((w2 - w1) * x3 - (w3 - w1) * x2); + + // a*z^2 + b*z + c = 0 + float a = a1 * a1 + a2 * a2 + dnm * dnm; + float b = fast_flt_mul2((a1 * b1 + a2 * (b2 - y1 * dnm) - z1 * dnm * dnm)); + float c = (b2 - y1 * dnm) * (b2 - y1 * dnm) + b1 * b1 + dnm * dnm * (z1 * z1 - re * re); + + // discriminant + float d = b * b - fast_flt_mul4((a * c)); + if (d < 0) + { + // return NaN + axis[AXIS_X] = NAN; + axis[AXIS_Y] = NAN; + axis[AXIS_Z] = NAN; + return; // non-existing point + } + + float z0 = -fast_flt_div2((b + sqrt(d))) / a; + axis[AXIS_X] = (a1 * z0 + b1) / dnm; + axis[AXIS_Y] = (a2 * z0 + b2) / dnm; + axis[AXIS_Z] = z0 - delta_cuboid_z_home; #if AXIS_COUNT > 3 for (uint8_t i = 3; i < AXIS_COUNT; i++) @@ -145,6 +323,17 @@ void kinematics_apply_forward(int32_t *steps, float *axis) uint8_t kinematics_home(void) { + // delta starts by invalidating the current position and considers it's at the far end of the homing position + float axis[AXIS_COUNT]; + // reset home offset + delta_cuboid_z_home = 0; + // reset coordinates + memset(axis, 0, sizeof(axis)); + // set z axis at the far end from the + axis[AXIS_Z] = ((g_settings.homing_dir_invert_mask & (1 << AXIS_Z)) ? delta_cuboid_z_min : delta_cuboid_z_max); + // sync interpolator to new position (motion homing syncs remaining systems) + itp_reset_rt_position(axis); + if (mc_home_axis(AXIS_Z, LIMITS_DELTA_MASK)) { return KINEMATIC_HOMING_ERROR_Z; @@ -154,7 +343,7 @@ uint8_t kinematics_home(void) #if (defined(AXIS_A) && !(LIMIT_A < 0)) if (mc_home_axis(AXIS_A, LIMIT_A_MASK)) { - return (KINEMATIC_HOMING_ERROR_X|KINEMATIC_HOMING_ERROR_Y|KINEMATIC_HOMING_ERROR_Z); + return (KINEMATIC_HOMING_ERROR_X | KINEMATIC_HOMING_ERROR_Y | KINEMATIC_HOMING_ERROR_Z); } #endif #endif @@ -182,7 +371,13 @@ uint8_t kinematics_home(void) cnc_set_exec_state(EXEC_HOMING); float target[AXIS_COUNT]; motion_data_t block_data = {0}; - mc_get_position(target); + + int32_t angle_steps[AXIS_COUNT]; + delta_home_angle_to_steps(angle_steps); + kinematics_apply_forward(angle_steps, target); + // sync systems (interpolator, motion control and parser - the latest is synched ny motion control) + itp_reset_rt_position(target); + mc_sync_position(); // pull of only on the Z axis target[AXIS_Z] += ((g_settings.homing_dir_invert_mask & (1 << AXIS_Z)) ? -g_settings.homing_offset : g_settings.homing_offset); @@ -194,18 +389,19 @@ uint8_t kinematics_home(void) mc_line(target, &block_data); itp_sync(); - cnc_clear_exec_state(EXEC_HOMING); - - memset(target, 0, sizeof(target)); -#ifndef SET_ORIGIN_AT_HOME_POS - if (g_settings.homing_dir_invert_mask & (1 << AXIS_Z)) - { - target[AXIS_Z] = g_settings.max_distance[AXIS_Z]; - } +// add the internal offset to the kinematics +#ifdef SET_ORIGIN_AT_HOME_POS + delta_cuboid_z_home = target[AXIS_Z]; +#else + delta_cuboid_z_home = delta_cuboid_z_min; #endif - // reset position + // sync systems again to the origin (interpolator, motion control and parser - the latest is synched ny motion control) + memset(target, 0, sizeof(target)); itp_reset_rt_position(target); + mc_sync_position(); + + cnc_clear_exec_state(EXEC_HOMING); return STATUS_OK; } @@ -222,30 +418,38 @@ bool kinematics_check_boundaries(float *axis) { if (!g_settings.soft_limits_enabled || cnc_get_exec_state(EXEC_HOMING)) { + // modifies the homing seek position to not exceed the maximum distance that the maxine can run + if (cnc_get_exec_state(EXEC_HOMING)) + { + if (g_settings.homing_dir_invert_mask & (1 << AXIS_Z)) + { + axis[AXIS_Z] = MIN(axis[AXIS_Z], delta_cuboid_z_max); + } + else + { + axis[AXIS_Z] = MAX(axis[AXIS_Z], delta_cuboid_z_min); + } + } return true; } - if (axis[AXIS_X] < -delta_base_max_travel || axis[AXIS_X] > delta_base_max_travel) - { - return false; - } + float xy_limit = delta_cuboid_xy; + float z_offset = delta_cuboid_z_home; - if (axis[AXIS_Y] < -delta_base_max_travel || axis[AXIS_Y] > delta_base_max_travel) + if (axis[AXIS_X] < -xy_limit || axis[AXIS_X] > xy_limit) { return false; } -#ifdef SET_ORIGIN_AT_HOME_POS - if (axis[AXIS_Z] < -g_settings.max_distance[AXIS_Z] || axis[AXIS_Z] > 0) + if (axis[AXIS_Y] < -xy_limit || axis[AXIS_Y] > xy_limit) { return false; } -#else - if (axis[AXIS_Z] > g_settings.max_distance[AXIS_Z] || axis[AXIS_Z] < 0) + + if (axis[AXIS_Z] < (delta_cuboid_z_min - z_offset) || axis[AXIS_Z] > (delta_cuboid_z_max - z_offset)) { return false; } -#endif return true; } diff --git a/uCNC/src/hal/kinematics/kinematic_delta.h b/uCNC/src/hal/kinematics/kinematic_delta.h index f31171b7c..1b3abe316 100644 --- a/uCNC/src/hal/kinematics/kinematic_delta.h +++ b/uCNC/src/hal/kinematics/kinematic_delta.h @@ -4,7 +4,7 @@ Copyright: Copyright (c) João Martins Author: João Martins - Date: 06/02/2020 + Date: 03/11/2022 µCNC is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by @@ -24,37 +24,24 @@ extern "C" { #endif +#define KINEMATIC_TYPE_STR "D" + #if AXIS_COUNT < 3 #error "Delta kinematics expects at least 3 axis" #endif -#ifndef STEPPER0_ANGLE -#define STEPPER0_ANGLE 30 -#endif -#ifndef STEPPER1_ANGLE -#define STEPPER1_ANGLE (STEPPER0_ANGLE + 120) -#endif -#ifndef STEPPER2_ANGLE -#define STEPPER2_ANGLE (STEPPER0_ANGLE + 240) -#endif +// kinematic motion is done by segments to cope with non linear kinematics motion +#define KINEMATICS_MOTION_BY_SEGMENTS +// kinematics homing +#define IS_DELTA_KINEMATICS // the maximum size of the computed segments that are sent to the planner // this forces linear motions in the delta to treated has an arc motion to // cope with the non linear kinematic motion of the towers -#ifndef DELTA_MOTION_SEGMENT_SIZE -#define DELTA_MOTION_SEGMENT_SIZE 1.0f +#ifndef KINEMATICS_MOTION_SEGMENT_SIZE +#define KINEMATICS_MOTION_SEGMENT_SIZE 1.0f #endif -#define DELTA_MOTION_SEGMENT_FACTOR (1.0f / DELTA_MOTION_SEGMENT_SIZE) -// minimum arm angle that is allowed for the delta (for software limits) -#ifndef DELTA_ARM_MIN_ANGLE -#define DELTA_ARM_MIN_ANGLE 20 -#endif - -// maximum angle (should not be bigger then 90º deg angle) -#ifndef DELTA_ARM_MAX_ANGLE -#define DELTA_ARM_MAX_ANGLE 89 -#endif /* Enable Skew compensation diff --git a/uCNC/src/hal/kinematics/kinematic_linear_delta.c b/uCNC/src/hal/kinematics/kinematic_linear_delta.c new file mode 100644 index 000000000..431bb0ae2 --- /dev/null +++ b/uCNC/src/hal/kinematics/kinematic_linear_delta.c @@ -0,0 +1,253 @@ +/* + Name: kinematic_linear_delta.c + Description: Implements all kinematics math equations to translate the motion of a delta machine. + Also implements the homing motion for this type of machine. + + Copyright: Copyright (c) João Martins + Author: João Martins + Date: 19/01/2022 + + µCNC 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. Please see + + µCNC is distributed WITHOUT ANY WARRANTY; + Also without the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU General Public License for more details. +*/ + +#include "../../cnc.h" + +#if (KINEMATIC == KINEMATIC_LINEAR_DELTA) +#include +#include + +#define STEPPER0_FACTX (cos(STEPPER0_ANGLE * DEG_RAD_MULT)); +#define STEPPER0_FACTY (sin(STEPPER0_ANGLE * DEG_RAD_MULT)); +#define STEPPER1_FACTX (cos(STEPPER1_ANGLE * DEG_RAD_MULT)); +#define STEPPER1_FACTY (sin(STEPPER1_ANGLE * DEG_RAD_MULT)); +#define STEPPER2_FACTX (cos(STEPPER2_ANGLE * DEG_RAD_MULT)); +#define STEPPER2_FACTY (sin(STEPPER2_ANGLE * DEG_RAD_MULT)); + +static float delta_arm_sqr; +static float delta_base_height; +static float delta_base_max_travel; +static float delta_x[3]; +static float delta_y[3]; + +void kinematics_init(void) +{ + float delta_triang_base = g_settings.delta_armbase_radius; + delta_arm_sqr = g_settings.delta_arm_length * g_settings.delta_arm_length; + delta_x[0] = delta_triang_base * STEPPER0_FACTX; + delta_x[1] = delta_triang_base * STEPPER1_FACTX; + delta_x[2] = delta_triang_base * STEPPER2_FACTX; + delta_y[0] = delta_triang_base * STEPPER0_FACTY; + delta_y[1] = delta_triang_base * STEPPER1_FACTY; + delta_y[2] = delta_triang_base * STEPPER2_FACTY; + delta_base_height = sqrtf(delta_arm_sqr - delta_x[0] * delta_x[0] - delta_y[0] * delta_y[0]); + float min_travel = (g_settings.delta_arm_length * cos(DELTA_ARM_MIN_ANGLE * DEG_RAD_MULT)) - delta_triang_base; + float max_travel = (g_settings.delta_arm_length * cos(DELTA_ARM_MAX_ANGLE * DEG_RAD_MULT)) - delta_triang_base; + min_travel = ABS(min_travel); + max_travel = ABS(max_travel); + delta_base_max_travel = MIN(min_travel, max_travel); +} + +void kinematics_apply_inverse(float *axis, int32_t *steps) +{ + float x = axis[AXIS_X] - delta_x[0]; + float y = axis[AXIS_Y] - delta_y[0]; + float z = axis[AXIS_Z] - delta_base_height; + float steps_mm = sqrt(delta_arm_sqr - (x * x) - (y * y)) + z; + steps[0] = (int32_t)lroundf(g_settings.step_per_mm[0] * steps_mm); + x = delta_x[1] - axis[AXIS_X]; + y = delta_y[1] - axis[AXIS_Y]; + steps_mm = sqrt(delta_arm_sqr - (x * x) - (y * y)) + z; + steps[1] = (int32_t)lroundf(g_settings.step_per_mm[1] * steps_mm); + x = delta_x[2] - axis[AXIS_X]; + y = delta_y[2] - axis[AXIS_Y]; + steps_mm = sqrt(delta_arm_sqr - (x * x) - (y * y)) + z; + steps[2] = (int32_t)lroundf(g_settings.step_per_mm[2] * steps_mm); + +#if AXIS_COUNT > 3 + for (uint8_t i = 3; i < AXIS_COUNT; i++) + { + steps[i] = (int32_t)lroundf(g_settings.step_mm[i] * axis[i]); + } +#endif +} + +void kinematics_apply_forward(int32_t *steps, float *axis) +{ + // using trialteration (similar to marlin) + float z0 = (steps[0] / g_settings.step_per_mm[0]); + float z1 = (steps[1] / g_settings.step_per_mm[1]); + float z2 = (steps[2] / g_settings.step_per_mm[2]); + float p01[3] = {delta_x[1] - delta_x[0], delta_y[1] - delta_y[0], z1 - z0}; + + // Get the reciprocal of Magnitude of vector. + float d2 = (p01[0] * p01[0]) + (p01[1] * p01[1]) + (p01[2] * p01[2]); + float inv_d = 1.0f / sqrtf(d2); + + // Create unit vector by multiplying by the inverse of the magnitude. + float ex[3] = {p01[0] * inv_d, p01[1] * inv_d, p01[2] * inv_d}; + + // Get the vector from the origin of the new system to the third point. + float p02[3] = {delta_x[2] - delta_x[0], delta_y[2] - delta_y[0], z2 - z0}; + + // Use the dot product to find the component of this vector on the X axis. + float i = ex[0] * p02[0] + ex[1] * p02[1] + ex[2] * p02[2]; + + // Create a vector along the x axis that represents the x component of p02. + float 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] = {p02[0] - iex[0], p02[1] - iex[1], p02[2] - iex[2]}; + + // The magnitude and the inverse of the magnitude of Y component + float j2 = (ey[0] * ey[0]) + (ey[1] * ey[1]) + (ey[2] * ey[2]); + float inv_j = 1.0f / sqrtf(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); + 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 + float Xnew = d2 * inv_d * 0.5; + float Ynew = ((i * i + j2) * 0.5 - i * Xnew) * inv_j; + float Znew = sqrtf(delta_arm_sqr - (Xnew * Xnew + Ynew * 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. + axis[0] = delta_x[0] + ex[0] * Xnew + ey[0] * Ynew - ez[0] * Znew; + axis[1] = delta_y[0] + ex[1] * Xnew + ey[1] * Ynew - ez[1] * Znew; + axis[2] = z0 + ex[2] * Xnew + ey[2] * Ynew - ez[2] * Znew + delta_base_height; + +#if AXIS_COUNT > 3 + for (uint8_t i = 3; i < AXIS_COUNT; i++) + { + axis[i] = (((float)steps[i]) / g_settings.step_per_mm[i]); + } +#endif +} + +uint8_t kinematics_home(void) +{ + if (mc_home_axis(AXIS_Z, LIMITS_DELTA_MASK)) + { + return KINEMATIC_HOMING_ERROR_Z; + } + +#ifndef DISABLE_A_HOMING +#if (defined(AXIS_A) && !(LIMIT_A < 0)) + if (mc_home_axis(AXIS_A, LIMIT_A_MASK)) + { + return (KINEMATIC_HOMING_ERROR_X|KINEMATIC_HOMING_ERROR_Y|KINEMATIC_HOMING_ERROR_Z); + } +#endif +#endif + +#ifndef DISABLE_B_HOMING +#if (defined(AXIS_B) && !(LIMIT_B < 0)) + if (mc_home_axis(AXIS_B, LIMIT_B_MASK)) + { + return KINEMATIC_HOMING_ERROR_B; + } +#endif +#endif + +#ifndef DISABLE_C_HOMING +#if (defined(AXIS_C) && !(LIMIT_C < 0)) + if (mc_home_axis(AXIS_C, LIMIT_C_MASK)) + { + return KINEMATIC_HOMING_ERROR_C; + } +#endif +#endif + + // unlocks the machine to go to offset + cnc_unlock(true); + cnc_set_exec_state(EXEC_HOMING); + float target[AXIS_COUNT]; + motion_data_t block_data = {0}; + mc_get_position(target); + + // pull of only on the Z axis + target[AXIS_Z] += ((g_settings.homing_dir_invert_mask & (1 << AXIS_Z)) ? -g_settings.homing_offset : g_settings.homing_offset); + + block_data.feed = g_settings.homing_fast_feed_rate; + block_data.spindle = 0; + block_data.dwell = 0; + // starts offset and waits to finnish + mc_line(target, &block_data); + itp_sync(); + + cnc_clear_exec_state(EXEC_HOMING); + + memset(target, 0, sizeof(target)); +#ifndef SET_ORIGIN_AT_HOME_POS + if (g_settings.homing_dir_invert_mask & (1 << AXIS_Z)) + { + target[AXIS_Z] = g_settings.max_distance[AXIS_Z]; + } +#endif + + // reset position + itp_reset_rt_position(target); + + return STATUS_OK; +} + +void kinematics_apply_transform(float *axis) +{ +} + +void kinematics_apply_reverse_transform(float *axis) +{ +} + +bool kinematics_check_boundaries(float *axis) +{ + if (!g_settings.soft_limits_enabled || cnc_get_exec_state(EXEC_HOMING)) + { + return true; + } + + if (axis[AXIS_X] < -delta_base_max_travel || axis[AXIS_X] > delta_base_max_travel) + { + return false; + } + + if (axis[AXIS_Y] < -delta_base_max_travel || axis[AXIS_Y] > delta_base_max_travel) + { + return false; + } + +#ifdef SET_ORIGIN_AT_HOME_POS + if (axis[AXIS_Z] < -g_settings.max_distance[AXIS_Z] || axis[AXIS_Z] > 0) + { + return false; + } +#else + if (axis[AXIS_Z] > g_settings.max_distance[AXIS_Z] || axis[AXIS_Z] < 0) + { + return false; + } +#endif + + return true; +} + +#endif diff --git a/uCNC/src/hal/kinematics/kinematic_linear_delta.h b/uCNC/src/hal/kinematics/kinematic_linear_delta.h new file mode 100644 index 000000000..27f1a2a95 --- /dev/null +++ b/uCNC/src/hal/kinematics/kinematic_linear_delta.h @@ -0,0 +1,73 @@ +/* + Name: kinematic_linear_delta.h + Description: Custom kinematics definitions for delta machine + + Copyright: Copyright (c) João Martins + Author: João Martins + Date: 06/02/2020 + + µCNC 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. Please see + + µCNC is distributed WITHOUT ANY WARRANTY; + Also without the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU General Public License for more details. +*/ + +#ifndef KINEMATIC_LINEAR_DELTA_H +#define KINEMATIC_LINEAR_DELTA_H + +#ifdef __cplusplus +extern "C" +{ +#endif + +#define KINEMATIC_TYPE_STR "LD" + +#if AXIS_COUNT < 3 +#error "Linear delta kinematics expects at least 3 axis" +#endif + +#ifndef STEPPER0_ANGLE +#define STEPPER0_ANGLE 30 +#endif +#ifndef STEPPER1_ANGLE +#define STEPPER1_ANGLE (STEPPER0_ANGLE + 120) +#endif +#ifndef STEPPER2_ANGLE +#define STEPPER2_ANGLE (STEPPER0_ANGLE + 240) +#endif + +// kinematic motion is done by segments to cope with non linear kinematics motion +#define KINEMATICS_MOTION_BY_SEGMENTS +// kinematics homing +#define IS_DELTA_KINEMATICS + +// the maximum size of the computed segments that are sent to the planner +// this forces linear motions in the delta to treated has an arc motion to +// cope with the non linear kinematic motion of the towers +#ifndef KINEMATICS_MOTION_SEGMENT_SIZE +#define KINEMATICS_MOTION_SEGMENT_SIZE 1.0f +#endif + +// minimum arm angle that is allowed for the delta (for software limits) +#ifndef DELTA_ARM_MIN_ANGLE +#define DELTA_ARM_MIN_ANGLE 20 +#endif + +// maximum angle (should not be bigger then 90º deg angle) +#ifndef DELTA_ARM_MAX_ANGLE +#define DELTA_ARM_MAX_ANGLE 89 +#endif + + /* + Enable Skew compensation +*/ + //#define ENABLE_SKEW_COMPENSATION + +#ifdef __cplusplus +} +#endif +#endif diff --git a/uCNC/src/hal/kinematics/kinematicdefs.h b/uCNC/src/hal/kinematics/kinematicdefs.h index d5d3bbe44..a6c642a5a 100644 --- a/uCNC/src/hal/kinematics/kinematicdefs.h +++ b/uCNC/src/hal/kinematics/kinematicdefs.h @@ -61,6 +61,8 @@ extern "C" #include "kinematic_cartesian.h" #elif (KINEMATIC == KINEMATIC_COREXY) #include "kinematic_corexy.h" +#elif (KINEMATIC == KINEMATIC_LINEAR_DELTA) +#include "kinematic_linear_delta.h" #elif (KINEMATIC == KINEMATIC_DELTA) #include "kinematic_delta.h" #else diff --git a/uCNC/src/hal/kinematics/kinematics.h b/uCNC/src/hal/kinematics/kinematics.h index 5bc9e1db0..cfe8e7f71 100644 --- a/uCNC/src/hal/kinematics/kinematics.h +++ b/uCNC/src/hal/kinematics/kinematics.h @@ -26,7 +26,8 @@ extern "C" #define KINEMATIC_CARTESIAN 1 #define KINEMATIC_COREXY 2 -#define KINEMATIC_DELTA 3 +#define KINEMATIC_LINEAR_DELTA 3 +#define KINEMATIC_DELTA 4 #ifdef __cplusplus } diff --git a/uCNC/src/hal/mcus/virtual/mcumap_virtual.h b/uCNC/src/hal/mcus/virtual/mcumap_virtual.h index 8dbe91e2e..0e4e6743e 100644 --- a/uCNC/src/hal/mcus/virtual/mcumap_virtual.h +++ b/uCNC/src/hal/mcus/virtual/mcumap_virtual.h @@ -205,6 +205,7 @@ #define mcu_nop() #define mcu_config_pullup(diopin) #define mcu_config_analog(diopin) +#define asm __asm__ #define mcu_delay_cycles(X) extern void virtual_delay_us(uint16_t delay); diff --git a/uCNC/src/hal/tools/tools/laser.c b/uCNC/src/hal/tools/tools/laser.c index f9326c7d3..b12fb1423 100644 --- a/uCNC/src/hal/tools/tools/laser.c +++ b/uCNC/src/hal/tools/tools/laser.c @@ -103,7 +103,7 @@ uint16_t laser_get_speed(void) { #if !(LASER_PWM < 0) float laser = (float)mcu_get_pwm(LASER_PWM) * g_settings.spindle_max_rpm * UINT8_MAX_INV; - return (uint16_t)roundf(laser); + return (uint16_t)lroundf(laser); #else return 0; #endif diff --git a/uCNC/src/hal/tools/tools/spindle_pwm.c b/uCNC/src/hal/tools/tools/spindle_pwm.c index d9390eb0c..4d6726649 100644 --- a/uCNC/src/hal/tools/tools/spindle_pwm.c +++ b/uCNC/src/hal/tools/tools/spindle_pwm.c @@ -98,7 +98,7 @@ uint16_t spindle_pwm_get_speed(void) { #if SPINDLE_PWM >= 0 float spindle = (float)mcu_get_pwm(SPINDLE_PWM) * g_settings.spindle_max_rpm * UINT8_MAX_INV; - return (uint16_t)roundf(spindle); + return (uint16_t)lroundf(spindle); #else return 0; #endif diff --git a/uCNC/src/hal/tools/tools/vfd.c b/uCNC/src/hal/tools/tools/vfd.c index 03fed7cb1..413454723 100644 --- a/uCNC/src/hal/tools/tools/vfd.c +++ b/uCNC/src/hal/tools/tools/vfd.c @@ -83,7 +83,7 @@ static vfd_state_t vfd_state; #define VFD_MAX_COMMAND_RETRIES 2 // uncomment the right type of VFD used -// #define VFD_HUANYANG_TYPE1 + #define VFD_HUANYANG_TYPE1 // #define VFD_HUANYANG_TYPE2 // #define VFD_YL620 // #define VFD_POWTRAN8100 @@ -306,7 +306,7 @@ static bool vfd_update_rpm(void) { modbus_response_t response = {0}; uint8_t cmd[7] = VFD_SETRPM_CMD; - uint16_t hz = (uint16_t)roundf((float)ABS(vfd_state.rpm) * VFD_OUT_MULT / VFD_OUT_DIV); + uint16_t hz = (uint16_t)lroundf((float)ABS(vfd_state.rpm) * VFD_OUT_MULT / VFD_OUT_DIV); // cmd starts at index 1 not at 0 uint8_t i = cmd[0] - 4 + 1; cmd[i] = (uint8_t)(hz >> 8); diff --git a/uCNC/src/interface/defaults.h b/uCNC/src/interface/defaults.h index 590fcdbc7..271d3d10d 100644 --- a/uCNC/src/interface/defaults.h +++ b/uCNC/src/interface/defaults.h @@ -65,8 +65,14 @@ extern "C" #define DEFAULT_DEBOUNCE_MS 250 -#define DEFAULT_DELTA_ARM_LENGTH 230 -#define DEFAULT_DELTA_BASE_RADIUS 115 +#define DEFAULT_LIN_DELTA_ARM_LENGTH 230 +#define DEFAULT_LIN_DELTA_BASE_RADIUS 115 + +#define DEFAULT_DELTA_BICEP_LENGTH 100 +#define DEFAULT_DELTA_FOREARM_LENGTH 300 +#define DEFAULT_DELTA_EFFECTOR_RADIUS 24 +#define DEFAULT_DELTA_BASE_RADIUS 75 +#define DEFAULT_DELTA_BICEP_HOMING_ANGLE 0 #define DEFAULT_LASER_PPI 254 #define DEFAULT_LASER_PPI_USWIDTH 1500 diff --git a/uCNC/src/interface/protocol.c b/uCNC/src/interface/protocol.c index 146c5a644..6ffbe30b4 100644 --- a/uCNC/src/interface/protocol.c +++ b/uCNC/src/interface/protocol.c @@ -609,6 +609,9 @@ void protocol_send_cnc_settings(void) protocol_send_gcode_setting_line_flt(25, g_settings.homing_fast_feed_rate); protocol_send_gcode_setting_line_int(26, g_settings.debounce_ms); protocol_send_gcode_setting_line_flt(27, g_settings.homing_offset); +#if (KINEMATIC == KINEMATIC_DELTA) + protocol_send_gcode_setting_line_flt(28, g_settings.delta_bicep_homing_angle); +#endif protocol_send_gcode_setting_line_int(30, g_settings.spindle_max_rpm); protocol_send_gcode_setting_line_int(31, g_settings.spindle_min_rpm); protocol_send_gcode_setting_line_int(32, g_settings.laser_mode); @@ -648,10 +651,15 @@ void protocol_send_cnc_settings(void) protocol_send_gcode_setting_line_flt(100 + i, g_settings.step_per_mm[i]); } -#if (KINEMATIC == KINEMATIC_DELTA) +#if (KINEMATIC == KINEMATIC_LINEAR_DELTA) protocol_send_gcode_setting_line_flt(106, g_settings.delta_arm_length); protocol_send_gcode_setting_line_flt(107, g_settings.delta_armbase_radius); // protocol_send_gcode_setting_line_int(108, g_settings.delta_efector_height); +#elif (KINEMATIC == KINEMATIC_DELTA) + protocol_send_gcode_setting_line_flt(106, g_settings.delta_base_radius); + protocol_send_gcode_setting_line_flt(107, g_settings.delta_effector_radius); + protocol_send_gcode_setting_line_flt(108, g_settings.delta_bicep_length); + protocol_send_gcode_setting_line_flt(109, g_settings.delta_forearm_length); #endif for (uint8_t i = 0; i < AXIS_COUNT; i++) @@ -767,15 +775,10 @@ void protocol_send_pins_states(void) #endif #ifdef ENABLE_SYSTEM_INFO -#if (KINEMATIC == KINEMATIC_CARTESIAN) -#define KINEMATIC_INFO "C" STRGIFY(AXIS_COUNT) "," -#elif (KINEMATIC == KINEMATIC_COREXY) -#define KINEMATIC_INFO "XY" STRGIFY(AXIS_COUNT) "," -#elif (KINEMATIC == KINEMATIC_DELTA) -#define KINEMATIC_INFO "D" STRGIFY(AXIS_COUNT) "," -#else -#define KINEMATIC_INFO "" +#ifndef KINEMATIC_TYPE_STR +#define KINEMATIC_TYPE_STR "UK" /*undefined kynematic*/ #endif +#define KINEMATIC_INFO KINEMATIC_TYPE_STR STRGIFY(AXIS_COUNT) "," #define TOOLS_INFO "T" STRGIFY(TOOL_COUNT) "," #ifdef GCODE_PROCESS_LINE_NUMBERS @@ -876,7 +879,7 @@ void protocol_send_pins_states(void) WEAK_EVENT_HANDLER(protocol_send_cnc_info) { - //custom handler + // custom handler protocol_send_cnc_info_delegate_event_t *ptr = protocol_send_cnc_info_event; while (ptr != NULL) { diff --git a/uCNC/src/interface/serial.c b/uCNC/src/interface/serial.c index 89e06a277..57655984d 100644 --- a/uCNC/src/interface/serial.c +++ b/uCNC/src/interface/serial.c @@ -278,7 +278,7 @@ void serial_print_flt(float num) num -= interger; uint32_t mult = (!g_settings.report_inches) ? 1000 : 10000; num *= mult; - uint32_t digits = (uint32_t)roundf(num); + uint32_t digits = (uint32_t)lroundf(num); if (digits == mult) { interger++; diff --git a/uCNC/src/interface/settings.c b/uCNC/src/interface/settings.c index 00acdaa9b..414a2b0b4 100644 --- a/uCNC/src/interface/settings.c +++ b/uCNC/src/interface/settings.c @@ -122,10 +122,16 @@ const settings_t __rom__ default_settings = .default_tool = DEFAULT_STARTUP_TOOL, .tool_length_offset = DEFAULT_ARRAY(TOOL_COUNT, 0), #endif -#if (KINEMATIC == KINEMATIC_DELTA) - .delta_arm_length = DEFAULT_DELTA_ARM_LENGTH, - .delta_armbase_radius = DEFAULT_DELTA_BASE_RADIUS, +#if (KINEMATIC == KINEMATIC_LINEAR_DELTA) + .delta_arm_length = DEFAULT_LIN_DELTA_ARM_LENGTH, + .delta_armbase_radius = DEFAULT_LIN_DELTA_BASE_RADIUS, // float delta_efector_height; +#elif (KINEMATIC == KINEMATIC_DELTA) + .delta_base_radius = DEFAULT_DELTA_BASE_RADIUS, + .delta_effector_radius = DEFAULT_DELTA_EFFECTOR_RADIUS, + .delta_bicep_length = DEFAULT_DELTA_BICEP_LENGTH, + .delta_forearm_length = DEFAULT_DELTA_FOREARM_LENGTH, + .delta_bicep_homing_angle = DEFAULT_DELTA_BICEP_HOMING_ANGLE, #endif #ifdef ENABLE_BACKLASH_COMPENSATION @@ -452,7 +458,7 @@ uint8_t settings_change(setting_offset_t id, float value) g_settings.default_tool = CLAMP(0, value8, (uint8_t)TOOL_COUNT); break; #endif -#if (KINEMATIC == KINEMATIC_DELTA) +#if (KINEMATIC == KINEMATIC_LINEAR_DELTA) case 106: g_settings.delta_arm_length = value; break; @@ -462,6 +468,22 @@ uint8_t settings_change(setting_offset_t id, float value) // case 108: // g_settings.delta_efector_height = value; // break; +#elif (KINEMATIC == KINEMATIC_DELTA) + case 106: + g_settings.delta_base_radius = value; + break; + case 107: + g_settings.delta_effector_radius = value; + break; + case 108: + g_settings.delta_bicep_length = value; + break; + case 109: + g_settings.delta_forearm_length = value; + break; + case 28: + g_settings.delta_bicep_homing_angle = value; + break; #endif default: if (setting >= 100 && setting < (100 + AXIS_COUNT)) diff --git a/uCNC/src/interface/settings.h b/uCNC/src/interface/settings.h index 6d5c7e999..7a345cc82 100644 --- a/uCNC/src/interface/settings.h +++ b/uCNC/src/interface/settings.h @@ -72,10 +72,16 @@ extern "C" uint8_t default_tool; float tool_length_offset[TOOL_COUNT]; #endif -#if (KINEMATIC == KINEMATIC_DELTA) +#if (KINEMATIC == KINEMATIC_LINEAR_DELTA) float delta_arm_length; float delta_armbase_radius; // float delta_efector_height; +#elif (KINEMATIC == KINEMATIC_DELTA) + float delta_base_radius; + float delta_effector_radius; + float delta_bicep_length; + float delta_forearm_length; + float delta_bicep_homing_angle; #endif #ifdef ENABLE_BACKLASH_COMPENSATION uint16_t backlash_steps[AXIS_TO_STEPPERS]; diff --git a/uCNC/src/modules/pid.c b/uCNC/src/modules/pid.c index 32febfdc3..8f9a68773 100644 --- a/uCNC/src/modules/pid.c +++ b/uCNC/src/modules/pid.c @@ -236,7 +236,7 @@ void FORCEINLINE pid_update(void) output += rateerror; } - pid_set_output(current_pid, (int16_t)roundf(output)); + pid_set_output(current_pid, (int16_t)lroundf(output)); } if (++pid_freqdiv[current_pid] >= pid_get_freqdiv(current_pid)) diff --git a/uCNC/src/utils.h b/uCNC/src/utils.h index 2d9ed102d..f4ae0ba1d 100644 --- a/uCNC/src/utils.h +++ b/uCNC/src/utils.h @@ -161,6 +161,9 @@ extern "C" #ifndef M_PI #define M_PI 3.1415926535897932385f #endif +#ifndef M_PI_INV +#define M_PI_INV 0.3183098861837906715f +#endif #ifndef M_COS_TAYLOR_1 #define M_COS_TAYLOR_1 0.1666666666666666667f #endif