diff --git a/CMakeLists.txt b/CMakeLists.txt index 8cd4153..d141dbd 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -3,6 +3,7 @@ add_library(grbl INTERFACE) target_sources(grbl INTERFACE ${CMAKE_CURRENT_LIST_DIR}/grbllib.c ${CMAKE_CURRENT_LIST_DIR}/coolant_control.c + ${CMAKE_CURRENT_LIST_DIR}/crossbar.c ${CMAKE_CURRENT_LIST_DIR}/nvs_buffer.c ${CMAKE_CURRENT_LIST_DIR}/gcode.c ${CMAKE_CURRENT_LIST_DIR}/machine_limits.c diff --git a/changelog.md b/changelog.md index 14c6fa8..8e57c3d 100644 --- a/changelog.md +++ b/changelog.md @@ -1,5 +1,31 @@ ## grblHAL changelog +Build 20230903 + +Core: + +* Changed handling of homing inputs from limit switches. Some drivers will now only disable hard limits (if enabled) for axes that are homing, this includes max/min limit switches. +If max limit switches are available for the board/configuration these will be picked for homing in the positive direction and min switches in the negative direction. +The "unused" limit switches may have hard limits still enabled - depending on the driver. +__NOTE:__ I plan to add full support for all drivers to keep hard limits enabled for limit switches that are not used for the running homing cycle, this may take some time though as the changes has to be verified. +__NOTE:__ !! This is a __potentiallly dangerous change___, be careful when homing the machine for the first time after installing/upgrading. + +* HAL entry points and core handlers/events has been added and some have changed signatures in order to better support kinematics implementations. + +* More work on delta kinematics: new and changed settings, some improved functionality. Still in progress. + +Drivers: + +* Most: updated for HAL/core event signature changes. + +* STM32F4xx: "hardened" Trinamic soft UART code to improve reliability. Added fans plugin. + +Plugins: + +* Motors: fixed bug that would cause a hard fault if the X driver is not configured as Trinamic when others are. Updated for core event signature change. + +--- + Build 20230825 Core: diff --git a/config.h b/config.h index 022d62b..ae8846e 100644 --- a/config.h +++ b/config.h @@ -137,9 +137,11 @@ Experimental - testing required and homing needs to be worked out. */ #if !defined DELTA_ROBOT || defined __DOXYGEN__ #define DELTA_ROBOT Off -#if !defined MINIMUM_FEED_RATE -#define MINIMUM_FEED_RATE 0.1f // (radians/min) #endif + +// Reduce minimum feedrate for delta robots +#if DELTA_ROBOT && !defined MINIMUM_FEED_RATE +#define MINIMUM_FEED_RATE 0.1f // (radians/min) #endif /*! \def POLAR_ROBOT diff --git a/core_handlers.h b/core_handlers.h index 12db0db..41a80b0 100644 --- a/core_handlers.h +++ b/core_handlers.h @@ -78,6 +78,8 @@ typedef struct { typedef bool (*enqueue_gcode_ptr)(char *data); typedef bool (*protocol_enqueue_realtime_command_ptr)(char c); +typedef bool (*travel_limits_ptr)(float *target, bool is_cartesian); +typedef bool (*home_machine_ptr)(axes_signals_t cycle, axes_signals_t auto_square); typedef void (*on_parser_init_ptr)(parser_state_t *gc_state); typedef void (*on_state_change_ptr)(sys_state_t state); @@ -91,6 +93,7 @@ typedef bool (*on_unknown_realtime_cmd_ptr)(char c); typedef void (*on_report_handlers_init_ptr)(void); typedef void (*on_report_options_ptr)(bool newopt); typedef void (*on_report_command_help_ptr)(void); +typedef const char *(*on_setting_get_description_ptr)(setting_id_t id); typedef void (*on_global_settings_restore_ptr)(void); typedef void (*on_realtime_report_ptr)(stream_write_ptr stream_write, report_tracking_flags_t report); typedef void (*on_unknown_feedback_message_ptr)(stream_write_ptr stream_write); @@ -112,6 +115,7 @@ typedef void (*on_gcode_message_ptr)(char *msg); typedef void (*on_rt_reports_added_ptr)(report_tracking_flags_t report); typedef void (*on_vfs_mount_ptr)(const char *path, const vfs_t *fs); typedef void (*on_vfs_unmount_ptr)(const char *path); +typedef const char *(*on_set_axis_setting_unit_ptr)(setting_id_t setting_id, uint_fast8_t axis_idx); typedef status_code_t (*on_file_open_ptr)(const char *fname, vfs_file_t *handle, bool stream); typedef status_code_t (*on_unknown_sys_command_ptr)(sys_state_t state, char *line); // return Status_Unhandled. typedef status_code_t (*on_user_command_ptr)(char *line); @@ -137,6 +141,7 @@ typedef struct { on_report_command_help_ptr on_report_command_help; on_rt_reports_added_ptr on_rt_reports_added; on_global_settings_restore_ptr on_global_settings_restore; + on_setting_get_description_ptr on_setting_get_description; on_get_alarms_ptr on_get_alarms; on_get_errors_ptr on_get_errors; on_get_settings_ptr on_get_settings; @@ -152,6 +157,7 @@ typedef struct { on_probe_fixture_ptr on_probe_fixture; on_probe_start_ptr on_probe_start; on_probe_completed_ptr on_probe_completed; + on_set_axis_setting_unit_ptr on_set_axis_setting_unit; on_gcode_message_ptr on_gcode_message; //!< Called on output of message parsed from gcode. NOTE: string pointed to is freed after this call. on_gcode_message_ptr on_gcode_comment; //!< Called when a plain gcode comment has been parsed. on_tool_selected_ptr on_tool_selected; //!< Called prior to executing M6 or after executing M61. @@ -166,6 +172,9 @@ typedef struct { on_vfs_unmount_ptr on_vfs_unmount; //!< Called when a file system is unmounted. on_file_open_ptr on_file_open; //!< Called when a file is opened for streaming. // core entry points - set up by core before driver_init() is called. + home_machine_ptr home_machine; + travel_limits_ptr check_travel_limits; + travel_limits_ptr apply_jog_limits; enqueue_gcode_ptr enqueue_gcode; enqueue_realtime_command_ptr enqueue_realtime_command; on_macro_execute_ptr on_macro_execute; diff --git a/crossbar.c b/crossbar.c new file mode 100644 index 0000000..92c9bd2 --- /dev/null +++ b/crossbar.c @@ -0,0 +1,129 @@ +/* + crossbar.h - signal crossbar functions + + Part of grblHAL + + Copyright (c) 2023 Terje Io + + 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 . +*/ + +#include "hal.h" + +static limit_signals_t home_source = {0}; + +axes_signals_t xbar_fn_to_axismask (pin_function_t fn) +{ + axes_signals_t mask = {0}; + + switch(fn) { + + case Input_LimitX: + case Input_LimitX_Max: + case Input_LimitX_2: + case Input_HomeX: + mask.x = On; + break; + + case Input_LimitY: + case Input_LimitY_Max: + case Input_LimitY_2: + case Input_HomeY: + mask.y = On; + break; + + case Input_LimitZ: + case Input_LimitZ_Max: + case Input_LimitZ_2: + case Input_HomeZ: + mask.z = On; + break; + +#if N_AXIS > 3 + case Input_LimitA: + case Input_LimitA_Max: + case Input_HomeA: + mask.a = On; + break; +#endif +#if N_AXIS > 4 + case Input_LimitB: + case Input_LimitB_Max: + case Input_HomeB: + mask.b = On; + break; +#endif +#if N_AXIS > 5 + case Input_LimitC: + case Input_LimitC_Max: + case Input_HomeC: + mask.c = On; + break; +#endif +#if N_AXIS > 6 + case Input_LimitU: + case Input_LimitU_Max: + case Input_HomeU: + mask.u = On; + break; +#endif +#if N_AXIS == 8 + case Input_LimitV: + case Input_LimitV_Max: + case Input_HomeV: + mask.v = On; + break; +#endif + + default: + break; + } + + return mask; +} + +// Sets limit signals used by homing when home signals are not available. +// For internal use, called by settings.c when homing direction mask is changed. +void xbar_set_homing_source (void) +{ + if(hal.home_cap.a.mask == 0) { + home_source.max.mask = hal.limits_cap.max.mask & ((~settings.homing.dir_mask.mask) & AXES_BITMASK); + home_source.min.mask = (~home_source.max.mask) & AXES_BITMASK; + home_source.max2.mask = hal.limits_cap.max2.mask & ((~settings.homing.dir_mask.mask) & AXES_BITMASK); + home_source.min2.mask = (~home_source.max2.mask) & AXES_BITMASK; + } +} + +// Returns limit signals used by homing when home signals are not available. +limit_signals_t xbar_get_homing_source (void) +{ + return home_source; +} + +// Returns limit signals used by homing cycle when home signals are not available. +limit_signals_t xbar_get_homing_source_from_cycle (axes_signals_t homing_cycle) +{ + limit_signals_t source = home_source; + + if(hal.home_cap.a.mask == 0) { + source.min.mask &= homing_cycle.mask; + source.min2.mask &= homing_cycle.mask; + source.min.mask |= source.min2.mask; + source.max.mask &= homing_cycle.mask; + source.max2.mask &= homing_cycle.mask; + source.max.mask |= source.max2.mask; + } + + return source; +} diff --git a/crossbar.h b/crossbar.h index 3711615..b610b84 100644 --- a/crossbar.h +++ b/crossbar.h @@ -41,22 +41,30 @@ typedef enum { Input_LimitX, Input_LimitX_2, Input_LimitX_Max, + Input_HomeX, Input_LimitY, Input_LimitY_2, Input_LimitY_Max, + Input_HomeY, Input_LimitZ, Input_LimitZ_2, Input_LimitZ_Max, + Input_HomeZ, Input_LimitA, Input_LimitA_Max, + Input_HomeA, Input_LimitB, Input_LimitB_Max, + Input_HomeB, Input_LimitC, Input_LimitC_Max, + Input_HomeC, Input_LimitU, Input_LimitU_Max, + Input_HomeU, Input_LimitV, Input_LimitV_Max, + Input_HomeV, Input_MISO, Input_SPIIRQ, Input_RX, @@ -195,12 +203,15 @@ PROGMEM static const pin_name_t pin_names[] = { { .function = Input_LimitX, .name = "X limit min" }, { .function = Input_LimitX_2, .name = "X limit min 2" }, { .function = Input_LimitX_Max, .name = "X limit max" }, + { .function = Input_HomeX, .name = "X home" }, { .function = Input_LimitY, .name = "Y limit min" }, { .function = Input_LimitY_2, .name = "Y limit min 2" }, { .function = Input_LimitY_Max, .name = "Y limit max" }, + { .function = Input_HomeY, .name = "Y home" }, { .function = Input_LimitZ, .name = "Z limit min" }, { .function = Input_LimitZ_2, .name = "Z limit min 2" }, { .function = Input_LimitZ_Max, .name = "Z limit max" }, + { .function = Input_HomeZ, .name = "Z home" }, { .function = Input_MISO, .name = "MISO" }, { .function = Input_SPIIRQ, .name = "SPI IRQ" }, { .function = Input_RX, .name = "RX" }, @@ -254,6 +265,7 @@ PROGMEM static const pin_name_t pin_names[] = { { .function = Output_StepperEnableA, .name = "A enable" }, { .function = Input_LimitA, .name = "A limit min" }, { .function = Input_LimitA_Max, .name = "A limit max" }, + { .function = Input_HomeA, .name = "A home" }, #endif #ifdef B_AXIS { .function = Output_StepB, .name = "B step" }, @@ -262,6 +274,7 @@ PROGMEM static const pin_name_t pin_names[] = { { .function = Output_StepperEnableAB, .name = "AB enable" }, { .function = Input_LimitB, .name = "B limit min" }, { .function = Input_LimitB_Max, .name = "B limit max" }, + { .function = Input_HomeB, .name = "B home" }, #endif #ifdef C_AXIS { .function = Output_StepC, .name = "C step" }, @@ -269,6 +282,7 @@ PROGMEM static const pin_name_t pin_names[] = { { .function = Output_StepperEnableC, .name = "C enable" }, { .function = Input_LimitC, .name = "C limit min" }, { .function = Input_LimitC_Max, .name = "C limit max" }, + { .function = Input_HomeC, .name = "C home" }, #endif #ifdef U_AXIS { .function = Output_StepU, .name = "U step" }, @@ -276,6 +290,7 @@ PROGMEM static const pin_name_t pin_names[] = { { .function = Output_StepperEnableU, .name = "U enable" }, { .function = Input_LimitU, .name = "U limit min" }, { .function = Input_LimitU_Max, .name = "U limit max" }, + { .function = Input_HomeU, .name = "U home" }, #endif #ifdef V_AXIS { .function = Output_StepV, .name = "V step" }, @@ -283,6 +298,7 @@ PROGMEM static const pin_name_t pin_names[] = { { .function = Output_StepperEnableV, .name = "V enable" }, { .function = Input_LimitV, .name = "V limit min" }, { .function = Input_LimitV_Max, .name = "V limit max" }, + { .function = Input_HomeV, .name = "V home" }, #endif { .function = Output_MotorChipSelect, .name = "Motor CS" }, { .function = Output_MotorChipSelectX, .name = "Motor CSX" }, @@ -357,18 +373,20 @@ typedef enum { PinGroup_UART4, PinGroup_USB, PinGroup_CAN, + PinGroup_Home, // Interrupt capable pins that may have debounce processing enabled PinGroup_Control = (1<<8), PinGroup_Limit = (1<<9), - PinGroup_Probe = (1<<10), - PinGroup_Keypad = (1<<11), - PinGroup_MPG = (1<<12), - PinGroup_QEI = (1<<13), - PinGroup_QEI_Select = (1<<14), - PinGroup_QEI_Index = (1<<15), - PinGroup_Motor_Warning = (1<<16), - PinGroup_Motor_Fault = (1<<17), - PinGroup_AuxInput = (1<<18) + PinGroup_LimitMax = (1<<10), + PinGroup_Probe = (1<<11), + PinGroup_Keypad = (1<<12), + PinGroup_MPG = (1<<13), + PinGroup_QEI = (1<<14), + PinGroup_QEI_Select = (1<<15), + PinGroup_QEI_Index = (1<<16), + PinGroup_Motor_Warning = (1<<17), + PinGroup_Motor_Fault = (1<<18), + PinGroup_AuxInput = (1<<19) } pin_group_t; //! Pin interrupt modes, may be or'ed when reporting pin capability. @@ -479,4 +497,9 @@ typedef struct periph_signal { struct periph_signal *next; } periph_signal_t; +void xbar_set_homing_source (void); +limit_signals_t xbar_get_homing_source (void); +limit_signals_t xbar_get_homing_source_from_cycle (axes_signals_t homing_cycle); +axes_signals_t xbar_fn_to_axismask (pin_function_t id); + #endif diff --git a/grbl.h b/grbl.h index 5ef5252..79cc82a 100644 --- a/grbl.h +++ b/grbl.h @@ -42,7 +42,7 @@ #else #define GRBL_VERSION "1.1f" #endif -#define GRBL_BUILD 20230825 +#define GRBL_BUILD 20230903 #define GRBL_URL "https://github.com/grblHAL" diff --git a/grbllib.c b/grbllib.c index 573b0d6..f2c5f29 100644 --- a/grbllib.c +++ b/grbllib.c @@ -126,6 +126,30 @@ static void auto_realtime_report (sys_state_t state) on_execute_realtime(state); } +// "Wire" homing signals to limit signals, used when max limit inputs not available. +ISR_CODE static home_signals_t ISR_FUNC(get_homing_status)(void) +{ + home_signals_t home; + limit_signals_t limits = hal.limits.get_state(); + + home.a.value = limits.min.value; + home.b.value = limits.min2.value; + + return home; +} + +// "Wire" homing signals to limit signals, used when max limit inputs available. +ISR_CODE static home_signals_t ISR_FUNC(get_homing_status2)(void) +{ + home_signals_t home; + limit_signals_t source = xbar_get_homing_source(), limits = hal.limits.get_state(); + + home.a.value = (limits.min.value & source.min.mask) | (limits.max.value & source.max.mask); + home.b.value = (limits.min2.value & source.min2.mask) | (limits.max2.value & source.max2.mask); + + return home; +} + // main entry point int grbl_enter (void) @@ -162,6 +186,8 @@ int grbl_enter (void) sys.cold_start = true; + limits_init(); + #if NVSDATA_BUFFER_ENABLE nvs_buffer_alloc(); // Allocate memory block for NVS buffer #endif @@ -251,7 +277,6 @@ int grbl_enter (void) if(hal.get_position) hal.get_position(&sys.position); // TODO: restore on abort when returns true? - #if ENABLE_BACKLASH_COMPENSATION mc_backlash_init((axes_signals_t){AXES_BITMASK}); #endif @@ -260,7 +285,7 @@ int grbl_enter (void) // "Wire" homing switches to limit switches if not provided by the driver. if(hal.homing.get_state == NULL) - hal.homing.get_state = hal.limits.get_state; + hal.homing.get_state = hal.limits_cap.max.mask ? get_homing_status2 : get_homing_status; if(settings.report_interval) { on_execute_realtime = grbl.on_execute_realtime; @@ -298,7 +323,7 @@ int grbl_enter (void) // Reset Grbl primary systems. hal.stream.reset_read_buffer(); // Clear input stream buffer gc_init(); // Set g-code parser to default state - hal.limits.enable(settings.limits.flags.hard_enabled, false); + hal.limits.enable(settings.limits.flags.hard_enabled, (axes_signals_t){0}); plan_reset(); // Clear block buffer and planner variables st_reset(); // Clear stepper subsystem variables. limits_set_homing_axes(); // Set axes to be homed from settings. diff --git a/hal.h b/hal.h index f7a3d9d..58a72fb 100644 --- a/hal.h +++ b/hal.h @@ -141,7 +141,7 @@ typedef struct { \param on true to enable limit switches interrupts. \param homing true when machine is in a homing cycle. Usually ignored by driver code, may be used if Trinamic drivers are supported. */ -typedef void (*limits_enable_ptr)(bool on, bool homing); +typedef void (*limits_enable_ptr)(bool on, axes_signals_t homing_cycle); /*! \brief Pointer to function for getting limit switches state. \returns switch states in a limit_signals_t struct. @@ -165,11 +165,15 @@ typedef struct { * Homing * ************/ +/*! \brief Pointer to function for getting home switches state. +\returns switch states in a home_signals_t struct. +*/ +typedef home_signals_t (*home_get_state_ptr)(void); typedef float (*homing_get_feedrate_ptr)(axes_signals_t axes, homing_mode_t mode); //! Limit switches handler for homing cycle. typedef struct { - limits_get_state_ptr get_state; //!< Handler for getting limit switches status. Usually set to the same function as _hal.limits.get_state_. + home_get_state_ptr get_state; //!< Handler for getting homing switches status. Usually read from _hal.limits.get_state_. homing_get_feedrate_ptr get_feedrate; } homing_ptrs_t; @@ -500,6 +504,10 @@ typedef struct { rtc_set_datetime_ptr set_datetime; //!< Optional handler setting the current datetime. } rtc_ptrs_t; +/*! \brief Pointer to function for performing a pallet shuttle. +*/ +typedef void (*pallet_shuttle_ptr)(void); + /*! \brief HAL structure used for the driver interface. This structure contains properties and function pointers (to handlers) that the core uses to communicate with the driver. @@ -574,7 +582,7 @@ typedef struct { irq_claim_ptr irq_claim; limits_ptrs_t limits; //!< Handlers for limit switches. - homing_ptrs_t homing; //!< Handlers for limit switches, used by homing cycle. + homing_ptrs_t homing; //!< Handlers for homing switches, used by homing cycle. control_signals_ptrs_t control; //!< Handlers for control switches. coolant_ptrs_t coolant; //!< Handlers for coolant. spindle_data_ptrs_t spindle_data; //!< Handlers for getting/resetting spindle data (RPM, angular position, ...). @@ -591,7 +599,7 @@ typedef struct { enumerate_pins_ptr enumerate_pins; //!< Optional handler for enumerating pins used by the driver. bool (*driver_release)(void); //!< Optional handler for releasing hardware resources before exiting. uint32_t (*get_elapsed_ticks)(void); //!< Optional handler for getting number of elapsed 1ms tics since startup. Required by a number of plugins. - void (*pallet_shuttle)(void); //!< Optional handler for performing a pallet shuttle on program end (M60). + pallet_shuttle_ptr pallet_shuttle; //!< Optional handler for performing a pallet shuttle on program end (M60). void (*reboot)(void); //!< Optoional handler for rebooting the controller. This will be called when #ASCII_ESC followed by #CMD_REBOOT is received. user_mcode_ptrs_t user_mcode; //!< Optional handlers for user defined M-codes. @@ -619,6 +627,7 @@ typedef struct { driver_cap_t driver_cap; //!< Basic driver capabilities flags. control_signals_t signals_cap; //!< Control input signals supported by the driver. limit_signals_t limits_cap; //!< Limit input signals supported by the driver. + home_signals_t home_cap; //!< Home input signals supported by the driver. } grbl_hal_t; diff --git a/ioports.c b/ioports.c index 41a12c9..a06c60f 100644 --- a/ioports.c +++ b/ioports.c @@ -343,12 +343,12 @@ static bool is_setting_available (const setting_detail_t *setting) case Settings_IoPort_InvertIn: case Settings_IoPort_Pullup_Disable: - available = digital.in.ports->n_ports > 0; + available = digital.in.ports && digital.in.ports->n_ports > 0; break; case Settings_IoPort_InvertOut: case Settings_IoPort_OD_Enable: - available = digital.out.ports->n_ports > 0; + available = digital.out.ports && digital.out.ports->n_ports > 0; break; default: diff --git a/kinematics.h b/kinematics.h index fdc553d..886a8ed 100644 --- a/kinematics.h +++ b/kinematics.h @@ -3,7 +3,7 @@ Part of grblHAL - Copyright (c) 2019-2022 Terje Io + Copyright (c) 2019-2023 Terje Io Grbl is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by @@ -30,7 +30,7 @@ typedef struct { void (*limits_set_target_pos)(uint_fast8_t idx); void (*limits_set_machine_positions)(axes_signals_t cycle); bool (*homing_cycle_validate)(axes_signals_t cycle); - float (*homing_cycle_get_feedrate)(float feedrate, axes_signals_t cycle); + float (*homing_cycle_get_feedrate)(axes_signals_t axes, float rate, homing_mode_t mode); } kinematics_t; extern kinematics_t kinematics; diff --git a/kinematics/corexy.c b/kinematics/corexy.c index 66e9b24..9350bdf 100644 --- a/kinematics/corexy.c +++ b/kinematics/corexy.c @@ -197,7 +197,7 @@ static bool homing_cycle_validate (axes_signals_t cycle) return (cycle.mask & (X_AXIS_BIT|Y_AXIS_BIT)) == 0 || cycle.mask < 3; } -static float homing_cycle_get_feedrate (float feedrate, axes_signals_t cycle) +static float homing_cycle_get_feedrate (axes_signals_t cycle, float feedrate, homing_mode_t mode) { return feedrate * sqrtf(2.0f); } diff --git a/kinematics/delta.c b/kinematics/delta.c index 6ca8a31..df8e5c3 100644 --- a/kinematics/delta.c +++ b/kinematics/delta.c @@ -34,8 +34,24 @@ #include "../settings.h" #include "../nvs_buffer.h" #include "../planner.h" +#include "../motion_control.h" +#include "../protocol.h" #include "../kinematics.h" +#define A_MOTOR X_AXIS +#define B_MOTOR Y_AXIS +#define C_MOTOR Z_AXIS + +// Define step segment generator state flags. +typedef union { + uint8_t mask; + struct { + uint8_t home_to_cuboid_top :1, + limit_to_cuboid :1, + unassigned :6; + }; +} delta_settings_flags_t; + typedef struct { float rf; // bicep length float re; // forearm length @@ -43,28 +59,43 @@ typedef struct { float e; // end effector radius float b; // base to floor float sl; // max segment length TODO: replace with calculated value? + float home_angle; + delta_settings_flags_t flags; } delta_settings_t; +typedef struct { + float home_z; + float home_pulloff; + float resolution; + float envelope_midz; + float min_angle[3]; + float max_angle[3]; + delta_settings_t cfg; +} delta_properties_t; + static bool jog_cancel = false; static coord_data_t last_pos = {0}; -static delta_settings_t machine = {0}, delta_settings; +static delta_settings_t delta_settings; +static delta_properties_t machine; +static homing_mode_t homing_mode; static on_report_options_ptr on_report_options; static on_homing_completed_ptr on_homing_completed; static on_report_command_help_ptr on_report_command_help; +static on_set_axis_setting_unit_ptr on_set_axis_setting_unit; +static on_setting_get_description_ptr on_setting_get_description; static nvs_address_t nvs_address; -static float z0, resolution; // inverse kinematics // helper functions, calculates angle position[X_AXIS] (for YZ-pane) int delta_calcAngleYZ (float x0, float y0, float z0, float *theta) { - float y1 = -0.5f * TAN30 * machine.f; // f/2 * tg 30 - y0 -= 0.5f * TAN30 * machine.e; // shift center to edge + float y1 = -0.5f * TAN30 * machine.cfg.f; // f/2 * tg 30 + y0 -= 0.5f * TAN30 * machine.cfg.e; // shift center to edge // z = a + b*y - float a = (x0 * x0 + y0 * y0 + z0 * z0 + machine.rf * machine.rf - machine.re * machine.re - y1 * y1) / (2.0f * z0); + float a = (x0 * x0 + y0 * y0 + z0 * z0 + machine.cfg.rf * machine.cfg.rf - machine.cfg.re * machine.cfg.re - y1 * y1) / (2.0f * z0); float b = (y1 - y0) / z0; // discriminant - float d = -(a + b * y1) * (a + b * y1) + machine.rf * (b * b * machine.rf + machine.rf); + float d = -(a + b * y1) * (a + b * y1) + machine.cfg.rf * (b * b * machine.cfg.rf + machine.cfg.rf); if (d < 0.0f) return -1; // non-existing point @@ -94,23 +125,23 @@ int delta_calcInverse (coord_data_t *mpos, float *position) // Returns machine position in mm converted from system position. static float *transform_to_cartesian (float *target, float *position) { - float t = (machine.f - machine.e) * TAN30_2; + float t = (machine.cfg.f - machine.cfg.e) * TAN30_2; /* float dtr = M_PI / 180.0f; position[X_AXIS] *= dtr; position[Y_AXIS] *= dtr; position[Z_AXIS] *= dtr; */ - float y1 = -(t + machine.rf * cosf(position[X_AXIS])); - float z1 = -machine.rf * sinf(position[X_AXIS]); + float y1 = -(t + machine.cfg.rf * cosf(position[X_AXIS])); + float z1 = -machine.cfg.rf * sinf(position[X_AXIS]); - float y2 = (t + machine.rf * cosf(position[Y_AXIS])) * SIN30; + float y2 = (t + machine.cfg.rf * cosf(position[Y_AXIS])) * SIN30; float x2 = y2 * TAN60; - float z2 = -machine.rf * sinf(position[Y_AXIS]); + float z2 = -machine.cfg.rf * sinf(position[Y_AXIS]); - float y3 = (t + machine.rf * cosf(position[Z_AXIS])) * SIN30; + float y3 = (t + machine.cfg.rf * cosf(position[Z_AXIS])) * SIN30; float x3 = -y3 * TAN60; - float z3 = -machine.rf * sinf(position[Z_AXIS]); + float z3 = -machine.cfg.rf * sinf(position[Z_AXIS]); float dnm = (y2 - y1) * x3 -(y3 - y1) * x2; @@ -129,7 +160,7 @@ static float *transform_to_cartesian (float *target, float *position) // a*z^2 + b*z + c = 0 float a = a1 * a1 + a2 * a2 + dnm * dnm; float b = 2.0f * (a1 * b1 + a2 * (b2 - y1 * dnm) - z1 * dnm * dnm); - float c = (b2 - y1 * dnm) * (b2 - y1 * dnm) + b1 * b1 + dnm * dnm * (z1 * z1 - machine.re * machine.re); + float c = (b2 - y1 * dnm) * (b2 - y1 * dnm) + b1 * b1 + dnm * dnm * (z1 * z1 - machine.cfg.re * machine.cfg.re); // discriminant float d = b * b - 4.0f * a * c; @@ -204,10 +235,10 @@ static float *delta_segment_line (float *target, float *position, plan_line_data distance = sqrtf(delta.x * delta.x + delta.y * delta.y + delta.z * delta.z); - if((segmented = distance > machine.sl && !(delta.x == 0.0f && delta.y == 0.0f && delta.z == 0.0f))) { + if((segmented = distance > machine.cfg.sl && !(delta.x == 0.0f && delta.y == 0.0f && delta.z == 0.0f))) { idx = N_AXIS; - iterations = (uint_fast16_t)ceilf(distance / machine.sl); + iterations = (uint_fast16_t)ceilf(distance / machine.cfg.sl); do { --idx; @@ -223,7 +254,7 @@ static float *delta_segment_line (float *target, float *position, plan_line_data } else { // out of bounds, report? or should never happen? iterations = 1; - memcpy(&segment_target, target, sizeof(coord_data_t)); + memcpy(&final_target, position, sizeof(coord_data_t)); } iterations++; // return at least one iteration @@ -240,7 +271,10 @@ static float *delta_segment_line (float *target, float *position, plan_line_data } else memcpy(&segment_target, &final_target, sizeof(coord_data_t)); - delta_calcInverse(&segment_target, mpos.values); + if(delta_calcInverse(&segment_target, mpos.values) != 0) { + memcpy(&mpos, &last_pos, sizeof(coord_data_t)); + iterations = 0; + } if(!pl_data->condition.rapid_motion && distance != 0.0f) { float rate_multiplier = get_distance(mpos.values, last_pos.values) / distance; @@ -256,20 +290,27 @@ static float *delta_segment_line (float *target, float *position, plan_line_data static void get_cuboid_envelope (void) { - float maxx = -machine.e - machine.f - machine.re - machine.rf; + float maxx = -machine.cfg.e - machine.cfg.f - machine.cfg.re - machine.cfg.rf; float maxz = maxx; float minz = -maxx; - float sr = (2.0f * M_PI) / settings.axis[X_AXIS].steps_per_mm; // Steps/rev -> rad/step, XYZ motors should have the same setting! + float sr = 1.0f / settings.axis[X_AXIS].steps_per_mm; // Steps/rev -> rad/step, XYZ motors should have the same setting! float pos[N_AXIS]; uint32_t z; - coord_data_t mpos; + coord_data_t mpos, home = { + .x = machine.cfg.home_angle, + .y = machine.cfg.home_angle, + .z = machine.cfg.home_angle + }; struct { int32_t res; float pos[N_AXIS]; } r[8]; + transform_to_cartesian(mpos.values, home.values); + machine.home_z = mpos.z; + // find extents - for(z = 0; z < settings.axis[X_AXIS].steps_per_mm; ++z) { + for(z = 0; z < settings.axis[X_AXIS].steps_per_mm * 2.0f * M_PI ; ++z) { pos[0] = pos[1] = pos[2] = sr * (float)z; transform_to_cartesian(mpos.values, pos); if(!isnanf(mpos.x)) { @@ -280,7 +321,9 @@ static void get_cuboid_envelope (void) } } - float btf = -machine.b; + maxz = machine.home_z; + + float btf = -machine.cfg.b; if(minz < btf) minz = btf; if(maxz < btf) @@ -290,14 +333,10 @@ static void get_cuboid_envelope (void) float original_dist = (maxz - middlez); float dist = original_dist * 0.5f; float sum = 0.0f; -/* - float mint1 = 2.0 * M_PI; - float maxt1 = -2.0 * M_PI; - float mint2 = 2.0 * M_PI; - float maxt2 = -2.0 * M_PI; - float mint3 = 2.0 * M_PI; - float maxt3 = -2.0 * M_PI; -*/ + + machine.min_angle[A_MOTOR] = machine.min_angle[B_MOTOR] = machine.min_angle[C_MOTOR] = 2.0 * M_PI; + machine.max_angle[A_MOTOR] = machine.max_angle[B_MOTOR] = machine.max_angle[C_MOTOR] = -2.0 * M_PI; + do { sum += dist; @@ -331,24 +370,23 @@ static void get_cuboid_envelope (void) if(r[0].res || r[1].res || r[2].res || r[3].res || r[4].res || r[5].res || r[6].res || r[7].res) { sum -= dist; dist *= 0.5f; - } /* else { + } else { uint32_t i; - for(i = 0; i < 8; ++i) - { - if(mint1 > r[i].pos[0]) - mint1 = r[i].pos[0]; - if(maxt1 < r[i].pos[0]) - maxt1 = r[i].pos[0]; - if(mint2 > r[i].pos[1]) - mint2 = r[i].pos[1]; - if(maxt2 < r[i].pos[1]) - maxt2 = r[i].pos[1]; - if(mint3 > r[i].pos[2]) - mint3 = r[i].pos[2]; - if(maxt3 < r[i].pos[2]) - maxt3 = r[i].pos[2]; + for(i = 0; i < 8; ++i) { + if(machine.min_angle[A_MOTOR] > r[i].pos[A_MOTOR]) + machine.min_angle[A_MOTOR] = r[i].pos[A_MOTOR]; + if(machine.max_angle[A_MOTOR] < r[i].pos[A_MOTOR]) + machine.max_angle[A_MOTOR] = r[i].pos[A_MOTOR]; + if(machine.min_angle[B_MOTOR] > r[i].pos[B_MOTOR]) + machine.min_angle[B_MOTOR] = r[i].pos[B_MOTOR]; + if(machine.max_angle[B_MOTOR] < r[i].pos[B_MOTOR]) + machine.max_angle[B_MOTOR] = r[i].pos[B_MOTOR]; + if(machine.min_angle[C_MOTOR] > r[i].pos[C_MOTOR]) + machine.min_angle[C_MOTOR] = r[i].pos[C_MOTOR]; + if(machine.max_angle[C_MOTOR] < r[i].pos[C_MOTOR]) + machine.max_angle[C_MOTOR] = r[i].pos[C_MOTOR]; } - } */ + } } while(original_dist > sum && dist > 0.1f); sys.work_envelope.min[X_AXIS] = -sum; @@ -366,7 +404,8 @@ static void get_cuboid_envelope (void) float x = r[0].pos[0] - r[1].pos[0]; float y = r[0].pos[1] - r[1].pos[1]; - resolution = sqrtf(x * x + y * y); // use as segment length (/ 2)? + machine.resolution = sqrtf(x * x + y * y); // use as segment length (/ 2)? + machine.envelope_midz = middlez; } static float *get_homing_target (float *target, float *position) @@ -375,10 +414,12 @@ static float *get_homing_target (float *target, float *position) do { idx--; - if((settings.homing.pulloff * HOMING_AXIS_LOCATE_SCALAR - fabsf(position[X_AXIS])) > - 0.1f) - target[idx] = position[X_AXIS] * (2.0f * M_PI) / settings.axis[X_AXIS].steps_per_mm; + if(homing_mode == HomingMode_Pulloff) + target[idx] = machine.home_pulloff = position[X_AXIS] / machine.resolution / settings.axis[X_AXIS].steps_per_mm; + else if(homing_mode == HomingMode_Locate) + target[idx] = position[X_AXIS] / machine.resolution / settings.axis[X_AXIS].steps_per_mm; else - target[idx] = bit_istrue(settings.homing.dir_mask.value, bit(idx)) ? -.5f : .5f; + target[idx] = bit_istrue(settings.homing.dir_mask.value, bit(idx)) ? -M_PI : M_PI; // 0.5 revolution } while(idx); return target; @@ -394,10 +435,13 @@ static void delta_limits_set_target_pos (uint_fast8_t idx) sys.position[idx] = 0; } -static float homing_cycle_get_feedrate (float feedrate, axes_signals_t cycle) +static float homing_cycle_get_feedrate (axes_signals_t cycle, float feedrate, homing_mode_t mode) { + homing_mode = mode; kinematics.transform_from_cartesian = get_homing_target; + // TODO: transform feedrate to rad/min + return feedrate; } @@ -405,10 +449,11 @@ static float homing_cycle_get_feedrate (float feedrate, axes_signals_t cycle) // NOTE: settings.max_travel[] is stored as a negative value. static void delta_limits_set_machine_positions (axes_signals_t cycle) { - uint_fast8_t idx = N_AXIS; -// float pulloff = add_pulloff ? settings.homing.pulloff : 0.0f; - float pulloff = settings.homing.pulloff; +// uint_fast8_t idx = N_AXIS; + sys.position[X_AXIS] = sys.position[Y_AXIS] = sys.position[Z_AXIS] = (machine.cfg.home_angle + machine.home_pulloff) * settings.axis[X_AXIS].steps_per_mm; + +/* if(settings.homing.flags.force_set_origin || true) { do { if(cycle.mask & bit(--idx)) { @@ -424,14 +469,48 @@ static void delta_limits_set_machine_positions (axes_signals_t cycle) sys.position[idx] = lroundf(sys.home_position[idx] * settings.axis[idx].steps_per_mm); } } while(idx); + + */ +} + +static void delta_go_home (sys_state_t state) +{ + plan_line_data_t plan_data; + + plan_data_init(&plan_data); + plan_data.condition.rapid_motion = On; + + if(mc_line(sys.home_position, &plan_data)) { + protocol_buffer_synchronize(); + sync_position(); + } } static void delta_homing_complete (bool success) { + coord_data_t pos, home = { + .x = machine.cfg.home_angle, + .y = machine.cfg.home_angle, + .z = machine.cfg.home_angle + }; + kinematics.transform_from_cartesian = transform_from_cartesian; - if(success) + if(success) { + get_cuboid_envelope(); + transform_to_cartesian(pos.values, home.values); +// sys.work_envelope.max[Z_AXIS] = pos.z; + + sys.home_position[0] = .0f; + sys.home_position[1] = .0f; + sys.home_position[2] = machine.cfg.flags.home_to_cuboid_top + ? sys.work_envelope.max[Z_AXIS] + : machine.home_z; // + pulloff + + if(machine.cfg.flags.home_to_cuboid_top) + protocol_enqueue_rt_command(delta_go_home); + } if(on_homing_completed) on_homing_completed(success); @@ -442,6 +521,112 @@ static void cancel_jog (sys_state_t state) jog_cancel = true; } +// Checks and reports if target array exceeds machine travel limits. Returns false if check failed. +static bool is_target_inside_cuboid (float *target, bool is_cartesian) +{ + bool failed = false; + uint_fast8_t idx = N_AXIS; + + if(is_cartesian && sys.homed.mask) do { + idx--; + if(bit_istrue(sys.homed.mask, bit(idx)) && settings.axis[idx].max_travel < -0.0f) + failed = target[idx] < sys.work_envelope.min[idx] || target[idx] > sys.work_envelope.max[idx]; + } while(!failed && idx); + + return is_cartesian && !failed; +} + +// Checks and reports if target array exceeds machine travel limits. Returns false if check failed. +static bool delta_check_travel_limits (float *target, bool is_cartesian) +{ + bool failed = false; + uint_fast8_t idx = N_AXIS; + coord_data_t pos; + + if(!is_cartesian) { + if(isnanf(transform_to_cartesian(pos.values, target)[A_MOTOR])) + return false; + } + + if(is_target_inside_cuboid(is_cartesian ? target : pos.values, true)) + return true; + + if(machine.cfg.flags.limit_to_cuboid) + return false; + + if(is_cartesian && delta_calcInverse((coord_data_t *)target, pos.values)) + return false; + + if(!is_cartesian) + memcpy(&pos.values, target, sizeof(coord_data_t)); + + if(is_cartesian && sys.homed.mask) do { + idx--; + if(bit_istrue(sys.homed.mask, bit(idx)) && settings.axis[idx].max_travel < -0.0f) { + if(idx > Z_AXIS) + failed = target[idx] < sys.work_envelope.min[idx] || target[idx] > sys.work_envelope.max[idx]; + else + failed = pos.values[idx] < machine.min_angle[idx] || pos.values[idx] > machine.max_angle[idx]; + } + } while(!failed && idx); + + return !failed; +} + +static bool delta_apply_jog_limits (float *target, bool is_cartesian) +{ + uint_fast8_t idx = N_AXIS; + + if(machine.cfg.flags.limit_to_cuboid) { + if(sys.homed.mask) do { + idx--; + if(bit_istrue(sys.homed.mask, bit(idx)) && settings.axis[idx].max_travel < -0.0f) + target[idx] = max(min(target[idx], sys.work_envelope.max[idx]), sys.work_envelope.min[idx]); + } while(idx); + + return true; + } else if(is_target_inside_cuboid(target, is_cartesian)) + return true; + + coord_data_t mpos; + + if(delta_calcInverse((coord_data_t *)target, mpos.values)) { +// find and apply limits... + } + + return true; +} + +static const char *delta_set_axis_setting_unit (setting_id_t setting_id, uint_fast8_t axis_idx) +{ + const char *unit = NULL; + + if(axis_idx <= Z_AXIS) switch(setting_id) { + + case Setting_AxisStepsPerMM: + unit = "step/rad"; + break; + + case Setting_AxisMaxRate: + unit = "rad/min"; + break; + + case Setting_AxisAcceleration: + unit = "rad/sec^2"; + break; + + case Setting_AxisMaxTravel: + case Setting_AxisBacklash: + unit = "rad"; + break; + + default: + break; + } + + return unit == NULL && on_set_axis_setting_unit != NULL ? on_set_axis_setting_unit(setting_id, axis_idx) : unit; +} + static const setting_group_detail_t kinematics_groups [] = { { Group_Root, Group_Kinematics, "Delta robot"} }; @@ -452,28 +637,28 @@ static const setting_detail_t kinematics_settings[] = { { Setting_Kinematics2, Group_Kinematics, "Bicep length", "mm", Format_Decimal, "##0.000", NULL, NULL, Setting_NonCore, &delta_settings.rf, NULL, NULL }, { Setting_Kinematics3, Group_Kinematics, "Base radius", "mm", Format_Decimal, "##0.000", NULL, NULL, Setting_NonCore, &delta_settings.f, NULL, NULL }, { Setting_Kinematics4, Group_Kinematics, "End effector radius", "mm", Format_Decimal, "##0.000", NULL, NULL, Setting_NonCore, &delta_settings.e, NULL, NULL }, - { Setting_Kinematics5, Group_Kinematics, "Base to floor", "mm", Format_Decimal, "###0.000", NULL, NULL, Setting_NonCore, &delta_settings.b, NULL, NULL } + { Setting_Kinematics5, Group_Kinematics, "Base to floor", "mm", Format_Decimal, "###0.000", NULL, NULL, Setting_NonCore, &delta_settings.b, NULL, NULL }, + { Setting_Kinematics6, Group_Kinematics, "Home position", "deg", Format_Decimal, "-#0.000", "-90", "90", Setting_NonCore, &delta_settings.home_angle, NULL, NULL }, + { Setting_Kinematics7, Group_Kinematics, "Flags...", NULL, Format_Bitfield, "Home to cuboid top,Limit to cuboid", NULL, NULL, Setting_NonCore, &delta_settings.flags, NULL, NULL }, }; #ifndef NO_SETTINGS_DESCRIPTIONS static const setting_descr_t kinematics_settings_descr[] = { - { Setting_Kinematics0, "Step jogging speed in millimeters per minute." }, - { Setting_Kinematics1, "Slow jogging speed in millimeters per minute." }, - { Setting_Kinematics2, "Fast jogging speed in millimeters per minute." }, - { Setting_Kinematics3, "Jog distance for single step jogging." }, - { Setting_Kinematics4, "Jog distance before automatic stop." } + { Setting_Kinematics0, "Size that moves are broken up into to compensate for the non-linear movement of a delta robot." }, + { Setting_Kinematics1, "Forearm length is the length of the connecting rod in millimeters." }, + { Setting_Kinematics2, "Bicep length is the length of the driven arm in millimeters." }, + { Setting_Kinematics3, "Base radius is the radius in millimeters from the center of the drive platform to the bicep drive axle." }, + { Setting_Kinematics4, "End effector radius is the distance from the center of the end effector to the connection points of the main connecting rods." } }; #endif static void delta_settings_changed (settings_t *settings, settings_changed_flags_t changed) { - float position[N_AXIS] = {0}, cartesian[N_AXIS]; + memcpy(&machine.cfg, &delta_settings, sizeof(delta_settings_t)); - memcpy(&machine, &delta_settings, sizeof(delta_settings_t)); - - z0 = transform_to_cartesian(cartesian, position)[Z_AXIS]; + machine.cfg.home_angle = delta_settings.home_angle * RADDEG; get_cuboid_envelope(); } @@ -491,6 +676,8 @@ static void delta_settings_restore (void) delta_settings.re = 300.0f; delta_settings.rf = 100.0f; delta_settings.sl = .2f; + delta_settings.home_angle = 0.0f; + delta_settings.flags.mask = 0; hal.nvs.memcpy_to_nvs(nvs_address, (uint8_t *)&delta_settings, sizeof(delta_settings_t), true); } @@ -499,6 +686,11 @@ static void delta_settings_load (void) { if(hal.nvs.memcpy_from_nvs((uint8_t *)&delta_settings, nvs_address, sizeof(delta_settings_t), true) != NVS_TransferResult_OK) delta_settings_restore(); + + if(on_set_axis_setting_unit == NULL) { + on_set_axis_setting_unit = grbl.on_set_axis_setting_unit; + grbl.on_set_axis_setting_unit = delta_set_axis_setting_unit; + } } static setting_details_t setting_details = { @@ -507,8 +699,8 @@ static setting_details_t setting_details = { .settings = kinematics_settings, .n_settings = sizeof(kinematics_settings) / sizeof(setting_detail_t), #ifndef NO_SETTINGS_DESCRIPTIONS -// .descriptions = kinematics_settings_descr, -// .n_descriptions = sizeof(kinematics_settings_descr) / sizeof(setting_descr_t), + .descriptions = kinematics_settings_descr, + .n_descriptions = sizeof(kinematics_settings_descr) / sizeof(setting_descr_t), #endif .load = delta_settings_load, .restore = delta_settings_restore, @@ -521,35 +713,40 @@ static void report_options (bool newopt) on_report_options(newopt); if(!newopt) - hal.stream.write("[KINEMATICS:Delta v0.01]" ASCII_EOL); + hal.stream.write("[KINEMATICS:Delta v0.02]" ASCII_EOL); } static status_code_t delta_info (sys_state_t state, char *args) { hal.stream.write("Delta robot:" ASCII_EOL); - hal.stream.write(" Rectangular cuboid envelope:" ASCII_EOL); - hal.stream.write(" X: "); + hal.stream.write(" Rectangular cuboid envelope:" ASCII_EOL " X: "); hal.stream.write(ftoa(sys.work_envelope.min[X_AXIS], 3)); hal.stream.write(" to "); hal.stream.write(ftoa(sys.work_envelope.max[X_AXIS], 3)); - hal.stream.write(" mm" ASCII_EOL); - hal.stream.write(" Y: "); + hal.stream.write(" mm" ASCII_EOL " Y: "); hal.stream.write(ftoa(sys.work_envelope.min[Y_AXIS], 3)); hal.stream.write(" to "); hal.stream.write(ftoa(sys.work_envelope.max[Y_AXIS], 3)); - hal.stream.write(" mm" ASCII_EOL); - hal.stream.write(" Z: "); + hal.stream.write(" mm" ASCII_EOL " Z: "); hal.stream.write(ftoa(sys.work_envelope.min[Z_AXIS], 3)); hal.stream.write(" to "); hal.stream.write(ftoa(sys.work_envelope.max[Z_AXIS], 3)); - hal.stream.write(" mm" ASCII_EOL); - hal.stream.write(" Resolution:" ASCII_EOL " "); - hal.stream.write(ftoa(resolution, 3)); + hal.stream.write(" mm" ASCII_EOL " Mid Z:" ASCII_EOL " "); + hal.stream.write(ftoa(machine.envelope_midz, 3)); + hal.stream.write(" mm" ASCII_EOL " Resolution:" ASCII_EOL " "); + hal.stream.write(ftoa(machine.resolution, 3)); hal.stream.write(" mm" ASCII_EOL); return Status_OK; } +static const char *delta_setting_get_description (setting_id_t id) +{ + return id >= Setting_AxisStepsPerMM && id <= (Setting_AxisStepsPerMM + Z_AXIS) + ? "Travel resolution in steps per radian (57.296 degrees)." + : (on_setting_get_description ? on_setting_get_description(id) : NULL); +} + static void delta_command_help (void) { hal.stream.write("$DELTA - show info about delta robot parameters" ASCII_EOL); @@ -586,6 +783,8 @@ void delta_robot_init (void) kinematics.homing_cycle_get_feedrate = homing_cycle_get_feedrate; grbl.on_jog_cancel = cancel_jog; + grbl.apply_jog_limits = delta_apply_jog_limits; + grbl.check_travel_limits = delta_check_travel_limits; on_report_options = grbl.on_report_options; grbl.on_report_options = report_options; @@ -599,6 +798,9 @@ void delta_robot_init (void) on_homing_completed = grbl.on_homing_completed; grbl.on_homing_completed = delta_homing_complete; + on_setting_get_description = grbl.on_setting_get_description; + grbl.on_setting_get_description = delta_setting_get_description; + settings_register(&setting_details); } } diff --git a/machine_limits.c b/machine_limits.c index 0f09cff..b7f6803 100644 --- a/machine_limits.c +++ b/machine_limits.c @@ -61,25 +61,25 @@ ISR_CODE axes_signals_t ISR_FUNC(limit_signals_merge)(limit_signals_t signals) } // Merge (bitwise or) home switch inputs (typically acquired from limits.min and limits.min2). -ISR_CODE static axes_signals_t ISR_FUNC(homing_signals_select)(limit_signals_t signals, axes_signals_t auto_square, squaring_mode_t mode) +ISR_CODE static axes_signals_t ISR_FUNC(homing_signals_select)(home_signals_t signals, axes_signals_t auto_square, squaring_mode_t mode) { axes_signals_t state; switch(mode) { case SquaringMode_A: - signals.min.mask &= ~auto_square.mask; + signals.a.mask &= ~auto_square.mask; break; case SquaringMode_B: - signals.min2.mask &= ~auto_square.mask; + signals.b.mask &= ~auto_square.mask; break; default: break; } - state.mask = signals.min.mask | signals.min2.mask; + state.mask = signals.a.mask | signals.b.mask; return state; } @@ -251,25 +251,17 @@ static bool limits_pull_off (axes_signals_t axis, float distance) return true; // Note: failure is returned above if move fails. } -static float limits_get_homing_rate (axes_signals_t cycle, homing_mode_t mode) -{ - return mode == HomingMode_Locate ? settings.homing.feed_rate : settings.homing.seek_rate; -} - // Homes the specified cycle axes, sets the machine position, and performs a pull-off motion after // completing. Homing is a special motion case, which involves rapid uncontrolled stops to locate // the trigger point of the limit switches. The rapid stops are handled by a system level axis lock // mask, which prevents the stepper algorithm from executing step pulses. Homing motions typically // circumvent the processes for executing motions in normal operation. // NOTE: Only the abort realtime command can interrupt this process. -static bool limits_homing_cycle (axes_signals_t cycle, axes_signals_t auto_square) +static bool homing_cycle (axes_signals_t cycle, axes_signals_t auto_square) { if (ABORTED) // Block if system reset has been issued. return false; - if(hal.homing.get_feedrate == NULL) - hal.homing.get_feedrate = limits_get_homing_rate; - int32_t initial_trigger_position = 0, autosquare_fail_distance = 0; uint_fast8_t n_cycle = (2 * settings.homing.locate_cycles + 1); uint_fast8_t step_pin[N_AXIS], n_active_axis, dual_motor_axis = 0; @@ -277,7 +269,7 @@ static bool limits_homing_cycle (axes_signals_t cycle, axes_signals_t auto_squar float max_travel = 0.0f, homing_rate; homing_mode_t mode = HomingMode_Seek; axes_signals_t axislock, homing_state; - limit_signals_t limits_state; + home_signals_t signals_state; squaring_mode_t squaring_mode = SquaringMode_Both; coord_data_t target; plan_line_data_t plan_data; @@ -360,7 +352,7 @@ static bool limits_homing_cycle (axes_signals_t cycle, axes_signals_t auto_squar #ifdef KINEMATICS_API if(kinematics.homing_cycle_get_feedrate) - homing_rate = kinematics.homing_cycle_get_feedrate(homing_rate, cycle); + homing_rate = kinematics.homing_cycle_get_feedrate(cycle, homing_rate, mode); #endif if(grbl.on_homing_rate_set) @@ -389,14 +381,14 @@ static bool limits_homing_cycle (axes_signals_t cycle, axes_signals_t auto_squar if (mode != HomingMode_Pulloff) { // Check homing switches state. Lock out cycle axes when they change. - homing_state = homing_signals_select(limits_state = hal.homing.get_state(), auto_square, squaring_mode); + homing_state = homing_signals_select(signals_state = hal.homing.get_state(), auto_square, squaring_mode); // Auto squaring check if((homing_state.mask & auto_square.mask) && squaring_mode == SquaringMode_Both) { - if((autosquare_check = (limits_state.min.mask & auto_square.mask) != (limits_state.min2.mask & auto_square.mask))) { + if((autosquare_check = (signals_state.a.mask & auto_square.mask) != (signals_state.b.mask & auto_square.mask))) { initial_trigger_position = sys.position[dual_motor_axis]; homing_state.mask &= ~auto_square.mask; - squaring_mode = (limits_state.min.mask & auto_square.mask) ? SquaringMode_A : SquaringMode_B; + squaring_mode = (signals_state.a.mask & auto_square.mask) ? SquaringMode_A : SquaringMode_B; hal.stepper.disable_motors(auto_square, squaring_mode); } } @@ -440,6 +432,8 @@ static bool limits_homing_cycle (axes_signals_t cycle, axes_signals_t auto_squar if (rt_exec & EXEC_SAFETY_DOOR) system_set_exec_alarm(Alarm_HomingFailDoor); + hal.delay_ms(2, NULL); + // Homing failure condition: Homing switch(es) still engaged after pull-off motion if (mode == HomingMode_Pulloff && (homing_signals_select(hal.homing.get_state(), (axes_signals_t){0}, SquaringMode_Both).mask & cycle.mask)) system_set_exec_alarm(Alarm_FailPulloff); @@ -522,6 +516,8 @@ status_code_t limits_go_home (axes_signals_t cycle) { axes_signals_t auto_square = {0}, auto_squared = {0}; + hal.limits.enable(settings.limits.flags.hard_enabled, cycle); // Disable hard limits pin change register for cycle duration + if(hal.stepper.get_ganged) auto_squared = hal.stepper.get_ganged(true); @@ -545,7 +541,7 @@ status_code_t limits_go_home (axes_signals_t cycle) tc_clear_tlo_reference(cycle); - return limits_homing_cycle(cycle, auto_square) ? Status_OK : Status_Unhandled; + return grbl.home_machine(cycle, auto_square) ? Status_OK : Status_Unhandled; } // Performs a soft limit check. Called from mc_line() only. Assumes the machine has been homed, @@ -553,17 +549,21 @@ status_code_t limits_go_home (axes_signals_t cycle) // NOTE: Also used by jogging to block travel outside soft-limit volume. void limits_soft_check (float *target) { - if (!system_check_travel_limits(target)) { +#ifdef KINEMATICS_API + if(!grbl.check_travel_limits(target, false)) { +#else + if(!grbl.check_travel_limits(target, true)) { +#endif sys.flags.soft_limit = On; // Force feed hold if cycle is active. All buffered blocks are guaranteed to be within // workspace volume so just come to a controlled stop so position is not lost. When complete // enter alarm mode. - if (state_get() == STATE_CYCLE) { + if(state_get() == STATE_CYCLE) { system_set_exec_state_flag(EXEC_FEED_HOLD); do { if(!protocol_execute_realtime()) return; // aborted! - } while (state_get() != STATE_IDLE); + } while(state_get() != STATE_IDLE); } mc_reset(); // Issue system reset and ensure spindle and coolant are shutdown. system_set_exec_alarm(Alarm_SoftLimit); // Indicate soft limit critical event @@ -593,3 +593,44 @@ bool limits_homing_required (void) sys.homing.mask && (sys.homing.mask & sys.homed.mask) != sys.homing.mask; } +static float get_homing_rate (axes_signals_t cycle, homing_mode_t mode) +{ + return mode == HomingMode_Locate ? settings.homing.feed_rate : settings.homing.seek_rate; +} + +// Checks and reports if target array exceeds machine travel limits. Returns false if check failed. +static bool check_travel_limits (float *target, bool is_cartesian) +{ + bool failed = false; + uint_fast8_t idx = N_AXIS; + + if(is_cartesian && sys.homed.mask) do { + idx--; + if(bit_istrue(sys.homed.mask, bit(idx)) && settings.axis[idx].max_travel < -0.0f) + failed = target[idx] < sys.work_envelope.min[idx] || target[idx] > sys.work_envelope.max[idx]; + } while(!failed && idx); + + return is_cartesian && !failed; +} + +// Limits jog commands to be within machine limits, homed axes only. +static bool apply_jog_limits (float *target, bool is_cartesian) +{ + uint_fast8_t idx = N_AXIS; + + if(sys.homed.mask) do { + idx--; + if(bit_istrue(sys.homed.mask, bit(idx)) && settings.axis[idx].max_travel < -0.0f) + target[idx] = max(min(target[idx], sys.work_envelope.max[idx]), sys.work_envelope.min[idx]); + } while(idx); + + return is_cartesian; +} + +void limits_init (void) +{ + hal.homing.get_feedrate = get_homing_rate; + grbl.check_travel_limits = check_travel_limits; + grbl.apply_jog_limits = apply_jog_limits; + grbl.home_machine = homing_cycle; +} diff --git a/machine_limits.h b/machine_limits.h index a30e44e..491bb13 100644 --- a/machine_limits.h +++ b/machine_limits.h @@ -33,6 +33,8 @@ typedef enum HomingMode_Pulloff } homing_mode_t; +void limits_init (void); + // Perform one portion of the homing cycle based on the input settings. status_code_t limits_go_home (axes_signals_t cycle); diff --git a/motion_control.c b/motion_control.c index 33b39da..c9d60b0 100644 --- a/motion_control.c +++ b/motion_control.c @@ -766,8 +766,8 @@ status_code_t mc_jog_execute (plan_line_data_t *pl_data, parser_block_t *gc_bloc pl_data->line_number = gc_block->values.n; if(settings.limits.flags.jog_soft_limited) - system_apply_jog_limits(gc_block->values.xyz); - else if (settings.limits.flags.soft_enabled && !system_check_travel_limits(gc_block->values.xyz)) + grbl.apply_jog_limits(gc_block->values.xyz, true); + else if (settings.limits.flags.soft_enabled && !grbl.check_travel_limits(gc_block->values.xyz, true)) return Status_TravelExceeded; // Valid jog command. Plan, set state, and execute. @@ -825,7 +825,7 @@ status_code_t mc_homing_cycle (axes_signals_t cycle) // Check and abort homing cycle, if hard limits are already enabled. Helps prevent problems // with machines with limits wired on both ends of travel to one limit pin. // TODO: Move the pin-specific LIMIT_BIT call to limits.c as a function. - if (settings.limits.flags.two_switches && hal.homing.get_state == hal.limits.get_state && limit_signals_merge(hal.limits.get_state()).value) { + if (settings.limits.flags.two_switches && hal.home_cap.a.mask == 0 && limit_signals_merge(hal.limits.get_state()).value) { mc_reset(); // Issue system reset and ensure spindle and coolant are shutdown. system_set_exec_alarm(Alarm_HardLimit); return Status_Unhandled; @@ -858,8 +858,6 @@ status_code_t mc_homing_cycle (axes_signals_t cycle) protocol_enqueue_realtime_command(CMD_STATUS_REPORT); // Force a status report and delay_sec(0.1f, DelayMode_Dwell); // delay a bit to get it sent (or perhaps wait a bit for a request?) #endif - hal.limits.enable(false, true); // Disable hard limits pin change register for cycle duration - // Turn off spindle and coolant (and update parser state) if(spindle_is_on()) gc_spindle_off(); @@ -890,7 +888,7 @@ status_code_t mc_homing_cycle (axes_signals_t cycle) // If hard limits feature enabled, re-enable hard limits pin change register after homing cycle. // NOTE: always call at end of homing regadless of setting, may be used to disable // sensorless homing or switch back to limit switches input (if different from homing switches) - hal.limits.enable(settings.limits.flags.hard_enabled, false); + hal.limits.enable(settings.limits.flags.hard_enabled, (axes_signals_t){0}); } if(cycle.mask) { diff --git a/motor_pins.h b/motor_pins.h index adb09bb..8bd50e3 100644 --- a/motor_pins.h +++ b/motor_pins.h @@ -865,6 +865,27 @@ #ifndef Z_LIMIT_BIT #define Z_LIMIT_BIT (1<=4 && !defined(A_ENABLE_BIT) +#if N_AXIS >= 4 && !defined(A_ENABLE_BIT) #define A_ENABLE_BIT 0 #endif -#if N_AXIS >=5 && !defined(B_ENABLE_BIT) +#if N_AXIS >= 5 && !defined(B_ENABLE_BIT) #define B_ENABLE_BIT 0 #endif #if N_AXIS >= 6 && !defined(C_ENABLE_BIT) @@ -987,8 +1008,8 @@ #define LIMIT_MASK_BASE (X_LIMIT_BIT|Y_LIMIT_BIT|LIMIT2_MASK) #define LIMIT_MASK_BASE_SUM (X_LIMIT_BIT+Y_LIMIT_BIT+LIMIT2_MASK_SUM) #else -#define LIMIT_MASK_BASE (X_LIMIT_BIT|Y_LIMIT_BIT|Z_LIMIT_BIT) -#define LIMIT_MASK_BASE_SUM (X_LIMIT_BIT+Y_LIMIT_BIT+Z_LIMIT_BIT) +#define LIMIT_MASK_BASE (X_LIMIT_BIT|Y_LIMIT_BIT|Z_LIMIT_BIT|X_LIMIT_BIT_MAX|Y_LIMIT_BIT_MAX|Z_LIMIT_BIT_MAX) +#define LIMIT_MASK_BASE_SUM (X_LIMIT_BIT+Y_LIMIT_BIT+Z_LIMIT_BIT+X_LIMIT_BIT_MAX+Y_LIMIT_BIT_MAX+Z_LIMIT_BIT_MAX) #endif #if N_AXIS == 3 @@ -1014,6 +1035,10 @@ #endif // LIMIT_MASK +#ifndef HOME_MASK +#define HOME_MASK 0 +#endif + #ifndef N_GANGED #define N_GANGED 0 #endif @@ -1114,4 +1139,50 @@ static limit_signals_t get_limits_cap (void) return limits; } +static home_signals_t get_home_cap (void) +{ + home_signals_t home = {0}; + +#if HOME_MASK + +#if X_HOME_BIT + home.primary.x = On; +#endif +#if Y_HOME_BIT + home.primary.y = On; +#endif +#if Z_HOME_BIT + home.primary.z = On; +#endif +#if A_HOME_BIT + home.primary.a = On; +#endif +#if B_HOME_BIT + home.primary.b = On; +#endif +#if C_HOME_BIT + home.primary.c = On; +#endif +#if U_HOME_BIT + home.primary.u = On; +#endif +#if V_HOME_BIT + home.primary.v = On; +#endif + +#if X2_HOME_BIT + home.secondary.x = On; +#endif +#if Y2_HOME_BIT + home.secondary.y = On; +#endif +#if Z2_HOME_BIT + home.secondary.z = On; +#endif + +#endif // HOME_MASK + + return home; +} + /*EOF*/ diff --git a/nuts_bolts.h b/nuts_bolts.h index fbb54bb..29f5ebe 100644 --- a/nuts_bolts.h +++ b/nuts_bolts.h @@ -152,7 +152,7 @@ typedef union { #pragma pack(push, 1) -//! \brief Limit switches struct, consists of four packed axes_signals_t structs. +//! \brief Limit switches struct, consists of four packed axes_signals_t structs in 32 bits. typedef struct { axes_signals_t min; //!< Min limit switches status, required. axes_signals_t max; //!< Max limit switches status, optional. @@ -160,6 +160,12 @@ typedef struct { axes_signals_t max2; //!< Secondary max limit switches status, optional (of no practical use?). } limit_signals_t; +//! \brief Home switches struct, consists of two packed axes_signals_t structs. +typedef struct { + axes_signals_t a; //!< Primary home switches status, optional. Limit signals are used for homing if not available. + axes_signals_t b; //!< Secondary home switch(es) status, required for auto squaring enabled axes if primary switches are available. +} home_signals_t; + #pragma pack(pop) typedef enum { diff --git a/report.c b/report.c index 3f0de1c..f59b8f6 100644 --- a/report.c +++ b/report.c @@ -2093,6 +2093,25 @@ status_code_t report_current_limit_state (sys_state_t state, char *args) return Status_OK; } +status_code_t report_current_home_signal_state (sys_state_t state, char *args) +{ + char *append = &buf[7]; + home_signals_t home = hal.homing.get_state(); + + strcpy(buf, "[HOMES:"); + + append = axis_signals_tostring(append, home.a); + *append++ = ','; + append = axis_signals_tostring(append, home.b); + + strcat(append, hal.home_cap.a.mask ? ":H" : ":L"); + + hal.stream.write(buf); + hal.stream.write("]" ASCII_EOL); + + return Status_OK; +} + // Prints spindle data (encoder pulse and index count, angular position). status_code_t report_spindle_data (sys_state_t state, char *args) { diff --git a/report.h b/report.h index 34fdde8..0df4729 100644 --- a/report.h +++ b/report.h @@ -90,6 +90,7 @@ status_code_t report_setting_description (settings_format_t format, setting_id_t status_code_t report_last_signals_event (sys_state_t state, char *args); status_code_t report_current_limit_state (sys_state_t state, char *args); +status_code_t report_current_home_signal_state (sys_state_t state, char *args); // Prints spindle data (encoder pulse and index count, angular position). status_code_t report_spindle_data (sys_state_t state, char *args); diff --git a/settings.c b/settings.c index 9af412f..5332ca2 100644 --- a/settings.c +++ b/settings.c @@ -724,11 +724,7 @@ PROGMEM static const setting_descr_t setting_descr[] = { { Setting_PositionIGain, "" }, { Setting_PositionDGain, "" }, { Setting_PositionIMaxError, "Spindle sync PID max integrator error." }, -#if DELTA_ROBOT - { Setting_AxisStepsPerMM, "Travel resolution in steps per revolution." }, -#else { Setting_AxisStepsPerMM, "Travel resolution in steps per millimeter." }, -#endif { (setting_id_t)(Setting_AxisStepsPerMM + 1), "Travel resolution in steps per degree." }, // "Hack" to get correct description for rotary axes { Setting_AxisMaxRate, "Maximum rate. Used as G0 rapid rate." }, { Setting_AxisAcceleration, "Acceleration. Used for motion planning to not exceed motor torque and lose steps." }, @@ -1043,7 +1039,7 @@ static status_code_t set_hard_limits_enable (setting_id_t id, uint_fast16_t int_ #if COMPATIBILITY_LEVEL <= 1 settings.limits.flags.check_at_init = bit_istrue(int_value, bit(1)); #endif - hal.limits.enable(settings.limits.flags.hard_enabled, false); // Change immediately. NOTE: Nice to have but could be problematic later. + hal.limits.enable(settings.limits.flags.hard_enabled, (axes_signals_t){0}); // Change immediately. NOTE: Nice to have but could be problematic later. return Status_OK; } @@ -1219,6 +1215,13 @@ static status_code_t set_tool_restore_pos (setting_id_t id, uint_fast16_t int_va return Status_OK; } +static inline void set_axis_unit (const setting_detail_t *setting, const char *unit) +{ + // TODO: add length check + if(unit) + strcpy((char *)setting->unit, unit); +} + #if N_AXIS > 3 static status_code_t set_rotational_axes (setting_id_t id, uint_fast16_t int_value) @@ -1233,32 +1236,36 @@ static inline bool axis_is_rotary (uint_fast8_t axis_idx) return bit_istrue(settings.steppers.is_rotational.mask, bit(axis_idx)); } -static void set_axis_setting_unit (const setting_detail_t *setting, uint_fast8_t axis_idx) +static const char *set_axis_setting_unit (setting_id_t setting_id, uint_fast8_t axis_idx) { + char *unit = NULL; + bool is_rotary = axis_is_rotary(axis_idx); - switch(setting->id) { + switch(setting_id) { case Setting_AxisStepsPerMM: - strcpy((char *)setting->unit, is_rotary ? "step/deg" : "step/mm"); + unit = is_rotary ? "step/deg" : "step/mm"; break; case Setting_AxisMaxRate: - strcpy((char *)setting->unit, is_rotary ? "deg/min" : "mm/min"); + unit = is_rotary ? "deg/min" : "mm/min"; break; case Setting_AxisAcceleration: - strcpy((char *)setting->unit, is_rotary ? "deg/sec^2" : "mm/sec^2"); + unit = is_rotary ? "deg/sec^2" : "mm/sec^2"; break; case Setting_AxisMaxTravel: case Setting_AxisBacklash: - strcpy((char *)setting->unit, is_rotary ? "deg" : "mm"); + unit = is_rotary ? "deg" : "mm"; break; default: break; } + + return unit; } #endif @@ -2178,9 +2185,10 @@ bool settings_iterator (const setting_detail_t *setting, setting_output_ptr call uint_fast8_t axis_idx = 0; for(axis_idx = 0; axis_idx < N_AXIS; axis_idx++) { -#if N_AXIS > 3 - set_axis_setting_unit(setting, axis_idx); -#endif + + if(grbl.on_set_axis_setting_unit) + set_axis_unit(setting, grbl.on_set_axis_setting_unit(setting->id, axis_idx)); + if(callback(setting, axis_idx, data)) ok = true; } @@ -2205,14 +2213,16 @@ const setting_detail_t *setting_get_details (setting_id_t id, setting_details_t do { for(idx = 0; idx < details->n_settings; idx++) { if(details->settings[idx].id == id && is_available(&details->settings[idx])) { -#if N_AXIS > 3 - if(details->settings[idx].group == Group_Axis0) - set_axis_setting_unit(&details->settings[idx], offset); -#endif + + if(details->settings[idx].group == Group_Axis0 && grbl.on_set_axis_setting_unit) + set_axis_unit(&details->settings[idx], grbl.on_set_axis_setting_unit(details->settings[idx].id, offset)); + if(offset && details->iterator == NULL && offset >= (details->settings[idx].group == Group_Encoder0 ? hal.encoder.get_n_encoders() : N_AXIS)) return NULL; + if(set) *set = details; + return &details->settings[idx]; } } @@ -2227,24 +2237,27 @@ const char *setting_get_description (setting_id_t id) #ifndef NO_SETTINGS_DESCRIPTIONS - uint_fast16_t idx; - setting_details_t *settings = settings_get_details(); - const setting_detail_t *setting = setting_get_details(id, NULL); + if(grbl.on_setting_get_description == NULL || (description = grbl.on_setting_get_description(id)) == NULL) { - if(setting) do { - if(settings->descriptions) { - idx = settings->n_descriptions; - do { - if(settings->descriptions[--idx].id == setting->id) { -#if N_AXIS > 3 - if(setting->id == Setting_AxisStepsPerMM && axis_is_rotary(id - setting->id)) - idx++; -#endif - description = settings->descriptions[idx].description; - } - } while(idx && description == NULL); - } - } while(description == NULL && (settings = settings->next)); + uint_fast16_t idx; + setting_details_t *settings = settings_get_details(); + const setting_detail_t *setting = setting_get_details(id, NULL); + + if(setting) do { + if(settings->descriptions) { + idx = settings->n_descriptions; + do { + if(settings->descriptions[--idx].id == setting->id) { + #if N_AXIS > 3 + if(setting->id == Setting_AxisStepsPerMM && axis_is_rotary(id - setting->id)) + idx++; + #endif + description = settings->descriptions[idx].description; + } + } while(idx && description == NULL); + } + } while(description == NULL && (settings = settings->next)); + } #endif @@ -2651,6 +2664,8 @@ status_code_t settings_store_setting (setting_id_t id, char *svalue) if(status == Status_OK) { + xbar_set_homing_source(); + if(set->save) set->save(); @@ -2693,6 +2708,11 @@ void settings_init (void) { settings_changed_flags_t changed = {0}; +#if N_AXIS > 3 + if(grbl.on_set_axis_setting_unit == NULL) + grbl.on_set_axis_setting_unit = set_axis_setting_unit; +#endif + if(!read_global_settings()) { settings_restore_t settings = settings_all; @@ -2727,6 +2747,8 @@ void settings_init (void) hal.probe.configure(false, false); } + xbar_set_homing_source(); + if(spindle_get_count() == 0) spindle_add_null(); diff --git a/settings.h b/settings.h index 26084d6..57cab55 100644 --- a/settings.h +++ b/settings.h @@ -970,5 +970,6 @@ bool setting_is_list (const setting_detail_t *setting); bool setting_is_integer (const setting_detail_t *setting); void setting_remove_elements (setting_id_t id, uint32_t mask); bool settings_add_spindle_type (const char *type); +limit_signals_t settings_get_homing_source (void); #endif diff --git a/system.c b/system.c index 2146769..a660d9f 100644 --- a/system.c +++ b/system.c @@ -242,6 +242,7 @@ PROGMEM static const sys_command_t sys_commands[] = { #ifdef V_AXIS { "HV", home_v }, #endif + { "HSS", report_current_home_signal_state, { .noargs = On, .allow_blocking = On } }, { "HELP", output_help, { .allow_blocking = On } }, { "SPINDLES", output_spindles }, { "SLP", enter_sleep, { .noargs = On } }, @@ -294,6 +295,7 @@ void system_command_help (void) hal.stream.write("$H - home configured axes" ASCII_EOL); if(settings.homing.flags.single_axis_commands) hal.stream.write("$H - home single axis" ASCII_EOL); + hal.stream.write("$HSS - report homing switches status" ASCII_EOL); hal.stream.write("$X - unlock machine" ASCII_EOL); hal.stream.write("$SLP - enter sleep mode" ASCII_EOL); hal.stream.write("$HELP - output help topics" ASCII_EOL); @@ -1023,33 +1025,6 @@ bool system_xy_at_fixture (coord_system_id_t id, float tolerance) return ok; } -// Checks and reports if target array exceeds machine travel limits. Returns false if check failed. -bool system_check_travel_limits (float *target) -{ - bool failed = false; - uint_fast8_t idx = N_AXIS; - - if(sys.homed.mask) do { - idx--; - if(bit_istrue(sys.homed.mask, bit(idx)) && settings.axis[idx].max_travel < -0.0f) - failed = target[idx] < sys.work_envelope.min[idx] || target[idx] > sys.work_envelope.max[idx]; - } while(!failed && idx); - - return !failed; -} - -// Limits jog commands to be within machine limits, homed axes only. -void system_apply_jog_limits (float *target) -{ - uint_fast8_t idx = N_AXIS; - - if(sys.homed.mask) do { - idx--; - if(bit_istrue(sys.homed.mask, bit(idx)) && settings.axis[idx].max_travel < -0.0f) - target[idx] = max(min(target[idx], sys.work_envelope.max[idx]), sys.work_envelope.min[idx]); - } while(idx); -} - void system_raise_alarm (alarm_code_t alarm) { if(state_get() == STATE_HOMING && !(sys.rt_exec_state & EXEC_RESET)) diff --git a/system.h b/system.h index d9253a5..a6000e1 100644 --- a/system.h +++ b/system.h @@ -353,12 +353,6 @@ void system_convert_array_steps_to_mpos (float *position, int32_t *steps); //! Checks if XY position is within coordinate system XY with given tolerance. bool system_xy_at_fixture (coord_system_id_t id, float tolerance); -//! Checks and reports if target array exceeds machine travel limits. -bool system_check_travel_limits (float *target); - -//! Checks and limit jog commands to within machine travel limits. -void system_apply_jog_limits (float *target); - //! Raise and report alarm state void system_raise_alarm (alarm_code_t alarm);