diff --git a/CHANGELOG.md b/CHANGELOG.md index febf2fa88..bb0edb1b5 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -8,6 +8,55 @@ # Changelog +## [1.8.8] - 03-03-2024 + +## Contributors +[@lonelycorn](https://github.com/lonelycorn) - modified mcumap macros of ESP32 to improve support for ESP32 family (#649) and removed duplicated servo variables for ESP32 (#648) +[@ademenev](https://github.com/ademenev) - added kinematics option for MP Scara (#645) + +### Added + +- Fs page update endpoint (#612) +- added option for rotational axis work always in relative distances (#624) +- STM32 NucleoF411RE boardmap with CNC Shield V3 (#628) +- added option to enable translated pins names status print (#634) +- added kinematics option for MP Scara (#645) +- added aditional Grbl emulation level to prevent miss detection of senders (#650) +- added option to do limit detection at the step ISR (#652) + +### Changed + +- allow execution of main loop events with HOLD condition active (#633) +- modified extended settings event hooks to be separated from other overriding events and propagations methods (#635) (#637) (#641) +- allow detached ports to keep or not an internal buffer (#639) +- cross architecture definition of NVM_STORAGE_SIZE and setting (#643) +- moved spindle restore logic to planner override (#647) +- modified mcumap macros of ESP32 to improve support for ESP32 family (#649) (#654) +- modified endpoints to support handling of wildcard terminators (#655) +- on command error now also the parser is forced to sync with other sub-systems (#657) +- modified behavior of Cycle Start/Resume button to execute only once per press (#657) + +### Fixed + +- fixed extensions settings event handling that prevented extended settings to be saved (#615) +- fixed STM32F4 compilation error when I2C HW was defined (#615) +- fixed program stall while waiting for timeout condition inside an ISR (#619) +- fixed STM32F4 SPI configuration AFIO fixed (#622) +- fixed range function for Plasma THC (#627) +- fixed STM32F4 APB registers of timers in the mcumap (#629) +- fixed compilation error when tool count was set to 0 (#632) +- fixed realtime command spindle toggle control over the tool (#631) +- fixed spindle restart message spawning (#636) +- fixed uart2 detach from main protocol typo in multiple boards (#638) +- fixed reset command parsing and early execution (#642) +- fixed spindle stop/restore after cancel a jog (#644) +- fixed dwell/delay execute even after a reset occured (#646) +- removed duplicated servo variables for ESP32 (#648) +- fixed low speed clock options for STM32F1 (#653) +- fixed STM32 I2C stop bit logic to prevent trail of pulses at the end of a read operation (#656) +- fixed pending jog motions after jog cancel (#657) +- fixed interpolator acceleration calculations to prevent ultra thin time sampling windows (#657) + ## [1.8.7] - 03-02-2024 ## Contributors diff --git a/uCNC/boardmap_overrides.h b/uCNC/boardmap_overrides.h index e38625540..39de0269c 100644 --- a/uCNC/boardmap_overrides.h +++ b/uCNC/boardmap_overrides.h @@ -1,4 +1,4 @@ -//boardmap override dummy file +// boardmap override dummy file #ifndef BOARDMAP_OVERRIDES_H #define BOARDMAP_OVERRIDES_H diff --git a/uCNC/cnc_config.h b/uCNC/cnc_config.h index 47d01e371..c27f06b10 100644 --- a/uCNC/cnc_config.h +++ b/uCNC/cnc_config.h @@ -10,11 +10,11 @@ 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. + PARTICULAR PURPOSE. See the GNU General Public License for more details. */ #ifndef CNC_CONFIG_H diff --git a/uCNC/cnc_hal_config.h b/uCNC/cnc_hal_config.h index 0b8ac505d..116c8ed27 100644 --- a/uCNC/cnc_hal_config.h +++ b/uCNC/cnc_hal_config.h @@ -112,8 +112,8 @@ extern "C" * Enable this option if you want the rotation axis to work in relative distance mode only * This will mean that no matter if the machine is working in absolute (G90) or relative (G91) coordinates * the rotational axis will always calculate the motion in relative distance mode - * -*/ + * + */ // #define AXIS_A_FORCE_RELATIVE_MODE // #define AXIS_B_FORCE_RELATIVE_MODE // #define AXIS_C_FORCE_RELATIVE_MODE diff --git a/uCNC/cnc_hal_overrides.h b/uCNC/cnc_hal_overrides.h index cd09a4f01..8e32cf30d 100644 --- a/uCNC/cnc_hal_overrides.h +++ b/uCNC/cnc_hal_overrides.h @@ -1,4 +1,4 @@ -//boardmap override dummy file +// boardmap override dummy file #ifndef CNC_HAL_OVERRIDES_H #define CNC_HAL_OVERRIDES_H diff --git a/uCNC/src/cnc.h b/uCNC/src/cnc.h index b7612abef..0751a95eb 100644 --- a/uCNC/src/cnc.h +++ b/uCNC/src/cnc.h @@ -53,40 +53,40 @@ extern "C" /** * Flags and state changes - * + * * EXEC_KILL * Set by cnc_alarm. - * Cleared by reset or unlock depending on the the alarm priority. Cannot be cleared if ESTOP is pressed. - * + * Cleared by reset or unlock depending on the the alarm priority. Cannot be cleared if ESTOP is pressed. + * * EXEC_LIMITS - * Set when at a transition of a limit switch from inactive to the active state. + * Set when at a transition of a limit switch from inactive to the active state. * Cleared by reset or unlock. Not affected by the limit switch state. - * + * * EXEC_UNHOMED * Set when the interpolator is abruptly stopped causing the position to be lost. * Cleared by homing or unlock. - * + * * EXEC_DOOR * Set with when the safety door pin is active or the safety door command is called. * Cleared by cycle resume, unlock or reset. If the door is opened it will remain active - * + * */ // current cnc states (multiple can be active/overlapped at the same time) -#define EXEC_IDLE 0 // All flags cleared -#define EXEC_RUN 1 // Motions are being executed -#define EXEC_HOLD 2 // Feed hold is active -#define EXEC_JOG 4 // Jogging in execution -#define EXEC_HOMING 8 // Homing in execution -#define EXEC_DOOR 16 // Safety door open -#define EXEC_UNHOMED 32 // Machine is not homed or lost position due to abrupt stop -#define EXEC_LIMITS 64 // Limits hit -#define EXEC_KILL 128 // Emergency stop -#define EXEC_HOMING_HIT (EXEC_HOMING | EXEC_LIMITS) // Limit switch is active during a homing motion -#define EXEC_INTERLOCKING_FAIL (EXEC_LIMITS | EXEC_KILL) // Interlocking check failed -#define EXEC_ALARM (EXEC_UNHOMED | EXEC_INTERLOCKING_FAIL) // System alarms -#define EXEC_RESET_LOCKED (EXEC_ALARM | EXEC_DOOR | EXEC_HOLD) // System reset locked -#define EXEC_GCODE_LOCKED (EXEC_ALARM | EXEC_DOOR | EXEC_JOG) // Gcode is locked by an alarm or any special motion state -#define EXEC_ALLACTIVE 255 // All states +#define EXEC_IDLE 0 // All flags cleared +#define EXEC_RUN 1 // Motions are being executed +#define EXEC_HOLD 2 // Feed hold is active +#define EXEC_JOG 4 // Jogging in execution +#define EXEC_HOMING 8 // Homing in execution +#define EXEC_DOOR 16 // Safety door open +#define EXEC_UNHOMED 32 // Machine is not homed or lost position due to abrupt stop +#define EXEC_LIMITS 64 // Limits hit +#define EXEC_KILL 128 // Emergency stop +#define EXEC_HOMING_HIT (EXEC_HOMING | EXEC_LIMITS) // Limit switch is active during a homing motion +#define EXEC_INTERLOCKING_FAIL (EXEC_LIMITS | EXEC_KILL) // Interlocking check failed +#define EXEC_ALARM (EXEC_UNHOMED | EXEC_INTERLOCKING_FAIL) // System alarms +#define EXEC_RESET_LOCKED (EXEC_ALARM | EXEC_DOOR | EXEC_HOLD) // System reset locked +#define EXEC_GCODE_LOCKED (EXEC_ALARM | EXEC_DOOR | EXEC_JOG) // Gcode is locked by an alarm or any special motion state +#define EXEC_ALLACTIVE 255 // All states // creates a set of helper masks used to configure the controller #define ESTOP_MASK 1 @@ -99,14 +99,14 @@ extern "C" /** * Basic step and dir IO masks * STEPS DIRS and LIMITS can be combined to form MULTI AXIS/LIMITS combinations - * + * * Usually (depends on the kinematic) STEP0 is assigned to AXIS X, STEP1 is assigned to AXIS Y, etc.. * But STEP0 can be formed by multiple STEPPERS (for example STEPPER0, STEPPER5, STEPPER6 and STEPPER7) - * + * * STEP0_MASK can then be formed by a combinations of stepper IO masks like this - * + * * #define STEP0_MASK (STEPPER0_IO_MASK | STEPPER5_IO_MASK | STEPPER6_IO_MASK | STEPPER7_IO_MASK) - * + * * For auto-squaring LIMITS should also match this STEPx mask by merging all combined limits to form a multi-switch limit * **/ #define STEP_UNDEF_IO_MASK 0 diff --git a/uCNC/src/cnc_build.h b/uCNC/src/cnc_build.h index 7827704b1..9cdf322be 100644 --- a/uCNC/src/cnc_build.h +++ b/uCNC/src/cnc_build.h @@ -25,7 +25,7 @@ extern "C" #endif #define CNC_MAJOR_MINOR_VERSION "1.8" -#define CNC_PATCH_VERSION ".7" +#define CNC_PATCH_VERSION ".8" #define CNC_VERSION CNC_MAJOR_MINOR_VERSION CNC_PATCH_VERSION diff --git a/uCNC/src/cnc_hal_config_helper.h b/uCNC/src/cnc_hal_config_helper.h index 81aa635c5..e5dbdc273 100644 --- a/uCNC/src/cnc_hal_config_helper.h +++ b/uCNC/src/cnc_hal_config_helper.h @@ -53,9 +53,9 @@ extern "C" // machine tools configurations #include "hal/tools/tool.h" //configures the kinematics for the cnc machine // final HAL configurations -#include "../cnc_hal_config.h" //inicializes the HAL hardcoded connections +#include "../cnc_hal_config.h" //inicializes the HAL hardcoded connections #include "../cnc_hal_overrides.h" //config override file -#include "modules/ic74hc595.h" // io extender +#include "modules/ic74hc595.h" // io extender /** * diff --git a/uCNC/src/core/interpolator.h b/uCNC/src/core/interpolator.h index d85fbae47..38ad680bb 100644 --- a/uCNC/src/core/interpolator.h +++ b/uCNC/src/core/interpolator.h @@ -95,7 +95,7 @@ extern "C" float itp_get_rt_feed(void); bool itp_is_empty(void); uint8_t itp_sync(void); - itp_segment_t* itp_get_rt_segment(); + itp_segment_t *itp_get_rt_segment(); uint8_t itp_set_step_mode(uint8_t mode); void itp_sync_spindle(void); diff --git a/uCNC/src/core/io_control.h b/uCNC/src/core/io_control.h index 818e90ec9..82b323029 100644 --- a/uCNC/src/core/io_control.h +++ b/uCNC/src/core/io_control.h @@ -38,10 +38,10 @@ extern "C" * **/ #define io_config_input(pin) io_hal_config_input(pin) -#define io_config_pullup(pin) io_hal_config_pullup(pin) -#define io_get_input(pin) io_hal_get_input(pin) -#define io_config_analog(pin) io_hal_config_analog(pin) -#define io_get_analog(pin) io_hal_get_analog(pin) +#define io_config_pullup(pin) io_hal_config_pullup(pin) +#define io_get_input(pin) io_hal_get_input(pin) +#define io_config_analog(pin) io_hal_config_analog(pin) +#define io_get_analog(pin) io_hal_get_analog(pin) #define io_config_output(pin) io_hal_config_output(pin) #define io_set_output(pin) io_hal_set_output(pin) @@ -56,10 +56,10 @@ extern "C" MCU_CALLBACK void io_soft_pwm_update(void); #endif - // inputs - #ifdef ENABLE_MULTI_STEP_HOMING +// inputs +#ifdef ENABLE_MULTI_STEP_HOMING void io_lock_limits(uint8_t limitmask); - #endif +#endif void io_invert_limits(uint8_t limitmask); uint8_t io_get_limits(void); uint8_t io_get_controls(void); diff --git a/uCNC/src/core/parser.h b/uCNC/src/core/parser.h index 860636d8b..c99ee4ffa 100644 --- a/uCNC/src/core/parser.h +++ b/uCNC/src/core/parser.h @@ -116,11 +116,11 @@ extern "C" #define PARSER_PARAM_SIZE (sizeof(float) * AXIS_COUNT) // parser parameters array size #define PARSER_PARAM_ADDR_OFFSET (PARSER_PARAM_SIZE + 1) // parser parameters array size + 1 crc byte -#define G28HOME COORD_SYS_COUNT // G28 index -#define G30HOME COORD_SYS_COUNT + 1 // G30 index -#define G92OFFSET COORD_SYS_COUNT + 2 // G92 index +#define G28HOME COORD_SYS_COUNT // G28 index +#define G30HOME COORD_SYS_COUNT + 1 // G30 index +#define G92OFFSET COORD_SYS_COUNT + 2 // G92 index -#define PARSER_CORDSYS_ADDRESS SETTINGS_PARSER_PARAMETERS_ADDRESS_OFFSET // 1st coordinate system offset eeprom address (G54) +#define PARSER_CORDSYS_ADDRESS SETTINGS_PARSER_PARAMETERS_ADDRESS_OFFSET // 1st coordinate system offset eeprom address (G54) #define G28ADDRESS (SETTINGS_PARSER_PARAMETERS_ADDRESS_OFFSET + (PARSER_PARAM_ADDR_OFFSET * G28HOME)) // G28 coordinate offset eeprom address #define G30ADDRESS (SETTINGS_PARSER_PARAMETERS_ADDRESS_OFFSET + (PARSER_PARAM_ADDR_OFFSET * G30HOME)) // G28 coordinate offset eeprom address #ifdef G92_STORE_NONVOLATILE diff --git a/uCNC/src/hal/boards/avr/boardmap_rambo14.h b/uCNC/src/hal/boards/avr/boardmap_rambo14.h index c2af11a1d..04707e702 100644 --- a/uCNC/src/hal/boards/avr/boardmap_rambo14.h +++ b/uCNC/src/hal/boards/avr/boardmap_rambo14.h @@ -61,19 +61,19 @@ extern "C" // Setup limit pins -#define LIMIT_X_BIT 6 // assigns LIMIT_X pin +#define LIMIT_X_BIT 6 // assigns LIMIT_X pin #define LIMIT_X_PORT B // assigns LIMIT_X port -#define LIMIT_X_ISR 0 // assigns LIMIT_X ISR +#define LIMIT_X_ISR 0 // assigns LIMIT_X ISR #define LIMIT_X2_BIT 2 // assigns LIMIT_X pin #define LIMIT_X2_PORT A // assigns LIMIT_X port -#define LIMIT_Y_BIT 5 // assigns LIMIT_Y pin +#define LIMIT_Y_BIT 5 // assigns LIMIT_Y pin #define LIMIT_Y_PORT B // assigns LIMIT_Y port -#define LIMIT_Y_ISR 0 // assigns LIMIT_Y ISR +#define LIMIT_Y_ISR 0 // assigns LIMIT_Y ISR #define LIMIT_Y2_BIT 1 // assigns LIMIT_Y pin #define LIMIT_Y2_PORT A // assigns LIMIT_Y port -#define LIMIT_Z_BIT 4 // assigns LIMIT_Z pin +#define LIMIT_Z_BIT 4 // assigns LIMIT_Z pin #define LIMIT_Z_PORT B // assigns LIMIT_Z port -#define LIMIT_Z_ISR 0 // assigns LIMIT_Z ISR +#define LIMIT_Z_ISR 0 // assigns LIMIT_Z ISR // Setup probe pin #define PROBE_BIT 7 @@ -96,12 +96,12 @@ extern "C" // Setup generic IO Pins // Functionalities are set in config.h file -//#define DOUT0_BIT 5 -//#define DOUT0_PORT B -//#define DOUT1_BIT 0 +// #define DOUT0_BIT 5 +// #define DOUT0_PORT B +// #define DOUT1_BIT 0 // define DOUT1_PORT B -//#define DOUT2_BIT 3 -//#define DOUT2_PORT C +// #define DOUT2_BIT 3 +// #define DOUT2_PORT C // Stepper enable pin. For Grbl on Uno board a single pin is used #define STEP0_EN_BIT 7 @@ -117,10 +117,10 @@ extern "C" // Setup the Step Timer used has the heartbeat for µCNC // Timer 1 is used by default - //#define ITP_TIMER 1 + // #define ITP_TIMER 1 // Setup the RTC Timer used by µCNC to provide an (mostly) accurate time base for all time dependent functions // Timer 0 is set by default - //#define RTC_TIMER 0 + // #define RTC_TIMER 0 // blink led #define DOUT31_BIT 7 diff --git a/uCNC/src/hal/boards/avr/boardmap_ramps14.h b/uCNC/src/hal/boards/avr/boardmap_ramps14.h index 6c98afd8a..6fd7f7372 100644 --- a/uCNC/src/hal/boards/avr/boardmap_ramps14.h +++ b/uCNC/src/hal/boards/avr/boardmap_ramps14.h @@ -62,19 +62,19 @@ extern "C" // Setup limit pins -#define LIMIT_X_BIT 5 // assigns LIMIT_X pin +#define LIMIT_X_BIT 5 // assigns LIMIT_X pin #define LIMIT_X_PORT E // assigns LIMIT_X port #define LIMIT_X_ISR -6 // assigns LIMIT_X ISR #define LIMIT_X2_BIT 4 // assigns LIMIT_X2 pin #define LIMIT_X2_PORT E // assigns LIMIT_X2 port #define LIMIT_X2_ISR -5 // assigns LIMIT_X2 ISR -#define LIMIT_Y_BIT 1 // assigns LIMIT_Y pin +#define LIMIT_Y_BIT 1 // assigns LIMIT_Y pin #define LIMIT_Y_PORT J // assigns LIMIT_Y port -#define LIMIT_Y_ISR 1 // assigns LIMIT_Y ISR +#define LIMIT_Y_ISR 1 // assigns LIMIT_Y ISR #define LIMIT_Y2_BIT 0 // assigns LIMIT_Y2 pin #define LIMIT_Y2_PORT J // assigns LIMIT_Y2 port #define LIMIT_Y2_ISR 1 // assigns LIMIT_Y2 ISR -#define LIMIT_Z_BIT 3 // assigns LIMIT_Z pin +#define LIMIT_Z_BIT 3 // assigns LIMIT_Z pin #define LIMIT_Z_PORT D // assigns LIMIT_Z port #define LIMIT_Z_ISR -4 // assigns LIMIT_Z ISR @@ -129,10 +129,10 @@ extern "C" // Setup the Step Timer used has the heartbeat for µCNC // Timer 1 is used by default - //#define ITP_TIMER 1 + // #define ITP_TIMER 1 // Setup the RTC Timer used by µCNC to provide an (mostly) accurate time base for all time dependent functions // Timer 0 is set by default - //#define RTC_TIMER 0 + // #define RTC_TIMER 0 // TMC0 UART #define DOUT20_BIT 1 @@ -206,53 +206,53 @@ extern "C" #define SPI_CS_BIT 0 #define SPI_CS_PORT B #define SPI_FREQ 100000UL -//software SPI -// #define DOUT29_BIT 2 -// #define DOUT29_PORT B -// #define DIN29_BIT 3 -// #define DIN29_PORT B -// #define DOUT30_BIT 1 -// #define DOUT30_PORT B -//sd card detect +// software SPI +// #define DOUT29_BIT 2 +// #define DOUT29_PORT B +// #define DIN29_BIT 3 +// #define DIN29_PORT B +// #define DOUT30_BIT 1 +// #define DOUT30_PORT B +// sd card detect #define DIN19_BIT 0 #define DIN19_PORT L #define DIN19_PULLUP -//pins for smart adapter -//clk +// pins for smart adapter +// clk #define DOUT4_BIT 1 #define DOUT4_PORT A -//data +// data #define DOUT5_BIT 0 #define DOUT5_PORT H -//cs +// cs #define DOUT6_BIT 1 #define DOUT6_PORT H -//beep +// beep #define DOUT7_BIT 0 #define DOUT7_PORT C -//enc btn +// enc btn #define DIN16_BIT 2 #define DIN16_PORT C #define DIN16_PULLUP -//enc 1 +// enc 1 #define DIN17_BIT 4 #define DIN17_PORT C #define DIN17_PULLUP -//enc 2 +// enc 2 #define DIN18_BIT 6 #define DIN18_PORT C #define DIN18_PULLUP #define ONESHOT_TIMER 4 -// #define RX2_BIT 0 -// #define TX2_BIT 1 -// #define RX2_PORT H -// #define TX2_PORT H -// #define RX2_PULLUP -// // only uncomment this if other port other then 0 is used -// #define UART2_PORT 2 + // #define RX2_BIT 0 + // #define TX2_BIT 1 + // #define RX2_PORT H + // #define TX2_PORT H + // #define RX2_PULLUP + // // only uncomment this if other port other then 0 is used + // #define UART2_PORT 2 #ifdef __cplusplus } diff --git a/uCNC/src/hal/boards/avr/boardmap_uno.h b/uCNC/src/hal/boards/avr/boardmap_uno.h index 79d0fdf84..c542e6c6e 100644 --- a/uCNC/src/hal/boards/avr/boardmap_uno.h +++ b/uCNC/src/hal/boards/avr/boardmap_uno.h @@ -52,20 +52,20 @@ extern "C" #define DIR0_PORT D // assigns DIR0 port // Setup limit pins -#define LIMIT_Z_BIT 4 // assigns LIMIT_Z pin +#define LIMIT_Z_BIT 4 // assigns LIMIT_Z pin #define LIMIT_Z_PORT B // assigns LIMIT_Z port -#define LIMIT_Z_ISR 0 // assigns LIMIT_Z ISR - // #define LIMIT_Y2_BIT 4 //Z and second Y limit share the pin - // #define LIMIT_Y2_PORT B //Z and second Y limit share the pin - // #define LIMIT_Y2_ISR 0 //Z and second Y limit share the pin +#define LIMIT_Z_ISR 0 // assigns LIMIT_Z ISR + // #define LIMIT_Y2_BIT 4 //Z and second Y limit share the pin + // #define LIMIT_Y2_PORT B //Z and second Y limit share the pin + // #define LIMIT_Y2_ISR 0 //Z and second Y limit share the pin -#define LIMIT_Y_BIT 2 // assigns LIMIT_Y pin +#define LIMIT_Y_BIT 2 // assigns LIMIT_Y pin #define LIMIT_Y_PORT B // assigns LIMIT_Y port -#define LIMIT_Y_ISR 0 // assigns LIMIT_Y ISR +#define LIMIT_Y_ISR 0 // assigns LIMIT_Y ISR -#define LIMIT_X_BIT 1 // assigns LIMIT_X pin +#define LIMIT_X_BIT 1 // assigns LIMIT_X pin #define LIMIT_X_PORT B // assigns LIMIT_X port -#define LIMIT_X_ISR 0 // assigns LIMIT_X ISR +#define LIMIT_X_ISR 0 // assigns LIMIT_X ISR // Setup probe pin #define PROBE_BIT 5 @@ -140,9 +140,9 @@ extern "C" #define ONESHOT_TIMER 2 /** - * + * * These are some paramaters needed to reduce code size for the UNO board - * + * * **/ // reduces RAM usage a bit to prevent hardware resets #ifndef PLANNER_BUFFER_SIZE diff --git a/uCNC/src/hal/boards/avr/boardmap_uno_shield_v3.h b/uCNC/src/hal/boards/avr/boardmap_uno_shield_v3.h index 37ff14463..04d8a8a62 100644 --- a/uCNC/src/hal/boards/avr/boardmap_uno_shield_v3.h +++ b/uCNC/src/hal/boards/avr/boardmap_uno_shield_v3.h @@ -30,7 +30,7 @@ extern "C" #include "boardmap_uno.h" -//swap limit z and replace pwm by spin enable pin +// swap limit z and replace pwm by spin enable pin #ifdef LIMIT_Z_BIT #undef LIMIT_Z_BIT #endif @@ -51,9 +51,9 @@ extern "C" #endif // Grbl 0.8 limit z -#define LIMIT_Z_BIT 3 // assigns LIMIT_Z pin +#define LIMIT_Z_BIT 3 // assigns LIMIT_Z pin #define LIMIT_Z_PORT B // assigns LIMIT_Z port -#define LIMIT_Z_ISR 0 // assigns LIMIT_Z ISR +#define LIMIT_Z_ISR 0 // assigns LIMIT_Z ISR // spindle en #define DOUT1_BIT 4 diff --git a/uCNC/src/hal/boards/esp32/boardmap_esp32_shield_v3.h b/uCNC/src/hal/boards/esp32/boardmap_esp32_shield_v3.h index 6e6106d94..9ab812342 100644 --- a/uCNC/src/hal/boards/esp32/boardmap_esp32_shield_v3.h +++ b/uCNC/src/hal/boards/esp32/boardmap_esp32_shield_v3.h @@ -30,7 +30,7 @@ extern "C" #include "boardmap_wemos_d1_r32.h" -//swap limit z and replace pwm by spin enable pin +// swap limit z and replace pwm by spin enable pin #ifdef LIMIT_Z_BIT #undef LIMIT_Z_BIT #endif @@ -39,7 +39,7 @@ extern "C" #endif // Grbl 0.8 limit z -#define LIMIT_Z_BIT 23 // assigns LIMIT_Z pin +#define LIMIT_Z_BIT 23 // assigns LIMIT_Z pin // Grbl 0.8 spindle en #define PWM0_BIT 19 // assigns PWM0 pin diff --git a/uCNC/src/hal/boards/esp32/boardmap_mks_dlc32.h b/uCNC/src/hal/boards/esp32/boardmap_mks_dlc32.h index 12a104f97..f9090d303 100644 --- a/uCNC/src/hal/boards/esp32/boardmap_mks_dlc32.h +++ b/uCNC/src/hal/boards/esp32/boardmap_mks_dlc32.h @@ -29,19 +29,19 @@ extern "C" #endif // Setup limit pins -#define LIMIT_Z_BIT 34 // assigns LIMIT_Z pin +#define LIMIT_Z_BIT 34 // assigns LIMIT_Z pin // #define LIMIT_Z_ISR // assigns LIMIT_Z ISR -#define LIMIT_Y_BIT 35 // assigns LIMIT_Y pin +#define LIMIT_Y_BIT 35 // assigns LIMIT_Y pin // #define LIMIT_Y_ISR // assigns LIMIT_Y ISR -#define LIMIT_X_BIT 36 // assigns LIMIT_X pin +#define LIMIT_X_BIT 36 // assigns LIMIT_X pin // #define LIMIT_X_ISR // assigns LIMIT_X ISR // Setup com pins #define RX_BIT 3 #define TX_BIT 1 #define RX_PULLUP -// only uncomment this if other port other then 0 is used -// #define UART_PORT 0 + // only uncomment this if other port other then 0 is used + // #define UART_PORT 0 #define PWM0_BIT 32 #define PWM0_CHANNEL 0 @@ -52,12 +52,12 @@ extern "C" #define DOUT9_BIT 16 #define DOUT10_BIT 17 -// bitbanging 74hc595 (not used) -// uses 3 x 74HS595 -// #define IC74HC595_COUNT 1 -// #define IC74HC595_DELAY_CYCLES 0 + // bitbanging 74hc595 (not used) + // uses 3 x 74HS595 + // #define IC74HC595_COUNT 1 + // #define IC74HC595_DELAY_CYCLES 0 -#define IC74HC595_CUSTOM_SHIFT_IO //Enables custom MCU data shift transmission. In ESP32 that is via I2S +#define IC74HC595_CUSTOM_SHIFT_IO // Enables custom MCU data shift transmission. In ESP32 that is via I2S #define IC74HC595_I2S_WS 17 #define IC74HC595_I2S_CLK 16 #define IC74HC595_I2S_DATA 21 @@ -75,7 +75,7 @@ extern "C" // Setup the Step Timer used has the heartbeat for µCNC // Timer 1 is used by default - //#define ITP_TIMER 1 + // #define ITP_TIMER 1 // RTC Timer on ESP32 is granteed by a FreeRTOS @@ -86,16 +86,16 @@ extern "C" #define SPI_SDI_BIT 12 #define SPI_CS_BIT 15 -//software I2C +// software I2C #define DIN30_BIT 4 #define DIN31_BIT 0 -//pins for smart adapter -//clk +// pins for smart adapter +// clk #define DOUT4_BIT 26 -//data +// data #define DOUT5_BIT 05 -//cs +// cs #define DOUT6_BIT 27 #ifdef __cplusplus diff --git a/uCNC/src/hal/boards/esp32/boardmap_mks_tinybee.h b/uCNC/src/hal/boards/esp32/boardmap_mks_tinybee.h index f6c0790de..fbb238310 100644 --- a/uCNC/src/hal/boards/esp32/boardmap_mks_tinybee.h +++ b/uCNC/src/hal/boards/esp32/boardmap_mks_tinybee.h @@ -29,11 +29,11 @@ extern "C" #endif // Setup limit pins -#define LIMIT_Z_BIT 22 // assigns LIMIT_Z pin +#define LIMIT_Z_BIT 22 // assigns LIMIT_Z pin // #define LIMIT_Z_ISR // assigns LIMIT_Z ISR -#define LIMIT_Y_BIT 32 // assigns LIMIT_Y pin +#define LIMIT_Y_BIT 32 // assigns LIMIT_Y pin // #define LIMIT_Y_ISR // assigns LIMIT_Y ISR -#define LIMIT_X_BIT 33 // assigns LIMIT_X pin +#define LIMIT_X_BIT 33 // assigns LIMIT_X pin // #define LIMIT_X_ISR // assigns LIMIT_X ISR // Setup com pins @@ -53,8 +53,8 @@ extern "C" // #define IC74HC595_COUNT 3 // #define IC74HC595_DELAY_CYCLES 0 -//Use I2S to shift data in ESP32 -#define IC74HC595_CUSTOM_SHIFT_IO //Enables custom MCU data shift transmission. In ESP32 that is via I2S +// Use I2S to shift data in ESP32 +#define IC74HC595_CUSTOM_SHIFT_IO // Enables custom MCU data shift transmission. In ESP32 that is via I2S #define IC74HC595_I2S_WS 26 #define IC74HC595_I2S_CLK 25 #define IC74HC595_I2S_DATA 27 @@ -86,7 +86,7 @@ extern "C" #define DOUT2_IO_OFFSET 23 // Setup the Step Timer used has the heartbeat for µCNC // Timer 1 is used by default - //#define ITP_TIMER 1 + // #define ITP_TIMER 1 // RTC Timer on ESP32 is granteed by a FreeRTOS @@ -97,26 +97,26 @@ extern "C" #define SPI_SDO_BIT 23 #define SPI_SDI_BIT 19 #define SPI_CS_BIT 5 -//sd card detect +// sd card detect #define DIN19_BIT 34 -//pins for smart adapter -//clk +// pins for smart adapter +// clk #define DOUT4_BIT 15 -//data +// data #define DOUT5_BIT 21 -//cs +// cs #define DOUT6_BIT 4 -//beep +// beep #define DOUT7_IO_OFFSET 21 -//enc btn +// enc btn #define DIN16_BIT 13 #define DIN16_PULLUP -//enc 1 +// enc 1 #define DIN17_BIT 12 #define DIN17_PULLUP -//enc 2 +// enc 2 #define DIN18_BIT 14 #define DIN18_PULLUP diff --git a/uCNC/src/hal/boards/esp32/boardmap_wemos_d1_r32.h b/uCNC/src/hal/boards/esp32/boardmap_wemos_d1_r32.h index 5ae6be9bd..a3054d37e 100644 --- a/uCNC/src/hal/boards/esp32/boardmap_wemos_d1_r32.h +++ b/uCNC/src/hal/boards/esp32/boardmap_wemos_d1_r32.h @@ -51,12 +51,12 @@ extern "C" #define CS_RES_PULLUP // Setup limit pins -#define LIMIT_Z_BIT 19 // assigns LIMIT_Z pin -#define LIMIT_Z_ISR // assigns LIMIT_Z ISR -#define LIMIT_Y_BIT 5 // assigns LIMIT_Y pin -#define LIMIT_Y_ISR // assigns LIMIT_Y ISR -#define LIMIT_X_BIT 13 // assigns LIMIT_X pin -#define LIMIT_X_ISR // assigns LIMIT_X ISR +#define LIMIT_Z_BIT 19 // assigns LIMIT_Z pin +#define LIMIT_Z_ISR // assigns LIMIT_Z ISR +#define LIMIT_Y_BIT 5 // assigns LIMIT_Y pin +#define LIMIT_Y_ISR // assigns LIMIT_Y ISR +#define LIMIT_X_BIT 13 // assigns LIMIT_X pin +#define LIMIT_X_ISR // assigns LIMIT_X ISR // Setup probe pin #define PROBE_BIT 39 @@ -66,8 +66,8 @@ extern "C" #define RX_BIT 3 #define TX_BIT 1 #define RX_PULLUP -// only uncomment this if other port other then 0 is used -// #define UART_PORT 0 + // only uncomment this if other port other then 0 is used + // #define UART_PORT 0 // Setup PWM #define PWM0_BIT 23 // assigns PWM0 pin @@ -86,7 +86,7 @@ extern "C" // Setup the Step Timer used has the heartbeat for µCNC // Timer 1 is used by default - //#define ITP_TIMER 1 + // #define ITP_TIMER 1 // RTC Timer on ESP32 is granteed by a FreeRTOS diff --git a/uCNC/src/hal/boards/esp8266/boardmap_wemos_d1.h b/uCNC/src/hal/boards/esp8266/boardmap_wemos_d1.h index 1b882500c..91e5bdc32 100644 --- a/uCNC/src/hal/boards/esp8266/boardmap_wemos_d1.h +++ b/uCNC/src/hal/boards/esp8266/boardmap_wemos_d1.h @@ -1,19 +1,19 @@ /* - Name: boardmap_wemos_d1.h - Description: Contains all MCU and PIN definitions for Arduino WeMos D1 to run µCNC. + Name: boardmap_wemos_d1.h + Description: Contains all MCU and PIN definitions for Arduino WeMos D1 to run µCNC. - Copyright: Copyright (c) João Martins - Author: João Martins - Date: 17/06/2022 + Copyright: Copyright (c) João Martins + Author: João Martins + Date: 17/06/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 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. + µ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 BOARDMAP_WEMOS_D1_H @@ -30,9 +30,9 @@ extern "C" // SAME AS GRBL for test purposes // Setup step pins -#define STEP2_BIT 4 // assigns STEP2 pin +#define STEP2_BIT 4 // assigns STEP2 pin #define STEP2_PORT D // assigns STEP2 port -#define STEP1_BIT 5 // assigns STEP1 pin +#define STEP1_BIT 5 // assigns STEP1 pin #define STEP1_PORT D // assigns STEP1 port #define STEP0_BIT 16 // assigns STEP0 pin #define STEP0_PORT D // assigns STEP0 port @@ -48,7 +48,7 @@ extern "C" // Setup control input pins // #define ESTOP_BIT 0 // #define ESTOP_PORT A -//#define ESTOP_ISR +// #define ESTOP_ISR // Setup com pins #define RX_BIT 3 @@ -56,11 +56,11 @@ extern "C" #define RX_PORT D #define TX_PORT D #define RX_PULLUP -// only uncomment this if other port other then 0 is used -// #define UART_PORT 0 + // only uncomment this if other port other then 0 is used + // #define UART_PORT 0 - // Setup PWM -#define PWM0_BIT 2 // assigns PWM0 pin + // Setup PWM +#define PWM0_BIT 2 // assigns PWM0 pin #define PWM0_PORT D // assigns PWM0 pin // Setup generic IO Pins diff --git a/uCNC/src/hal/boards/lpc176x/boardmap_mks_base13.h b/uCNC/src/hal/boards/lpc176x/boardmap_mks_base13.h index 4aacf72a8..0b26d8ffa 100644 --- a/uCNC/src/hal/boards/lpc176x/boardmap_mks_base13.h +++ b/uCNC/src/hal/boards/lpc176x/boardmap_mks_base13.h @@ -45,13 +45,13 @@ extern "C" #define STEP4_PORT 2 // assigns STEP4 port // Setup dir pins -#define DIR0_BIT 5 // assigns DIR0 pin +#define DIR0_BIT 5 // assigns DIR0 pin #define DIR0_PORT 0 // assigns DIR0 port #define DIR1_BIT 11 // assigns DIR1 pin #define DIR1_PORT 0 // assigns DIR1 port #define DIR2_BIT 20 // assigns DIR2 pin #define DIR2_PORT 0 // assigns DIR2 port -#define DIR3_BIT 22 // assigns DIR2 pin +#define DIR3_BIT 22 // assigns DIR2 pin #define DIR3_PORT 0 // assigns DIR2 port #define DIR4_BIT 13 // assigns DIR2 pin #define DIR4_PORT 2 // assigns DIR2 port @@ -123,10 +123,10 @@ extern "C" // Setup the Step Timer used has the heartbeat for µCNC // Timer 0 is used by default - //#define ITP_TIMER 0 + // #define ITP_TIMER 0 // Setup the SERVO Timer used by µCNC // Timer 1 is set by default - //#define SERVO_TIMER 1 + // #define SERVO_TIMER 1 #define SERVO3_BIT 18 #define SERVO3_PORT 1 @@ -187,29 +187,29 @@ extern "C" #define DIN19_PORT 0 #define DIN19_PULLUP -//pins for smart adapter -//clk +// pins for smart adapter +// clk #define DOUT4_BIT 15 #define DOUT4_PORT 0 -//data +// data #define DOUT5_BIT 18 #define DOUT5_PORT 0 -//cs +// cs #define DOUT6_BIT 16 #define DOUT6_PORT 0 -//beep +// beep #define DOUT7_BIT 31 #define DOUT7_PORT 1 -//enc btn +// enc btn #define DIN16_BIT 30 #define DIN16_PORT 1 #define DIN16_PULLUP -//enc 1 +// enc 1 #define DIN17_BIT 26 #define DIN17_PORT 3 #define DIN17_PULLUP -//enc 2 +// enc 2 #define DIN18_BIT 25 #define DIN18_PORT 3 #define DIN18_PULLUP diff --git a/uCNC/src/hal/boards/lpc176x/boardmap_re_arm.h b/uCNC/src/hal/boards/lpc176x/boardmap_re_arm.h index 6e3c90937..3d332b298 100644 --- a/uCNC/src/hal/boards/lpc176x/boardmap_re_arm.h +++ b/uCNC/src/hal/boards/lpc176x/boardmap_re_arm.h @@ -85,8 +85,8 @@ extern "C" #define RX_PORT 0 #define TX_PORT 0 #define RX_PULLUP -// only uncomment this if other port other then 0 is used -//#define UART_PORT 0 + // only uncomment this if other port other then 0 is used + // #define UART_PORT 0 #define USB_DM_BIT 30 #define USB_DM_PORT 0 @@ -123,10 +123,10 @@ extern "C" // Setup the Step Timer used has the heartbeat for µCNC // Timer 0 is used by default - //#define ITP_TIMER 0 + // #define ITP_TIMER 0 // Setup the SERVO Timer used by µCNC // Timer 1 is set by default - //#define SERVO_TIMER 1 + // #define SERVO_TIMER 1 #define SERVO3_BIT 18 #define SERVO3_PORT 1 @@ -195,29 +195,29 @@ extern "C" // #define DOUT30_BIT 7 // #define DOUT30_PORT 0 -//pins for smart adapter -//clk +// pins for smart adapter +// clk #define DOUT4_BIT 15 #define DOUT4_PORT 0 -//data +// data #define DOUT5_BIT 18 #define DOUT5_PORT 0 -//cs +// cs #define DOUT6_BIT 16 #define DOUT6_PORT 0 -//beep +// beep #define DOUT7_BIT 30 #define DOUT7_PORT 1 -//enc btn +// enc btn #define DIN16_BIT 11 #define DIN16_PORT 2 #define DIN16_PULLUP -//enc 1 +// enc 1 #define DIN17_BIT 25 #define DIN17_PORT 3 #define DIN17_PULLUP -//enc 2 +// enc 2 #define DIN18_BIT 26 #define DIN18_PORT 3 #define DIN18_PULLUP diff --git a/uCNC/src/hal/boards/lpc176x/boardmap_skr_v14_turbo.h b/uCNC/src/hal/boards/lpc176x/boardmap_skr_v14_turbo.h index dcbe76910..ab4d206c7 100644 --- a/uCNC/src/hal/boards/lpc176x/boardmap_skr_v14_turbo.h +++ b/uCNC/src/hal/boards/lpc176x/boardmap_skr_v14_turbo.h @@ -35,23 +35,23 @@ extern "C" // Setup step pins #define STEP0_BIT 2 // assigns STEP0 pin #define STEP0_PORT 2 // assigns STEP0 port -#define STEP1_BIT 19 // assigns STEP1 pin +#define STEP1_BIT 19 // assigns STEP1 pin #define STEP1_PORT 0 // assigns STEP1 port -#define STEP2_BIT 22 // assigns STEP2 pin +#define STEP2_BIT 22 // assigns STEP2 pin #define STEP2_PORT 0 // assigns STEP2 port -#define STEP3_BIT 13 // assigns STEP3 pin +#define STEP3_BIT 13 // assigns STEP3 pin #define STEP3_PORT 2 // assigns STEP3 port -#define STEP4_BIT 15 // assigns STEP4 pin +#define STEP4_BIT 15 // assigns STEP4 pin #define STEP4_PORT 1 // assigns STEP4 port // Setup dir pins -#define DIR0_BIT 6 // assigns DIR0 pin +#define DIR0_BIT 6 // assigns DIR0 pin #define DIR0_PORT 2 // assigns DIR0 port #define DIR1_BIT 20 // assigns DIR1 pin #define DIR1_PORT 0 // assigns DIR1 port #define DIR2_BIT 11 // assigns DIR2 pin #define DIR2_PORT 2 // assigns DIR2 port -#define DIR3_BIT 11 // assigns DIR2 pin +#define DIR3_BIT 11 // assigns DIR2 pin #define DIR3_PORT 0 // assigns DIR2 port #define DIR4_BIT 14 // assigns DIR2 pin #define DIR4_PORT 1 // assigns DIR2 port @@ -126,10 +126,10 @@ extern "C" // Setup the Step Timer used has the heartbeat for µCNC // Timer 0 is used by default - //#define ITP_TIMER 0 + // #define ITP_TIMER 0 // Setup the SERVO Timer used by µCNC // Timer 1 is set by default - //#define SERVO_TIMER 1 + // #define SERVO_TIMER 1 #define SERVO3_BIT 18 #define SERVO3_PORT 1 @@ -201,29 +201,29 @@ extern "C" #define DIN19_PORT 1 #define DIN19_PULLUP -//pins for smart adapter -//clk +// pins for smart adapter +// clk #define DOUT4_BIT 20 #define DOUT4_PORT 1 -//data +// data #define DOUT5_BIT 18 #define DOUT5_PORT 1 -//cs +// cs #define DOUT6_BIT 19 #define DOUT6_PORT 1 -//beep +// beep #define DOUT7_BIT 30 #define DOUT7_PORT 1 -//enc btn +// enc btn #define DIN16_BIT 28 #define DIN16_PORT 0 #define DIN16_PULLUP -//enc 1 +// enc 1 #define DIN17_BIT 25 #define DIN17_PORT 3 #define DIN17_PULLUP -//enc 2 +// enc 2 #define DIN18_BIT 26 #define DIN18_PORT 3 #define DIN18_PULLUP diff --git a/uCNC/src/hal/boards/rp2040/boardmap_rpi_pico.h b/uCNC/src/hal/boards/rp2040/boardmap_rpi_pico.h index 92c59fe32..f8512e8ad 100644 --- a/uCNC/src/hal/boards/rp2040/boardmap_rpi_pico.h +++ b/uCNC/src/hal/boards/rp2040/boardmap_rpi_pico.h @@ -1,19 +1,19 @@ /* - Name: boardmap_rp_pico_w.h - Description: Contains all MCU and PIN definitions for Raspberry Pi Pico W to run µCNC. + Name: boardmap_rp_pico_w.h + Description: Contains all MCU and PIN definitions for Raspberry Pi Pico W to run µCNC. - Copyright: Copyright (c) João Martins - Author: João Martins - Date: 16/01/2023 + Copyright: Copyright (c) João Martins + Author: João Martins + Date: 16/01/2023 - µ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 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. + µ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 BOARDMAP_RPI_PICO_H @@ -30,14 +30,14 @@ extern "C" // SAME AS GRBL for test purposes // Setup step pins -#define STEP2_BIT 10 // assigns STEP2 pin -#define STEP1_BIT 6 // assigns STEP1 pin -#define STEP0_BIT 2 // assigns STEP0 pin +#define STEP2_BIT 10 // assigns STEP2 pin +#define STEP1_BIT 6 // assigns STEP1 pin +#define STEP0_BIT 2 // assigns STEP0 pin // Setup dir pins #define DIR2_BIT 11 // assigns DIR2 pin -#define DIR1_BIT 7 // assigns DIR1 pin -#define DIR0_BIT 3 // assigns DIR0 pin +#define DIR1_BIT 7 // assigns DIR1 pin +#define DIR0_BIT 3 // assigns DIR0 pin #define LIMIT_Z_BIT 13 #define LIMIT_Y_BIT 9 @@ -59,11 +59,11 @@ extern "C" // only uncomment this if other port other then 0 is used // #define UART_PORT 0 -//forces USB +// forces USB #define MCU_HAS_USB - // Setup PWM -#define PWM0_BIT 14 // assigns PWM0 pin + // Setup PWM +#define PWM0_BIT 14 // assigns PWM0 pin // Setup generic IO Pins // spindle dir @@ -74,55 +74,55 @@ extern "C" #define STEP1_EN_BIT 8 #define STEP0_EN_BIT 4 -//activity LED +// activity LED #define DOUT31_BIT 25 -//disable EEPROM emulation -// #ifndef RAM_ONLY_SETTINGS -// #define RAM_ONLY_SETTINGS -// #endif + // disable EEPROM emulation + // #ifndef RAM_ONLY_SETTINGS + // #define RAM_ONLY_SETTINGS + // #endif #define I2C_CLK_BIT 27 #define I2C_DATA_BIT 26 #define I2C_PORT 1 -// #define I2C_ADDRESS 1 - -/** - * This is an example of how to use RP2040 PIO to control - * up to 4 chainned 74hc595 (32 output pins) using only 3 pins - * from the board. - * The 3 pins should be sequential (for example GPIO's 26, 27 and 28) - * - * RP2040 does not yet support software generate PWM - * - * **/ - -// // Use PIO to shift data to 74HC595 shift registers (up to 4) -// // IO pins should be sequencial GPIO pins starting by data, then clock then the latch pin -// #define IC74HC595_CUSTOM_SHIFT_IO //Enables custom MCU data shift transmission. In RP2040 that is via a PIO -// #define IC74HC595_PIO_DATA 26 -// #define IC74HC595_PIO_CLK 27 -// #define IC74HC595_PIO_LATCH 28 -// // enabling IC74HC595_CUSTOM_SHIFT_IO will force IC74HC595_COUNT to be set to 4 no matter what -// // support up to 4 chained 74HC595. Less can be used (overflow bits will be discarded like in the ESP32 I2S implementation) -// #define IC74HC595_COUNT 4 - -// #define STEP0_EN_IO_OFFSET 0 -// #define STEP0_IO_OFFSET 1 -// #define DIR0_IO_OFFSET 2 -// #define STEP1_EN_IO_OFFSET 3 -// #define STEP1_IO_OFFSET 4 -// #define DIR1_IO_OFFSET 5 -// #define STEP2_EN_IO_OFFSET 6 -// #define STEP2_IO_OFFSET 7 -// #define DIR2_IO_OFFSET 8 -// #define STEP3_EN_IO_OFFSET 9 -// #define STEP3_IO_OFFSET 10 -// #define DIR3_IO_OFFSET 11 -// #define STEP4_EN_IO_OFFSET 12 -// #define STEP4_IO_OFFSET 13 -// #define DIR4_IO_OFFSET 14 -// #define DOUT0_IO_OFFSET 15 + // #define I2C_ADDRESS 1 + + /** + * This is an example of how to use RP2040 PIO to control + * up to 4 chainned 74hc595 (32 output pins) using only 3 pins + * from the board. + * The 3 pins should be sequential (for example GPIO's 26, 27 and 28) + * + * RP2040 does not yet support software generate PWM + * + * **/ + + // // Use PIO to shift data to 74HC595 shift registers (up to 4) + // // IO pins should be sequencial GPIO pins starting by data, then clock then the latch pin + // #define IC74HC595_CUSTOM_SHIFT_IO //Enables custom MCU data shift transmission. In RP2040 that is via a PIO + // #define IC74HC595_PIO_DATA 26 + // #define IC74HC595_PIO_CLK 27 + // #define IC74HC595_PIO_LATCH 28 + // // enabling IC74HC595_CUSTOM_SHIFT_IO will force IC74HC595_COUNT to be set to 4 no matter what + // // support up to 4 chained 74HC595. Less can be used (overflow bits will be discarded like in the ESP32 I2S implementation) + // #define IC74HC595_COUNT 4 + + // #define STEP0_EN_IO_OFFSET 0 + // #define STEP0_IO_OFFSET 1 + // #define DIR0_IO_OFFSET 2 + // #define STEP1_EN_IO_OFFSET 3 + // #define STEP1_IO_OFFSET 4 + // #define DIR1_IO_OFFSET 5 + // #define STEP2_EN_IO_OFFSET 6 + // #define STEP2_IO_OFFSET 7 + // #define DIR2_IO_OFFSET 8 + // #define STEP3_EN_IO_OFFSET 9 + // #define STEP3_IO_OFFSET 10 + // #define DIR3_IO_OFFSET 11 + // #define STEP4_EN_IO_OFFSET 12 + // #define STEP4_IO_OFFSET 13 + // #define DIR4_IO_OFFSET 14 + // #define DOUT0_IO_OFFSET 15 #ifdef __cplusplus } diff --git a/uCNC/src/hal/boards/rp2040/boardmap_rpi_pico_w.h b/uCNC/src/hal/boards/rp2040/boardmap_rpi_pico_w.h index e3574ff4c..86e04a9ce 100644 --- a/uCNC/src/hal/boards/rp2040/boardmap_rpi_pico_w.h +++ b/uCNC/src/hal/boards/rp2040/boardmap_rpi_pico_w.h @@ -1,19 +1,19 @@ /* - Name: boardmap_rp_pico_w.h - Description: Contains all MCU and PIN definitions for Raspberry Pi Pico W to run µCNC. + Name: boardmap_rp_pico_w.h + Description: Contains all MCU and PIN definitions for Raspberry Pi Pico W to run µCNC. - Copyright: Copyright (c) João Martins - Author: João Martins - Date: 16/01/2023 + Copyright: Copyright (c) João Martins + Author: João Martins + Date: 16/01/2023 - µ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 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. + µ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 BOARDMAP_RPI_PICO_W_H diff --git a/uCNC/src/hal/boards/samd21/boardmap_mzero.h b/uCNC/src/hal/boards/samd21/boardmap_mzero.h index c244811b8..2acf2d2b9 100644 --- a/uCNC/src/hal/boards/samd21/boardmap_mzero.h +++ b/uCNC/src/hal/boards/samd21/boardmap_mzero.h @@ -53,7 +53,7 @@ extern "C" #define DIR2_PORT A // assigns DIR2 port // Setup limit pins -#define LIMIT_X_BIT 7 // assigns LIMIT_X pin +#define LIMIT_X_BIT 7 // assigns LIMIT_X pin #define LIMIT_X_PORT A // assigns LIMIT_X port #define LIMIT_Y_BIT 18 // assigns LIMIT_Y pin #define LIMIT_Y_PORT A // assigns LIMIT_Y port @@ -100,11 +100,11 @@ extern "C" #define USB_DP_MUX G // Setup PWM -#define PWM0_BIT 16 // assigns PWM0 pin -#define PWM0_PORT A // assigns PWM0 port +#define PWM0_BIT 16 // assigns PWM0 pin +#define PWM0_PORT A // assigns PWM0 port #define PWM0_CHANNEL 0 // assigns PWM0 channel -#define PWM0_TIMER 2 // assigns PWM0 timer -#define PWM0_MUX E // assigns PWM0 mux +#define PWM0_TIMER 2 // assigns PWM0 timer +#define PWM0_MUX E // assigns PWM0 mux // Setup generic IO Pins // Functionalities are set in cnc_hal_config.h file @@ -138,12 +138,12 @@ extern "C" #define I2C_DATA_BIT 22 #define I2C_DATA_PORT A #define I2C_PORT 3 -// #define I2C_ADDRESS 0 + // #define I2C_ADDRESS 0 -// #define DIN30_BIT 23 -// #define DIN30_PORT A -// #define DIN31_BIT 22 -// #define DIN31_PORT A + // #define DIN30_BIT 23 + // #define DIN30_PORT A + // #define DIN31_BIT 22 + // #define DIN31_PORT A #define ONESHOT_TIMER 2 diff --git a/uCNC/src/hal/boards/stm32/boardmap_blackpill.h b/uCNC/src/hal/boards/stm32/boardmap_blackpill.h index 8f2a7fb28..890ec34e0 100644 --- a/uCNC/src/hal/boards/stm32/boardmap_blackpill.h +++ b/uCNC/src/hal/boards/stm32/boardmap_blackpill.h @@ -140,16 +140,15 @@ extern "C" // On STM32F1x cores this will default to Timer 3 // #define SERVO_TIMER 3 -// #define I2C_CLK_BIT 6 -// #define I2C_CLK_PORT B -// #define I2C_DATA_BIT 7 -// #define I2C_DATA_PORT B -// #define I2C_PORT 1 -// #define DIN7_BIT 5 -// #define DIN7_PORT A -// #define DIN7_ISR -// #define DIN7_PULLUP - + // #define I2C_CLK_BIT 6 + // #define I2C_CLK_PORT B + // #define I2C_DATA_BIT 7 + // #define I2C_DATA_PORT B + // #define I2C_PORT 1 + // #define DIN7_BIT 5 + // #define DIN7_PORT A + // #define DIN7_ISR + // #define DIN7_PULLUP #define ONESHOT_TIMER 1 diff --git a/uCNC/src/hal/boards/stm32/boardmap_bluepill.h b/uCNC/src/hal/boards/stm32/boardmap_bluepill.h index 6e971ed2f..dd0db841e 100644 --- a/uCNC/src/hal/boards/stm32/boardmap_bluepill.h +++ b/uCNC/src/hal/boards/stm32/boardmap_bluepill.h @@ -133,24 +133,24 @@ extern "C" // Setup the Step Timer used has the heartbeat for µCNC // On STM32F1x cores this will default to Timer 2 - //#define ITP_TIMER 2 + // #define ITP_TIMER 2 // Setup the Timer to be used exclusively by servos in µCNC. // If no servos are configured then the timer is free for other functions (like PWM) (even if defined in the board) // On STM32F1x cores this will default to Timer 3 - //#define SERVO_TIMER 3 - -// #define I2C_CLK_BIT 10 -// #define I2C_CLK_PORT B -// #define I2C_DATA_BIT 11 -// #define I2C_DATA_PORT B -// #define I2C_PORT 2 -// #define I2C_ADDRESS 1 - -// #define DIN7_BIT 5 -// #define DIN7_PORT B -// #define DIN7_ISR -// #define DIN7_PULLUP + // #define SERVO_TIMER 3 + + // #define I2C_CLK_BIT 10 + // #define I2C_CLK_PORT B + // #define I2C_DATA_BIT 11 + // #define I2C_DATA_PORT B + // #define I2C_PORT 2 + // #define I2C_ADDRESS 1 + + // #define DIN7_BIT 5 + // #define DIN7_PORT B + // #define DIN7_ISR + // #define DIN7_PULLUP #define ONESHOT_TIMER 1 diff --git a/uCNC/src/hal/boards/stm32/boardmap_mks_robin_nano_v1_2.h b/uCNC/src/hal/boards/stm32/boardmap_mks_robin_nano_v1_2.h index f0407f9ed..6c5e19164 100644 --- a/uCNC/src/hal/boards/stm32/boardmap_mks_robin_nano_v1_2.h +++ b/uCNC/src/hal/boards/stm32/boardmap_mks_robin_nano_v1_2.h @@ -74,7 +74,7 @@ extern "C" #define LIMIT_X_PORT A // assigns LIMIT_X port #define LIMIT_Y_BIT 12 // assigns LIMIT_Y pin #define LIMIT_Y_PORT A // assigns LIMIT_Y port -#define LIMIT_Z_BIT 4 // assigns LIMIT_Z+ pin +#define LIMIT_Z_BIT 4 // assigns LIMIT_Z+ pin #define LIMIT_Z_PORT C // assigns LIMIT_Z+ port #define LIMIT_Z2_BIT 11 // assigns LIMIT_Z- pin #define LIMIT_Z2_PORT A // assigns LIMIT_Z- port @@ -127,7 +127,7 @@ extern "C" // Setup the Step Timer used has the heartbeat for µCNC #define ITP_TIMER 5 -//software SPI for card access +// software SPI for card access #define DOUT29_BIT 2 #define DOUT29_PORT D #define DIN29_BIT 8 @@ -136,7 +136,7 @@ extern "C" #define DOUT30_PORT C #define SPI_CS_BIT 11 #define SPI_CS_PORT C -//SD detect pin +// SD detect pin #define DIN19_BIT 12 #define DIN19_PORT D diff --git a/uCNC/src/hal/boards/stm32/boardmap_nucleo_f411re_shield_v3.h b/uCNC/src/hal/boards/stm32/boardmap_nucleo_f411re_shield_v3.h index 5a211d2a3..f2c64f60d 100644 --- a/uCNC/src/hal/boards/stm32/boardmap_nucleo_f411re_shield_v3.h +++ b/uCNC/src/hal/boards/stm32/boardmap_nucleo_f411re_shield_v3.h @@ -29,7 +29,7 @@ extern "C" #endif // Setup step pins -#define STEP0_BIT 10 // assigns STEP0 pin +#define STEP0_BIT 10 // assigns STEP0 pin #define STEP0_PORT A // assigns STEP0 port #define STEP1_BIT 3 // assigns STEP1 pin #define STEP1_PORT B // assigns STEP1 port @@ -41,7 +41,7 @@ extern "C" // Setup dir pins #define DIR0_BIT 4 // assigns DIR0 pin #define DIR0_PORT B // assigns DIR0 port -#define DIR1_BIT 10 // assigns DIR1 pin +#define DIR1_BIT 10 // assigns DIR1 pin #define DIR1_PORT B // assigns DIR1 port #define DIR2_BIT 8 // assigns DIR2 pin #define DIR2_PORT A // assigns DIR2 port @@ -49,11 +49,11 @@ extern "C" // #define DIR3_PORT A // assigns DIR3 port but must comment Spindle PWM and Dir // Setup limit pins -#define LIMIT_X_BIT 7 // assigns LIMIT_X pin +#define LIMIT_X_BIT 7 // assigns LIMIT_X pin #define LIMIT_X_PORT C // assigns LIMIT_X port -#define LIMIT_Y_BIT 6 // assigns LIMIT_Y pin +#define LIMIT_Y_BIT 6 // assigns LIMIT_Y pin #define LIMIT_Y_PORT B // assigns LIMIT_Y port -#define LIMIT_Z_BIT 7 // assigns LIMIT_Z pin +#define LIMIT_Z_BIT 7 // assigns LIMIT_Z pin #define LIMIT_Z_PORT A // assigns LIMIT_Z port // Enable limits switch interrupt @@ -128,12 +128,12 @@ extern "C" // Setup the Step Timer used has the heartbeat for µCNC // On STM32F1x cores this will default to Timer 2 - //#define ITP_TIMER 2 + // #define ITP_TIMER 2 // Setup the Timer to be used exclusively by servos in µCNC. // If no servos are configured then the timer is free for other functions (like PWM) (even if defined in the board) // On STM32F1x cores this will default to Timer 3 - //#define SERVO_TIMER 3 + // #define SERVO_TIMER 3 // I2C port #define I2C_CLK_BIT 8 @@ -141,7 +141,7 @@ extern "C" #define I2C_DATA_BIT 9 #define I2C_DATA_PORT B #define I2C_PORT 1 -// #define I2C_ADDRESS 1 + // #define I2C_ADDRESS 1 #define ONESHOT_TIMER 1 diff --git a/uCNC/src/hal/boards/stm32/boardmap_srk_pro_v1_2.h b/uCNC/src/hal/boards/stm32/boardmap_srk_pro_v1_2.h index 31c13cef2..548e917d0 100644 --- a/uCNC/src/hal/boards/stm32/boardmap_srk_pro_v1_2.h +++ b/uCNC/src/hal/boards/stm32/boardmap_srk_pro_v1_2.h @@ -34,15 +34,15 @@ extern "C" // Setup step pins #define STEP0_BIT 9 // assigns STEP0 pin #define STEP0_PORT E // assigns STEP0 port -#define STEP1_BIT 11 // assigns STEP1 pin +#define STEP1_BIT 11 // assigns STEP1 pin #define STEP1_PORT E // assigns STEP1 port -#define STEP2_BIT 13 // assigns STEP2 pin +#define STEP2_BIT 13 // assigns STEP2 pin #define STEP2_PORT E // assigns STEP2 port -#define STEP3_BIT 14 // assigns STEP3 pin +#define STEP3_BIT 14 // assigns STEP3 pin #define STEP3_PORT E // assigns STEP3 port -#define STEP4_BIT 15 // assigns STEP4 pin +#define STEP4_BIT 15 // assigns STEP4 pin #define STEP4_PORT D // assigns STEP4 port -#define STEP5_BIT 13 // assigns STEP5 pin +#define STEP5_BIT 13 // assigns STEP5 pin #define STEP5_PORT D // assigns STEP5 port // Setup dir pins @@ -78,12 +78,12 @@ extern "C" #define LIMIT_X_PORT B // assigns LIMIT_X port #define LIMIT_Y_BIT 12 // assigns LIMIT_Y pin #define LIMIT_Y_PORT E // assigns LIMIT_Y port -#define LIMIT_Z_BIT 8 // assigns LIMIT_Z pin +#define LIMIT_Z_BIT 8 // assigns LIMIT_Z pin #define LIMIT_Z_PORT G // assigns LIMIT_Z port -#define LIMIT_X2_BIT 15 // assigns LIMIT_X2 pin -#define LIMIT_X2_PORT E // assigns LIMIT_X2 port -#define LIMIT_Y2_BIT 10 // assigns LIMIT_Y2 pin -#define LIMIT_Y2_PORT E // assigns LIMIT_Y2 port +#define LIMIT_X2_BIT 15 // assigns LIMIT_X2 pin +#define LIMIT_X2_PORT E // assigns LIMIT_X2 port +#define LIMIT_Y2_BIT 10 // assigns LIMIT_Y2 pin +#define LIMIT_Y2_PORT E // assigns LIMIT_Y2 port // #define LIMIT_Z2_BIT 5 // assigns LIMIT_Z2 pin // #define LIMIT_Z2_PORT G // assigns LIMIT_Z2 port @@ -100,24 +100,23 @@ extern "C" #define PROBE_PORT G #define PROBE_ISR -// #define UART_PORT 3 -// #define TX_BIT 10 -// #define TX_PORT B -// #define RX_BIT 11 -// #define RX_PORT B + // #define UART_PORT 3 + // #define TX_BIT 10 + // #define TX_PORT B + // #define RX_BIT 11 + // #define RX_PORT B #define USB_DM_BIT 11 #define USB_DM_PORT A #define USB_DP_BIT 12 #define USB_DP_PORT A - // Setup PWM #define PWM0_BIT 1 // assigns PWM0 pin #define PWM0_PORT B // assigns PWM0 pin #define PWM0_CHANNEL 4 #define PWM0_TIMER 3 -#define PWM1_BIT 14 // assigns PWM2 pin +#define PWM1_BIT 14 // assigns PWM2 pin #define PWM1_PORT D // assigns PWM2 pin #define PWM1_CHANNEL 3 #define PWM1_TIMER 4 @@ -142,7 +141,7 @@ extern "C" #define ITP_TIMER 2 #define SERVO_TIMER 5 -//activity led +// activity led #define DOUT32_BIT 7 #define DOUT32_PORT A @@ -188,7 +187,7 @@ extern "C" #define DIN25_PORT D #define DIN25_PULLUP -//hardware SPI for card access +// hardware SPI for card access #define SPI_SDO_BIT 5 #define SPI_SDO_PORT B #define SPI_SDI_BIT 6 @@ -198,32 +197,32 @@ extern "C" #define SPI_CS_BIT 4 #define SPI_CS_PORT A #define SPI_PORT 1 -//SD detect pin +// SD detect pin #define DIN19_BIT 11 #define DIN19_PORT B -//pins for smart adapter -//clk +// pins for smart adapter +// clk #define DOUT4_BIT 2 #define DOUT4_PORT G -//data +// data #define DOUT5_BIT 11 #define DOUT5_PORT D -//cs +// cs #define DOUT6_BIT 10 #define DOUT6_PORT D -//beep +// beep #define DOUT7_BIT 4 #define DOUT7_PORT G -//enc btn +// enc btn #define DIN16_BIT 8 #define DIN16_PORT A #define DIN16_PULLUP -//enc 1 +// enc 1 #define DIN17_BIT 11 #define DIN17_PORT F #define DIN17_PULLUP -//enc 2 +// enc 2 #define DIN18_BIT 10 #define DIN18_PORT G #define DIN18_PULLUP diff --git a/uCNC/src/hal/io_hal.h b/uCNC/src/hal/io_hal.h index 0deaaae24..7e4e9a500 100644 --- a/uCNC/src/hal/io_hal.h +++ b/uCNC/src/hal/io_hal.h @@ -3939,12 +3939,12 @@ extern "C" #define io25_set_pwm(value) mcu_set_pwm(PWM0, value) #define io25_get_pwm mcu_get_pwm(PWM0) #elif ASSERT_PIN_EXTENDED(PWM0) -#define io25_config_pwm(freq) \ - { \ +#define io25_config_pwm(freq) \ + { \ g_soft_pwm_res = mcu_softpwm_freq_config(freq); \ } -#define io25_set_pwm(value) \ - { \ +#define io25_set_pwm(value) \ + { \ g_io_soft_pwm[PWM0 - PWM_PINS_OFFSET] = (0xFF & value); \ } #define io25_get_pwm g_io_soft_pwm[PWM0 - PWM_PINS_OFFSET] @@ -3958,12 +3958,12 @@ extern "C" #define io26_set_pwm(value) mcu_set_pwm(PWM1, value) #define io26_get_pwm mcu_get_pwm(PWM1) #elif ASSERT_PIN_EXTENDED(PWM1) -#define io26_config_pwm(freq) \ - { \ +#define io26_config_pwm(freq) \ + { \ g_soft_pwm_res = mcu_softpwm_freq_config(freq); \ } -#define io26_set_pwm(value) \ - { \ +#define io26_set_pwm(value) \ + { \ g_io_soft_pwm[PWM1 - PWM_PINS_OFFSET] = (0xFF & value); \ } #define io26_get_pwm g_io_soft_pwm[PWM1 - PWM_PINS_OFFSET] @@ -3977,12 +3977,12 @@ extern "C" #define io27_set_pwm(value) mcu_set_pwm(PWM2, value) #define io27_get_pwm mcu_get_pwm(PWM2) #elif ASSERT_PIN_EXTENDED(PWM2) -#define io27_config_pwm(freq) \ - { \ +#define io27_config_pwm(freq) \ + { \ g_soft_pwm_res = mcu_softpwm_freq_config(freq); \ } -#define io27_set_pwm(value) \ - { \ +#define io27_set_pwm(value) \ + { \ g_io_soft_pwm[PWM2 - PWM_PINS_OFFSET] = (0xFF & value); \ } #define io27_get_pwm g_io_soft_pwm[PWM2 - PWM_PINS_OFFSET] @@ -3996,12 +3996,12 @@ extern "C" #define io28_set_pwm(value) mcu_set_pwm(PWM3, value) #define io28_get_pwm mcu_get_pwm(PWM3) #elif ASSERT_PIN_EXTENDED(PWM3) -#define io28_config_pwm(freq) \ - { \ +#define io28_config_pwm(freq) \ + { \ g_soft_pwm_res = mcu_softpwm_freq_config(freq); \ } -#define io28_set_pwm(value) \ - { \ +#define io28_set_pwm(value) \ + { \ g_io_soft_pwm[PWM3 - PWM_PINS_OFFSET] = (0xFF & value); \ } #define io28_get_pwm g_io_soft_pwm[PWM3 - PWM_PINS_OFFSET] @@ -4015,12 +4015,12 @@ extern "C" #define io29_set_pwm(value) mcu_set_pwm(PWM4, value) #define io29_get_pwm mcu_get_pwm(PWM4) #elif ASSERT_PIN_EXTENDED(PWM4) -#define io29_config_pwm(freq) \ - { \ +#define io29_config_pwm(freq) \ + { \ g_soft_pwm_res = mcu_softpwm_freq_config(freq); \ } -#define io29_set_pwm(value) \ - { \ +#define io29_set_pwm(value) \ + { \ g_io_soft_pwm[PWM4 - PWM_PINS_OFFSET] = (0xFF & value); \ } #define io29_get_pwm g_io_soft_pwm[PWM4 - PWM_PINS_OFFSET] @@ -4034,12 +4034,12 @@ extern "C" #define io30_set_pwm(value) mcu_set_pwm(PWM5, value) #define io30_get_pwm mcu_get_pwm(PWM5) #elif ASSERT_PIN_EXTENDED(PWM5) -#define io30_config_pwm(freq) \ - { \ +#define io30_config_pwm(freq) \ + { \ g_soft_pwm_res = mcu_softpwm_freq_config(freq); \ } -#define io30_set_pwm(value) \ - { \ +#define io30_set_pwm(value) \ + { \ g_io_soft_pwm[PWM5 - PWM_PINS_OFFSET] = (0xFF & value); \ } #define io30_get_pwm g_io_soft_pwm[PWM5 - PWM_PINS_OFFSET] @@ -4053,12 +4053,12 @@ extern "C" #define io31_set_pwm(value) mcu_set_pwm(PWM6, value) #define io31_get_pwm mcu_get_pwm(PWM6) #elif ASSERT_PIN_EXTENDED(PWM6) -#define io31_config_pwm(freq) \ - { \ +#define io31_config_pwm(freq) \ + { \ g_soft_pwm_res = mcu_softpwm_freq_config(freq); \ } -#define io31_set_pwm(value) \ - { \ +#define io31_set_pwm(value) \ + { \ g_io_soft_pwm[PWM6 - PWM_PINS_OFFSET] = (0xFF & value); \ } #define io31_get_pwm g_io_soft_pwm[PWM6 - PWM_PINS_OFFSET] @@ -4072,12 +4072,12 @@ extern "C" #define io32_set_pwm(value) mcu_set_pwm(PWM7, value) #define io32_get_pwm mcu_get_pwm(PWM7) #elif ASSERT_PIN_EXTENDED(PWM7) -#define io32_config_pwm(freq) \ - { \ +#define io32_config_pwm(freq) \ + { \ g_soft_pwm_res = mcu_softpwm_freq_config(freq); \ } -#define io32_set_pwm(value) \ - { \ +#define io32_set_pwm(value) \ + { \ g_io_soft_pwm[PWM7 - PWM_PINS_OFFSET] = (0xFF & value); \ } #define io32_get_pwm g_io_soft_pwm[PWM7 - PWM_PINS_OFFSET] @@ -4091,12 +4091,12 @@ extern "C" #define io33_set_pwm(value) mcu_set_pwm(PWM8, value) #define io33_get_pwm mcu_get_pwm(PWM8) #elif ASSERT_PIN_EXTENDED(PWM8) -#define io33_config_pwm(freq) \ - { \ +#define io33_config_pwm(freq) \ + { \ g_soft_pwm_res = mcu_softpwm_freq_config(freq); \ } -#define io33_set_pwm(value) \ - { \ +#define io33_set_pwm(value) \ + { \ g_io_soft_pwm[PWM8 - PWM_PINS_OFFSET] = (0xFF & value); \ } #define io33_get_pwm g_io_soft_pwm[PWM8 - PWM_PINS_OFFSET] @@ -4110,12 +4110,12 @@ extern "C" #define io34_set_pwm(value) mcu_set_pwm(PWM9, value) #define io34_get_pwm mcu_get_pwm(PWM9) #elif ASSERT_PIN_EXTENDED(PWM9) -#define io34_config_pwm(freq) \ - { \ +#define io34_config_pwm(freq) \ + { \ g_soft_pwm_res = mcu_softpwm_freq_config(freq); \ } -#define io34_set_pwm(value) \ - { \ +#define io34_set_pwm(value) \ + { \ g_io_soft_pwm[PWM9 - PWM_PINS_OFFSET] = (0xFF & value); \ } #define io34_get_pwm g_io_soft_pwm[PWM9 - PWM_PINS_OFFSET] @@ -4129,12 +4129,12 @@ extern "C" #define io35_set_pwm(value) mcu_set_pwm(PWM10, value) #define io35_get_pwm mcu_get_pwm(PWM10) #elif ASSERT_PIN_EXTENDED(PWM10) -#define io35_config_pwm(freq) \ - { \ +#define io35_config_pwm(freq) \ + { \ g_soft_pwm_res = mcu_softpwm_freq_config(freq); \ } -#define io35_set_pwm(value) \ - { \ +#define io35_set_pwm(value) \ + { \ g_io_soft_pwm[PWM10 - PWM_PINS_OFFSET] = (0xFF & value); \ } #define io35_get_pwm g_io_soft_pwm[PWM10 - PWM_PINS_OFFSET] @@ -4148,12 +4148,12 @@ extern "C" #define io36_set_pwm(value) mcu_set_pwm(PWM11, value) #define io36_get_pwm mcu_get_pwm(PWM11) #elif ASSERT_PIN_EXTENDED(PWM11) -#define io36_config_pwm(freq) \ - { \ +#define io36_config_pwm(freq) \ + { \ g_soft_pwm_res = mcu_softpwm_freq_config(freq); \ } -#define io36_set_pwm(value) \ - { \ +#define io36_set_pwm(value) \ + { \ g_io_soft_pwm[PWM11 - PWM_PINS_OFFSET] = (0xFF & value); \ } #define io36_get_pwm g_io_soft_pwm[PWM11 - PWM_PINS_OFFSET] @@ -4167,12 +4167,12 @@ extern "C" #define io37_set_pwm(value) mcu_set_pwm(PWM12, value) #define io37_get_pwm mcu_get_pwm(PWM12) #elif ASSERT_PIN_EXTENDED(PWM12) -#define io37_config_pwm(freq) \ - { \ +#define io37_config_pwm(freq) \ + { \ g_soft_pwm_res = mcu_softpwm_freq_config(freq); \ } -#define io37_set_pwm(value) \ - { \ +#define io37_set_pwm(value) \ + { \ g_io_soft_pwm[PWM12 - PWM_PINS_OFFSET] = (0xFF & value); \ } #define io37_get_pwm g_io_soft_pwm[PWM12 - PWM_PINS_OFFSET] @@ -4186,12 +4186,12 @@ extern "C" #define io38_set_pwm(value) mcu_set_pwm(PWM13, value) #define io38_get_pwm mcu_get_pwm(PWM13) #elif ASSERT_PIN_EXTENDED(PWM13) -#define io38_config_pwm(freq) \ - { \ +#define io38_config_pwm(freq) \ + { \ g_soft_pwm_res = mcu_softpwm_freq_config(freq); \ } -#define io38_set_pwm(value) \ - { \ +#define io38_set_pwm(value) \ + { \ g_io_soft_pwm[PWM13 - PWM_PINS_OFFSET] = (0xFF & value); \ } #define io38_get_pwm g_io_soft_pwm[PWM13 - PWM_PINS_OFFSET] @@ -4205,12 +4205,12 @@ extern "C" #define io39_set_pwm(value) mcu_set_pwm(PWM14, value) #define io39_get_pwm mcu_get_pwm(PWM14) #elif ASSERT_PIN_EXTENDED(PWM14) -#define io39_config_pwm(freq) \ - { \ +#define io39_config_pwm(freq) \ + { \ g_soft_pwm_res = mcu_softpwm_freq_config(freq); \ } -#define io39_set_pwm(value) \ - { \ +#define io39_set_pwm(value) \ + { \ g_io_soft_pwm[PWM14 - PWM_PINS_OFFSET] = (0xFF & value); \ } #define io39_get_pwm g_io_soft_pwm[PWM14 - PWM_PINS_OFFSET] @@ -4224,12 +4224,12 @@ extern "C" #define io40_set_pwm(value) mcu_set_pwm(PWM15, value) #define io40_get_pwm mcu_get_pwm(PWM15) #elif ASSERT_PIN_EXTENDED(PWM15) -#define io40_config_pwm(freq) \ - { \ +#define io40_config_pwm(freq) \ + { \ g_soft_pwm_res = mcu_softpwm_freq_config(freq); \ } -#define io40_set_pwm(value) \ - { \ +#define io40_set_pwm(value) \ + { \ g_io_soft_pwm[PWM15 - PWM_PINS_OFFSET] = (0xFF & value); \ } #define io40_get_pwm g_io_soft_pwm[PWM15 - PWM_PINS_OFFSET] diff --git a/uCNC/src/hal/kinematics/kinematic.h b/uCNC/src/hal/kinematics/kinematic.h index 1fc4fb640..6fa8b9e35 100644 --- a/uCNC/src/hal/kinematics/kinematic.h +++ b/uCNC/src/hal/kinematics/kinematic.h @@ -91,7 +91,7 @@ extern "C" */ void kinematics_apply_reverse_transform(float *axis); - /** + /** * @brief Converts from machine absolute coordinates to step position. * This calls kinematics_apply_inverse after applying any custom geometry transformation (like skew compensation) * diff --git a/uCNC/src/hal/kinematics/kinematic_scara.h b/uCNC/src/hal/kinematics/kinematic_scara.h index 4f82cd295..d97892210 100644 --- a/uCNC/src/hal/kinematics/kinematic_scara.h +++ b/uCNC/src/hal/kinematics/kinematic_scara.h @@ -38,11 +38,10 @@ extern "C" #define KINEMATICS_MOTION_SEGMENT_SIZE 1.0f #endif - /* Enable Skew compensation */ - //#define ENABLE_SKEW_COMPENSATION + // #define ENABLE_SKEW_COMPENSATION #ifdef __cplusplus } diff --git a/uCNC/src/hal/mcus/avr/mcumap_avr.h b/uCNC/src/hal/mcus/avr/mcumap_avr.h index 8ace43598..ad285c566 100644 --- a/uCNC/src/hal/mcus/avr/mcumap_avr.h +++ b/uCNC/src/hal/mcus/avr/mcumap_avr.h @@ -4537,14 +4537,14 @@ extern "C" #ifndef BYTE_OPS #define BYTE_OPS -#define SETBIT(x, y) ((x) |= (1U << (y))) /* Set bit y in byte x*/ +#define SETBIT(x, y) ((x) |= (1U << (y))) /* Set bit y in byte x*/ #define CLEARBIT(x, y) ((x) &= ~(1U << (y))) /* Clear bit y in byte x*/ #define CHECKBIT(x, y) ((x) & (1U << (y))) /* Check bit y in byte x*/ #define TOGGLEBIT(x, y) ((x) ^= (1U << (y))) /* Toggle bit y in byte x*/ -#define SETFLAG(x, y) ((x) |= (y)) /* Set byte y in byte x*/ +#define SETFLAG(x, y) ((x) |= (y)) /* Set byte y in byte x*/ #define CLEARFLAG(x, y) ((x) &= ~(y)) /* Clear byte y in byte x*/ -#define CHECKFLAG(x, y) ((x) & (y)) /* Check byte y in byte x*/ +#define CHECKFLAG(x, y) ((x) & (y)) /* Check byte y in byte x*/ #define TOGGLEFLAG(x, y) ((x) ^= (y)) /* Toggle byte y in byte x*/ #endif @@ -4560,8 +4560,8 @@ extern "C" #define mcu_config_pullup(x) SETBIT(__indirect__(x, OUTREG), __indirect__(x, BIT)) #define mcu_config_input_isr(x) SETFLAG(__indirect__(x, ISRREG), __indirect__(x, ISR_MASK)) -#define mcu_config_pwm(x, freq) \ - { \ +#define mcu_config_pwm(x, freq) \ + { \ SETBIT(__indirect__(x, DIRREG), __indirect__(x, BIT)); \ CLEARBIT(__indirect__(x, OUTREG), __indirect__(x, BIT)); \ __indirect__(x, TMRAREG) |= __indirect__(x, MODE); \ @@ -4569,50 +4569,50 @@ extern "C" uint8_t pre = 1; \ if (div > 1) \ { \ - div = ((div + 1) >> 3); \ - pre++; \ + div = ((div + 1) >> 3); \ + pre++; \ } \ if (__indirect__(x, TIMER) == 2) \ { \ - if (div > 1) \ - { \ - div = ((div + 1) >> 2); \ - pre++; \ - } \ - while (div > 1) \ - { \ - div = ((div + 1) >> 1); \ - pre++; \ - } \ + if (div > 1) \ + { \ + div = ((div + 1) >> 2); \ + pre++; \ + } \ + while (div > 1) \ + { \ + div = ((div + 1) >> 1); \ + pre++; \ + } \ } \ else \ { \ - if (div > 1) \ - { \ - div = ((div + 1) >> 3); \ - pre++; \ - } \ - while (div > 1) \ - { \ - div = ((div + 1) >> 2); \ - pre++; \ - } \ + if (div > 1) \ + { \ + div = ((div + 1) >> 3); \ + pre++; \ + } \ + while (div > 1) \ + { \ + div = ((div + 1) >> 2); \ + pre++; \ + } \ } \ __indirect__(x, TMRBREG) = pre; \ __indirect__(x, OCRREG) = 0; \ } -#define mcu_set_pwm(diopin, pwmvalue) \ - { \ - __indirect__(diopin, OCRREG) = (uint16_t)pwmvalue; \ - if (pwmvalue != 0) \ - { \ +#define mcu_set_pwm(diopin, pwmvalue) \ + { \ + __indirect__(diopin, OCRREG) = (uint16_t)pwmvalue; \ + if (pwmvalue != 0) \ + { \ SETFLAG(__indirect__(diopin, TMRAREG), __indirect__(diopin, ENABLE_MASK)); \ - } \ - else \ - { \ + } \ + else \ + { \ CLEARFLAG(__indirect__(diopin, TMRAREG), __indirect__(diopin, ENABLE_MASK)); \ - } \ + } \ } #define mcu_get_pwm(diopin) (__indirect__(diopin, OCRREG)) @@ -4624,12 +4624,12 @@ extern "C" #define F_CPU 16000000UL #endif #define ADC_PRESC (_min(7, (0xff & ((uint8_t)((float)(F_CPU / 100000) / LOG2))))) -#define mcu_get_analog(diopin) \ - { \ +#define mcu_get_analog(diopin) \ + { \ ADMUX = (0x00 | __indirect__(diopin, CHANNEL)); \ ADCSRA = (0xC0 | ADC_PRESC); \ while (ADCSRA & 0x40) \ - ; \ + ; \ (0x3FF & ((ADCH << 8) | ADCL)); \ } @@ -4648,14 +4648,14 @@ extern "C" #define US_DELAY_TICK (F_CPU / 3000000UL) #define US_DELAY_TICK2 (F_CPU / 4000000UL) -#define mcu_free_micros() ((1000UL*RTC_TCNT)/RTC_OCRA) +#define mcu_free_micros() ((1000UL * RTC_TCNT) / RTC_OCRA) #ifdef MCU_HAS_SPI -#define mcu_spi_xmit(X) \ - ({ \ +#define mcu_spi_xmit(X) \ + ({ \ SPDR = X; \ while (!(SPSR & (1 << SPIF))) \ - ; \ + ; \ SPDR; \ }) #endif diff --git a/uCNC/src/hal/mcus/esp32/mcumap_esp32.h b/uCNC/src/hal/mcus/esp32/mcumap_esp32.h index 644a8268d..786f1ba83 100644 --- a/uCNC/src/hal/mcus/esp32/mcumap_esp32.h +++ b/uCNC/src/hal/mcus/esp32/mcumap_esp32.h @@ -2797,34 +2797,34 @@ extern "C" #define ic74hc595_get_pin(pin) (__atomic_load_n((uint32_t *)&ic74hc595_i2s_pins, __ATOMIC_RELAXED) & ic74hc595_pin_mask(pin)) #endif -#define mcu_config_output(X) \ - { \ +#define mcu_config_output(X) \ + { \ gpio_pad_select_gpio(__indirect__(X, BIT)); \ gpio_set_direction(__indirect__(X, BIT), GPIO_MODE_INPUT_OUTPUT); \ } -#define mcu_config_input(X) \ - { \ +#define mcu_config_input(X) \ + { \ gpio_pad_select_gpio(__indirect__(X, BIT)); \ gpio_set_direction(__indirect__(X, BIT), GPIO_MODE_INPUT); \ gpio_pulldown_dis(__indirect__(X, BIT)); \ gpio_pullup_dis(__indirect__(X, BIT)); \ } #define mcu_config_analog(X) \ - { \ - mcu_config_input(X); \ - adc1_config_width(ADC_WIDTH_MAX - 1); \ + { \ + mcu_config_input(X); \ + adc1_config_width(ADC_WIDTH_MAX - 1); \ adc1_config_channel_atten(__indirect__(X, ADC_CHANNEL), (ADC_ATTEN_MAX - 1)); \ } -#define mcu_config_pullup(X) \ - { \ +#define mcu_config_pullup(X) \ + { \ gpio_pad_select_gpio(__indirect__(X, BIT)); \ gpio_set_direction(__indirect__(X, BIT), GPIO_MODE_INPUT); \ gpio_pulldown_dis(__indirect__(X, BIT)); \ gpio_pullup_en(__indirect__(X, BIT)); \ } extern void mcu_gpio_isr(void *); -#define mcu_config_input_isr(X) \ - { \ +#define mcu_config_input_isr(X) \ + { \ gpio_set_intr_type((__indirect__(X, BIT)), GPIO_INTR_ANYEDGE); \ gpio_isr_handler_add((__indirect__(X, BIT)), mcu_gpio_isr, (void *)__indirect__(X, ISRVAR)); \ } @@ -2832,21 +2832,21 @@ extern "C" #define mcu_get_input(X) gpio_get_level(__indirect__(X, BIT)) // #define mcu_get_input(X) ((__indirect__(X,INREG)->IN) & (1UL<<(0x1F & __indirect__(X, BIT)))) #define mcu_get_output(X) ((__indirect__(X, OUTREG)->OUT) & (1UL << (0x1F & __indirect__(X, BIT)))) -#define mcu_set_output(X) \ - { \ +#define mcu_set_output(X) \ + { \ __indirect__(X, OUTREG)->OUTSET = (1UL << (0x1F & __indirect__(X, BIT))); \ } -#define mcu_clear_output(X) \ - { \ +#define mcu_clear_output(X) \ + { \ __indirect__(X, OUTREG)->OUTCLR = (1UL << (0x1F & __indirect__(X, BIT))); \ } -#define mcu_toggle_output(X) \ - { \ +#define mcu_toggle_output(X) \ + { \ __indirect__(X, OUTREG)->OUT ^= (1UL << (0x1F & __indirect__(X, BIT))); \ } -#define mcu_config_pwm(X, Y) \ - { \ +#define mcu_config_pwm(X, Y) \ + { \ ledc_timer_config_t pwmtimer = {0}; \ pwmtimer.speed_mode = __indirect__(X, SPEEDMODE); \ pwmtimer.timer_num = __indirect__(X, TIMER); \ @@ -2864,8 +2864,8 @@ extern "C" ledc_channel_config(&pwm); \ } -#define mcu_set_pwm(X, Y) \ - { \ +#define mcu_set_pwm(X, Y) \ + { \ ledc_set_duty(__indirect__(X, SPEEDMODE), __indirect__(X, LEDCCHANNEL), Y); \ ledc_update_duty(__indirect__(X, SPEEDMODE), __indirect__(X, LEDCCHANNEL)); \ } @@ -2880,11 +2880,11 @@ extern "C" #endif #include "xtensa/core-macros.h" -#define mcu_delay_cycles(X) \ - { \ +#define mcu_delay_cycles(X) \ + { \ uint32_t x = XTHAL_GET_CCOUNT(); \ while (X > (((uint32_t)XTHAL_GET_CCOUNT()) - x)) \ - ; \ + ; \ } #ifdef __cplusplus diff --git a/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h b/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h index e0b4e1037..a319d5f6d 100644 --- a/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h +++ b/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h @@ -1044,7 +1044,7 @@ extern "C" #define mcu_config_output(X) pinMode(__indirect__(X, BIT), OUTPUT) #define mcu_config_pwm(X, freq) \ - g_soft_pwm_res = 1; \ + g_soft_pwm_res = 1; \ pinMode(__indirect__(X, BIT), OUTPUT) #define mcu_config_input(X) pinMode(__indirect__(X, BIT), INPUT) #define mcu_config_analog(X) mcu_config_input(X) @@ -1059,27 +1059,27 @@ extern "C" #define mcu_get_analog(X) analogRead(__indirect__(X, BIT)) -#define mcu_spi_xmit(X) \ - { \ +#define mcu_spi_xmit(X) \ + { \ while (SPI1CMD & SPIBUSY) \ - ; \ + ; \ SPI1W0 = x; \ SPI1CMD |= SPIBUSY; \ while (SPI1CMD & SPIBUSY) \ - ; \ + ; \ (uint8_t)(SPI1W0 & 0xff); \ } -#define cpucount() \ - ({ \ +#define cpucount() \ + ({ \ uint32_t r; \ asm volatile("rsr %0, ccount" : "=r"(r)); \ r; \ }) -#define mcu_delay_cycles(X) \ - { \ - uint32_t start = cpucount(); \ +#define mcu_delay_cycles(X) \ + { \ + uint32_t start = cpucount(); \ uint32_t end; \ do \ { \ diff --git a/uCNC/src/hal/mcus/lpc176x/mcumap_lpc176x.h b/uCNC/src/hal/mcus/lpc176x/mcumap_lpc176x.h index e707fac7f..8a0f5b8d8 100644 --- a/uCNC/src/hal/mcus/lpc176x/mcumap_lpc176x.h +++ b/uCNC/src/hal/mcus/lpc176x/mcumap_lpc176x.h @@ -68,47 +68,47 @@ extern "C" #define rom_read_byte * #define __IM volatile const /*! Defines 'read only' structure member permissions */ -#define __IOM volatile /*! Defines 'read / write' structure member permissions */ +#define __IOM volatile /*! Defines 'read / write' structure member permissions */ typedef struct { - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */ - __IOM uint32_t CYCCNT; /*!< Offset: 0x004 (R/W) Cycle Count Register */ - __IOM uint32_t CPICNT; /*!< Offset: 0x008 (R/W) CPI Count Register */ - __IOM uint32_t EXCCNT; /*!< Offset: 0x00C (R/W) Exception Overhead Count Register */ - __IOM uint32_t SLEEPCNT; /*!< Offset: 0x010 (R/W) Sleep Count Register */ - __IOM uint32_t LSUCNT; /*!< Offset: 0x014 (R/W) LSU Count Register */ - __IOM uint32_t FOLDCNT; /*!< Offset: 0x018 (R/W) Folded-instruction Count Register */ - __IM uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */ - __IOM uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */ - __IOM uint32_t MASK0; /*!< Offset: 0x024 (R/W) Mask Register 0 */ + __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */ + __IOM uint32_t CYCCNT; /*!< Offset: 0x004 (R/W) Cycle Count Register */ + __IOM uint32_t CPICNT; /*!< Offset: 0x008 (R/W) CPI Count Register */ + __IOM uint32_t EXCCNT; /*!< Offset: 0x00C (R/W) Exception Overhead Count Register */ + __IOM uint32_t SLEEPCNT; /*!< Offset: 0x010 (R/W) Sleep Count Register */ + __IOM uint32_t LSUCNT; /*!< Offset: 0x014 (R/W) LSU Count Register */ + __IOM uint32_t FOLDCNT; /*!< Offset: 0x018 (R/W) Folded-instruction Count Register */ + __IM uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */ + __IOM uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */ + __IOM uint32_t MASK0; /*!< Offset: 0x024 (R/W) Mask Register 0 */ __IOM uint32_t FUNCTION0; /*!< Offset: 0x028 (R/W) Function Register 0 */ uint32_t RESERVED0[1U]; - __IOM uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */ - __IOM uint32_t MASK1; /*!< Offset: 0x034 (R/W) Mask Register 1 */ + __IOM uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */ + __IOM uint32_t MASK1; /*!< Offset: 0x034 (R/W) Mask Register 1 */ __IOM uint32_t FUNCTION1; /*!< Offset: 0x038 (R/W) Function Register 1 */ uint32_t RESERVED1[1U]; - __IOM uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */ - __IOM uint32_t MASK2; /*!< Offset: 0x044 (R/W) Mask Register 2 */ + __IOM uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */ + __IOM uint32_t MASK2; /*!< Offset: 0x044 (R/W) Mask Register 2 */ __IOM uint32_t FUNCTION2; /*!< Offset: 0x048 (R/W) Function Register 2 */ uint32_t RESERVED2[1U]; - __IOM uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */ - __IOM uint32_t MASK3; /*!< Offset: 0x054 (R/W) Mask Register 3 */ + __IOM uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */ + __IOM uint32_t MASK3; /*!< Offset: 0x054 (R/W) Mask Register 3 */ __IOM uint32_t FUNCTION3; /*!< Offset: 0x058 (R/W) Function Register 3 */ } DWT_Type; -#define DWT_BASE (0xE0001000UL) /*!< DWT Base Address */ +#define DWT_BASE (0xE0001000UL) /*!< DWT Base Address */ #define DWT ((DWT_Type *)DWT_BASE) /*!< DWT configuration struct */ // custom cycle counter #ifndef MCU_CLOCKS_PER_CYCLE #define MCU_CLOCKS_PER_CYCLE 1 #endif -#define mcu_delay_cycles(X) \ - { \ +#define mcu_delay_cycles(X) \ + { \ DWT->CYCCNT = 0; \ while (X > DWT->CYCCNT) \ - ; \ + ; \ } // Helper macros @@ -2871,7 +2871,6 @@ extern "C" #define DIO211_PINCON RX2_PINCON #endif - #if (defined(TX) && defined(RX)) #define MCU_HAS_UART #endif @@ -3841,37 +3840,37 @@ extern "C" #define __indirect__(X, Y) __indirect__ex__(X, Y) #endif -#define mcu_config_output(diopin) \ - { \ +#define mcu_config_output(diopin) \ + { \ SETBIT(__indirect__(diopin, GPIOREG)->FIODIR, __indirect__(diopin, BIT)); \ LPC_PINCON->__helper__(PINSEL, __indirect__(diopin, PINCON), ) &= ~(3 << ((__indirect__(diopin, BIT) & 0x0F) << 1)); \ } -#define mcu_config_output_od(diopin) \ - { \ +#define mcu_config_output_od(diopin) \ + { \ mcu_config_output(diopin); \ LPC_PINCON->__helper__(PINMODE, __indirect__(diopin, PINCON), ) &= ~(3 << ((__indirect__(diopin, BIT) & 0x0F) << 1)); \ LPC_PINCON->__helper__(PINMODE, __indirect__(diopin, PINCON), ) |= (2 << ((__indirect__(diopin, BIT) & 0x0F) << 1)); \ LPC_PINCON->__helper__(PINMODE_OD, __indirect__(diopin, PORT), ) |= (1 << (__indirect__(diopin, BIT))); \ } -#define mcu_config_input(diopin) \ - { \ +#define mcu_config_input(diopin) \ + { \ CLEARBIT(__indirect__(diopin, GPIOREG)->FIODIR, __indirect__(diopin, BIT)); \ LPC_PINCON->__helper__(PINSEL, __indirect__(diopin, PINCON), ) &= ~(3 << ((__indirect__(diopin, BIT) & 0x0F) << 1)); \ } -#define mcu_config_pullup(diopin) \ - { \ +#define mcu_config_pullup(diopin) \ + { \ LPC_PINCON->__helper__(PINMODE, __indirect__(diopin, PINCON), ) &= ~(3 << ((__indirect__(diopin, BIT) & 0x0F) << 1)); \ } -#define mcu_config_af(diopin, mode) \ - { \ +#define mcu_config_af(diopin, mode) \ + { \ LPC_PINCON->__helper__(PINSEL, __indirect__(diopin, PINCON), ) &= ~(3 << ((__indirect__(diopin, BIT) & 0x0F) << 1)); \ LPC_PINCON->__helper__(PINSEL, __indirect__(diopin, PINCON), ) |= (mode << ((__indirect__(diopin, BIT) & 0x0F) << 1)); \ } -#define mcu_config_analog(diopin) \ - { \ +#define mcu_config_analog(diopin) \ + { \ mcu_config_input(diopin); \ mcu_config_af(diopin, __indirect__(diopin, ALT_FUNC)); \ LPC_SC->PCONP |= CLKPWR_PCONP_PCAD; \ @@ -3882,8 +3881,8 @@ extern "C" LPC_ADC->ADCR |= ADC_CR_BURST; \ } -#define mcu_config_input_isr(diopin) \ - { \ +#define mcu_config_input_isr(diopin) \ + { \ SETBIT(LPC_GPIOINT->__indirect__(diopin, RISEREG), __indirect__(diopin, BIT)); \ SETBIT(LPC_GPIOINT->__indirect__(diopin, FALLREG), __indirect__(diopin, BIT)); \ NVIC_SetPriority(EINT3_IRQn, 5); \ @@ -3891,8 +3890,8 @@ extern "C" NVIC_EnableIRQ(EINT3_IRQn); \ } -#define mcu_config_pwm(diopin, freq) \ - { \ +#define mcu_config_pwm(diopin, freq) \ + { \ mcu_config_output(diopin); \ LPC_SC->PCONP |= CLKPWR_PCONP_PCPWM1; \ LPC_SC->PCLKSEL0 &= ~(3 << 12); /* div clock by 4 */ \ @@ -3918,8 +3917,8 @@ extern "C" #define mcu_set_output(diopin) (__indirect__(diopin, GPIOREG)->FIOSET = (1 << __indirect__(diopin, BIT))) #define mcu_clear_output(diopin) (__indirect__(diopin, GPIOREG)->FIOCLR = (1 << __indirect__(diopin, BIT))) #define mcu_toggle_output(diopin) TOGGLEBIT(__indirect__(diopin, GPIOREG)->FIOPIN, __indirect__(diopin, BIT)) -#define mcu_set_pwm(diopin, pwmvalue) \ - { \ +#define mcu_set_pwm(diopin, pwmvalue) \ + { \ LPC_PWM1->__indirect__(diopin, MR) = pwmvalue; \ LPC_PWM1->LER |= ((uint32_t)(((__indirect__(diopin, CHANNEL)) < 7) ? (1 << (__indirect__(diopin, CHANNEL))) : 0)); \ LPC_PWM1->TCR |= ((uint32_t)(1 << 1)); \ @@ -3930,24 +3929,24 @@ extern "C" #define mcu_get_analog(diopin) (uint16_t)(((LPC_ADC->__indirect__(diopin, ADDR)) >> 2) & 0x03FF) extern volatile bool lpc_global_isr_enabled; -#define mcu_enable_global_isr() \ - { \ +#define mcu_enable_global_isr() \ + { \ __enable_irq(); \ lpc_global_isr_enabled = true; \ } -#define mcu_disable_global_isr() \ - { \ +#define mcu_disable_global_isr() \ + { \ lpc_global_isr_enabled = false; \ __disable_irq(); \ } #define mcu_get_global_isr() lpc_global_isr_enabled -#define mcu_free_micros() ({(1000UL - (SysTick->VAL * 1000UL / SysTick->LOAD));}) +#define mcu_free_micros() ({ (1000UL - (SysTick->VAL * 1000UL / SysTick->LOAD)); }) -#define mcu_spi_xmit(X) \ - ({ \ +#define mcu_spi_xmit(X) \ + ({ \ SPI_REG->DR = X; \ while (!(SPI_REG->SR & SSP_SR_RNE)) \ - ; \ + ; \ SPI_REG->DR; \ }) diff --git a/uCNC/src/hal/mcus/mcu.h b/uCNC/src/hal/mcus/mcu.h index c4f7da899..ecfb65823 100644 --- a/uCNC/src/hal/mcus/mcu.h +++ b/uCNC/src/hal/mcus/mcu.h @@ -334,103 +334,103 @@ extern "C" #error "MCU_CYCLES_PER_LOOP_OVERHEAD not defined for this MCU" #endif -#define mcu_delay_cycles(X) \ - { \ - if (X > (MCU_CYCLES_PER_LOOP + MCU_CYCLES_PER_LOOP_OVERHEAD)) \ - { \ +#define mcu_delay_cycles(X) \ + { \ + if (X > (MCU_CYCLES_PER_LOOP + MCU_CYCLES_PER_LOOP_OVERHEAD)) \ + { \ mcu_delay_loop((uint16_t)((X - MCU_CYCLES_PER_LOOP_OVERHEAD) / MCU_CYCLES_PER_LOOP)); \ if (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) - (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 0) \ { \ - mcu_nop(); \ + mcu_nop(); \ } \ if (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) - (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 1) \ { \ - mcu_nop(); \ + mcu_nop(); \ } \ if (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) - (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 2) \ { \ - mcu_nop(); \ + mcu_nop(); \ } \ if (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) - (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 3) \ { \ - mcu_nop(); \ + mcu_nop(); \ } \ if (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) - (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 4) \ { \ - mcu_nop(); \ + mcu_nop(); \ } \ if (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) - (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 5) \ { \ - mcu_nop(); \ + mcu_nop(); \ } \ if (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) - (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 6) \ { \ - mcu_nop(); \ + mcu_nop(); \ } \ if (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) - (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 7) \ { \ - mcu_nop(); \ + mcu_nop(); \ } \ if (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) - (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 8) \ { \ - mcu_nop(); \ + mcu_nop(); \ } \ if (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) - (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 9) \ { \ - mcu_nop(); \ + mcu_nop(); \ } \ if (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) - (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 10) \ { \ - mcu_nop(); \ + mcu_nop(); \ } \ - } \ - else \ - { \ + } \ + else \ + { \ if ((X - ((X / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 0) \ { \ - mcu_nop(); \ + mcu_nop(); \ } \ if ((X - ((X / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 1) \ { \ - mcu_nop(); \ + mcu_nop(); \ } \ if ((X - ((X / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 2) \ { \ - mcu_nop(); \ + mcu_nop(); \ } \ if ((X - ((X / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 3) \ { \ - mcu_nop(); \ + mcu_nop(); \ } \ if ((X - ((X / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 4) \ { \ - mcu_nop(); \ + mcu_nop(); \ } \ if ((X - ((X / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 5) \ { \ - mcu_nop(); \ + mcu_nop(); \ } \ if ((X - ((X / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 6) \ { \ - mcu_nop(); \ + mcu_nop(); \ } \ if ((X - ((X / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 7) \ { \ - mcu_nop(); \ + mcu_nop(); \ } \ if ((X - ((X / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 8) \ { \ - mcu_nop(); \ + mcu_nop(); \ } \ if ((X - ((X / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 9) \ { \ - mcu_nop(); \ + mcu_nop(); \ } \ if ((X - ((X / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 10) \ { \ - mcu_nop(); \ + mcu_nop(); \ } \ - } \ + } \ } #endif diff --git a/uCNC/src/hal/mcus/rp2040/ic74hc595.pio.h b/uCNC/src/hal/mcus/rp2040/ic74hc595.pio.h index ca630e7e3..8afd0be2f 100644 --- a/uCNC/src/hal/mcus/rp2040/ic74hc595.pio.h +++ b/uCNC/src/hal/mcus/rp2040/ic74hc595.pio.h @@ -16,32 +16,34 @@ #define ic74hc595_wrap 5 static const uint16_t ic74hc595_program_instructions[] = { - // .wrap_target - 0x80a0, // 0: pull block - 0xe03f, // 1: set x, 31 - 0xe000, // 2: set pins, 0 - 0x7001, // 3: out pins, 1 side 0 - 0x1843, // 4: jmp x--, 3 side 1 - 0xe002, // 5: set pins, 2 - // .wrap + // .wrap_target + 0x80a0, // 0: pull block + 0xe03f, // 1: set x, 31 + 0xe000, // 2: set pins, 0 + 0x7001, // 3: out pins, 1 side 0 + 0x1843, // 4: jmp x--, 3 side 1 + 0xe002, // 5: set pins, 2 + // .wrap }; #if !PICO_NO_HARDWARE static const struct pio_program ic74hc595_program = { - .instructions = ic74hc595_program_instructions, - .length = 6, - .origin = -1, + .instructions = ic74hc595_program_instructions, + .length = 6, + .origin = -1, }; -static inline pio_sm_config ic74hc595_program_get_default_config(uint offset) { - pio_sm_config c = pio_get_default_sm_config(); - sm_config_set_wrap(&c, offset + ic74hc595_wrap_target, offset + ic74hc595_wrap); - sm_config_set_sideset(&c, 2, true, false); - return c; +static inline pio_sm_config ic74hc595_program_get_default_config(uint offset) +{ + pio_sm_config c = pio_get_default_sm_config(); + sm_config_set_wrap(&c, offset + ic74hc595_wrap_target, offset + ic74hc595_wrap); + sm_config_set_sideset(&c, 2, true, false); + return c; } #include "hardware/clocks.h" -static inline void ic74hc595_program_init(PIO pio, uint sm, uint offset, uint pin_data, uint pin_clk, uint pin_latch, uint freq) { +static inline void ic74hc595_program_init(PIO pio, uint sm, uint offset, uint pin_data, uint pin_clk, uint pin_latch, uint freq) +{ pio_sm_config c = ic74hc595_program_get_default_config(offset); sm_config_set_out_pins(&c, pin_data, 1); // define one pin to respond to the out instruction sm_config_set_set_pins(&c, pin_clk, 2); // define all pins to respond to the set instruction @@ -61,8 +63,9 @@ static inline void ic74hc595_program_init(PIO pio, uint sm, uint offset, uint pi pio_sm_init(pio, sm, offset, &c); pio_sm_set_enabled(pio, sm, true); } -static inline void ic74hc595_program_write(PIO pio, uint sm, uint out) { - pio_sm_put_blocking(pio, sm, out); +static inline void ic74hc595_program_write(PIO pio, uint sm, uint out) +{ + pio_sm_put_blocking(pio, sm, out); } #endif diff --git a/uCNC/src/hal/mcus/rp2040/mcumap_rp2040.h b/uCNC/src/hal/mcus/rp2040/mcumap_rp2040.h index fe6a720f0..3813537eb 100644 --- a/uCNC/src/hal/mcus/rp2040/mcumap_rp2040.h +++ b/uCNC/src/hal/mcus/rp2040/mcumap_rp2040.h @@ -1126,20 +1126,20 @@ extern "C" #ifndef BYTE_OPS #define BYTE_OPS -#define SETBIT(x, y) ((x) |= (1UL << (y))) /* Set bit y in byte x*/ +#define SETBIT(x, y) ((x) |= (1UL << (y))) /* Set bit y in byte x*/ #define CLEARBIT(x, y) ((x) &= ~(1UL << (y))) /* Clear bit y in byte x*/ -#define CHECKBIT(x, y) ((x) & (1UL << (y))) /* Check bit y in byte x*/ +#define CHECKBIT(x, y) ((x) & (1UL << (y))) /* Check bit y in byte x*/ #define TOGGLEBIT(x, y) ((x) ^= (1UL << (y))) /* Toggle bit y in byte x*/ -#define SETFLAG(x, y) ((x) |= (y)) /* Set byte y in byte x*/ +#define SETFLAG(x, y) ((x) |= (y)) /* Set byte y in byte x*/ #define CLEARFLAG(x, y) ((x) &= ~(y)) /* Clear byte y in byte x*/ -#define CHECKFLAG(x, y) ((x) & (y)) /* Check byte y in byte x*/ +#define CHECKFLAG(x, y) ((x) & (y)) /* Check byte y in byte x*/ #define TOGGLEFLAG(x, y) ((x) ^= (y)) /* Toggle byte y in byte x*/ #endif #define mcu_config_output(X) pinMode(__indirect__(X, BIT), OUTPUT) -#define mcu_config_pwm(X, freq) \ - { \ +#define mcu_config_pwm(X, freq) \ + { \ pinMode(__indirect__(X, BIT), OUTPUT); \ analogWriteRange(255); \ analogWriteFreq(freq); \ @@ -1157,8 +1157,8 @@ extern "C" #define mcu_toggle_output(X) ({ sio_hw->gpio_togl = (1UL << __indirect__(X, BIT)); }) extern uint8_t rp2040_pwm[16]; -#define mcu_set_pwm(X, Y) \ - { \ +#define mcu_set_pwm(X, Y) \ + { \ rp2040_pwm[X - PWM_PINS_OFFSET] = Y; \ analogWrite(__indirect__(X, BIT), Y); \ } @@ -1167,7 +1167,7 @@ extern "C" #define mcu_millis() millis() #define mcu_micros() micros() -#define mcu_free_micros() ({(1000UL - (SysTick->VAL * 1000UL / SysTick->LOAD));}) +#define mcu_free_micros() ({ (1000UL - (SysTick->VAL * 1000UL / SysTick->LOAD)); }) #if (defined(ENABLE_WIFI) || defined(ENABLE_BLUETOOTH)) #ifndef BOARD_HAS_CUSTOM_SYSTEM_COMMANDS diff --git a/uCNC/src/hal/mcus/samd21/mcumap_samd21.h b/uCNC/src/hal/mcus/samd21/mcumap_samd21.h index e5b32b6ab..57e40b4fd 100644 --- a/uCNC/src/hal/mcus/samd21/mcumap_samd21.h +++ b/uCNC/src/hal/mcus/samd21/mcumap_samd21.h @@ -1314,9 +1314,9 @@ extern "C" #endif #if (defined(USB_DP) && defined(USB_DM)) #define MCU_HAS_USB -extern uint32_t tud_cdc_n_write_available(uint8_t itf); -extern uint32_t tud_cdc_n_available(uint8_t itf); -extern bool tud_cdc_n_connected (uint8_t itf); + extern uint32_t tud_cdc_n_write_available(uint8_t itf); + extern uint32_t tud_cdc_n_available(uint8_t itf); + extern bool tud_cdc_n_connected(uint8_t itf); #define usb_tx_available() (tud_cdc_n_write_available(0) || !tud_cdc_n_connected(0)) #define usb_rx_available() tud_cdc_n_available(0) #endif @@ -1967,41 +1967,41 @@ extern bool tud_cdc_n_connected (uint8_t itf); #define PWM0_PMUXVAL (pinmuxval(PWM0_MUX)) #if (PWM0_TIMER < 3) #define PWM0_TMR __helper__(TCC, PWM0_TIMER, ) -#define PWM0_CONFIG \ - { \ +#define PWM0_CONFIG \ + { \ PWM0_TMR->CTRLA.bit.SWRST = 1; \ while (PWM0_TMR->SYNCBUSY.bit.SWRST) \ - ; \ + ; \ PWM0_TMR->CTRLA.bit.PRESCALER = 2; \ PWM0_TMR->WAVE.bit.WAVEGEN = 2; \ while (PWM0_TMR->SYNCBUSY.bit.WAVE) \ - ; \ + ; \ PWM0_TMR->PER.bit.PER = 255; \ while (PWM0_TMR->SYNCBUSY.bit.PER) \ - ; \ + ; \ PWM0_TMR->CTRLA.bit.ENABLE = 1; \ while (PWM0_TMR->SYNCBUSY.bit.ENABLE) \ - ; \ + ; \ } #define PWM0_DUTYCYCLE (PWM0_TMR->CC[PWM0_CHANNEL].bit.CC) #else #define PWM0_TMR __helper__(TC, PWM0_TIMER, ) -#define PWM0_CONFIG \ - { \ +#define PWM0_CONFIG \ + { \ PWM0_TMR->COUNT8.CTRLA.bit.SWRST = 1; \ while (PWM0_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM0_TMR->COUNT8.CTRLA.bit.MODE = 1; \ PWM0_TMR->COUNT8.CTRLA.bit.PRESCALER = 2; \ PWM0_TMR->COUNT8.CTRLA.bit.WAVEGEN = 2; \ while (PWM0_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM0_TMR->COUNT8.PER.reg = 255; \ while (PWM0_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM0_TMR->COUNT8.CTRLA.bit.ENABLE = 1; \ while (PWM0_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ } #define PWM0_DUTYCYCLE (PWM0_TMR->COUNT8.CC[PWM0_CHANNEL].reg) #endif @@ -2017,41 +2017,41 @@ extern bool tud_cdc_n_connected (uint8_t itf); #define PWM1_PMUXVAL (pinmuxval(PWM1_MUX)) #if (PWM1_TIMER < 3) #define PWM1_TMR __helper__(TCC, PWM1_TIMER, ) -#define PWM1_CONFIG \ - { \ +#define PWM1_CONFIG \ + { \ PWM1_TMR->CTRLA.bit.SWRST = 1; \ while (PWM1_TMR->SYNCBUSY.bit.SWRST) \ - ; \ + ; \ PWM1_TMR->CTRLA.bit.PRESCALER = 2; \ PWM1_TMR->WAVE.bit.WAVEGEN = 2; \ while (PWM1_TMR->SYNCBUSY.bit.WAVE) \ - ; \ + ; \ PWM1_TMR->PER.bit.PER = 255; \ while (PWM1_TMR->SYNCBUSY.bit.PER) \ - ; \ + ; \ PWM1_TMR->CTRLA.bit.ENABLE = 1; \ while (PWM1_TMR->SYNCBUSY.bit.ENABLE) \ - ; \ + ; \ } #define PWM1_DUTYCYCLE (PWM1_TMR->CC[PWM1_CHANNEL].bit.CC) #else #define PWM1_TMR __helper__(TC, PWM1_TIMER, ) -#define PWM1_CONFIG \ - { \ +#define PWM1_CONFIG \ + { \ PWM1_TMR->COUNT8.CTRLA.bit.SWRST = 1; \ while (PWM1_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM1_TMR->COUNT8.CTRLA.bit.MODE = 1; \ PWM1_TMR->COUNT8.CTRLA.bit.PRESCALER = 2; \ PWM1_TMR->COUNT8.CTRLA.bit.WAVEGEN = 2; \ while (PWM1_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM1_TMR->COUNT8.PER.reg = 255; \ while (PWM1_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM1_TMR->COUNT8.CTRLA.bit.ENABLE = 1; \ while (PWM1_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ } #define PWM1_DUTYCYCLE (PWM1_TMR->COUNT8.CC[PWM1_CHANNEL].reg) #endif @@ -2067,41 +2067,41 @@ extern bool tud_cdc_n_connected (uint8_t itf); #define PWM2_PMUXVAL (pinmuxval(PWM2_MUX)) #if (PWM2_TIMER < 3) #define PWM2_TMR __helper__(TCC, PWM2_TIMER, ) -#define PWM2_CONFIG \ - { \ +#define PWM2_CONFIG \ + { \ PWM2_TMR->CTRLA.bit.SWRST = 1; \ while (PWM2_TMR->SYNCBUSY.bit.SWRST) \ - ; \ + ; \ PWM2_TMR->CTRLA.bit.PRESCALER = 2; \ PWM2_TMR->WAVE.bit.WAVEGEN = 2; \ while (PWM2_TMR->SYNCBUSY.bit.WAVE) \ - ; \ + ; \ PWM2_TMR->PER.bit.PER = 255; \ while (PWM2_TMR->SYNCBUSY.bit.PER) \ - ; \ + ; \ PWM2_TMR->CTRLA.bit.ENABLE = 1; \ while (PWM2_TMR->SYNCBUSY.bit.ENABLE) \ - ; \ + ; \ } #define PWM2_DUTYCYCLE (PWM2_TMR->CC[PWM2_CHANNEL].bit.CC) #else #define PWM2_TMR __helper__(TC, PWM2_TIMER, ) -#define PWM2_CONFIG \ - { \ +#define PWM2_CONFIG \ + { \ PWM2_TMR->COUNT8.CTRLA.bit.SWRST = 1; \ while (PWM2_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM2_TMR->COUNT8.CTRLA.bit.MODE = 1; \ PWM2_TMR->COUNT8.CTRLA.bit.PRESCALER = 2; \ PWM2_TMR->COUNT8.CTRLA.bit.WAVEGEN = 2; \ while (PWM2_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM2_TMR->COUNT8.PER.reg = 255; \ while (PWM2_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM2_TMR->COUNT8.CTRLA.bit.ENABLE = 1; \ while (PWM2_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ } #define PWM2_DUTYCYCLE (PWM2_TMR->COUNT8.CC[PWM2_CHANNEL].reg) #endif @@ -2117,41 +2117,41 @@ extern bool tud_cdc_n_connected (uint8_t itf); #define PWM3_PMUXVAL (pinmuxval(PWM3_MUX)) #if (PWM3_TIMER < 3) #define PWM3_TMR __helper__(TCC, PWM3_TIMER, ) -#define PWM3_CONFIG \ - { \ +#define PWM3_CONFIG \ + { \ PWM3_TMR->CTRLA.bit.SWRST = 1; \ while (PWM3_TMR->SYNCBUSY.bit.SWRST) \ - ; \ + ; \ PWM3_TMR->CTRLA.bit.PRESCALER = 2; \ PWM3_TMR->WAVE.bit.WAVEGEN = 2; \ while (PWM3_TMR->SYNCBUSY.bit.WAVE) \ - ; \ + ; \ PWM3_TMR->PER.bit.PER = 255; \ while (PWM3_TMR->SYNCBUSY.bit.PER) \ - ; \ + ; \ PWM3_TMR->CTRLA.bit.ENABLE = 1; \ while (PWM3_TMR->SYNCBUSY.bit.ENABLE) \ - ; \ + ; \ } #define PWM3_DUTYCYCLE (PWM3_TMR->CC[PWM3_CHANNEL].bit.CC) #else #define PWM3_TMR __helper__(TC, PWM3_TIMER, ) -#define PWM3_CONFIG \ - { \ +#define PWM3_CONFIG \ + { \ PWM3_TMR->COUNT8.CTRLA.bit.SWRST = 1; \ while (PWM3_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM3_TMR->COUNT8.CTRLA.bit.MODE = 1; \ PWM3_TMR->COUNT8.CTRLA.bit.PRESCALER = 2; \ PWM3_TMR->COUNT8.CTRLA.bit.WAVEGEN = 2; \ while (PWM3_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM3_TMR->COUNT8.PER.reg = 255; \ while (PWM3_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM3_TMR->COUNT8.CTRLA.bit.ENABLE = 1; \ while (PWM3_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ } #define PWM3_DUTYCYCLE (PWM3_TMR->COUNT8.CC[PWM3_CHANNEL].reg) #endif @@ -2167,41 +2167,41 @@ extern bool tud_cdc_n_connected (uint8_t itf); #define PWM4_PMUXVAL (pinmuxval(PWM4_MUX)) #if (PWM4_TIMER < 3) #define PWM4_TMR __helper__(TCC, PWM4_TIMER, ) -#define PWM4_CONFIG \ - { \ +#define PWM4_CONFIG \ + { \ PWM4_TMR->CTRLA.bit.SWRST = 1; \ while (PWM4_TMR->SYNCBUSY.bit.SWRST) \ - ; \ + ; \ PWM4_TMR->CTRLA.bit.PRESCALER = 2; \ PWM4_TMR->WAVE.bit.WAVEGEN = 2; \ while (PWM4_TMR->SYNCBUSY.bit.WAVE) \ - ; \ + ; \ PWM4_TMR->PER.bit.PER = 255; \ while (PWM4_TMR->SYNCBUSY.bit.PER) \ - ; \ + ; \ PWM4_TMR->CTRLA.bit.ENABLE = 1; \ while (PWM4_TMR->SYNCBUSY.bit.ENABLE) \ - ; \ + ; \ } #define PWM4_DUTYCYCLE (PWM4_TMR->CC[PWM4_CHANNEL].bit.CC) #else #define PWM4_TMR __helper__(TC, PWM4_TIMER, ) -#define PWM4_CONFIG \ - { \ +#define PWM4_CONFIG \ + { \ PWM4_TMR->COUNT8.CTRLA.bit.SWRST = 1; \ while (PWM4_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM4_TMR->COUNT8.CTRLA.bit.MODE = 1; \ PWM4_TMR->COUNT8.CTRLA.bit.PRESCALER = 2; \ PWM4_TMR->COUNT8.CTRLA.bit.WAVEGEN = 2; \ while (PWM4_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM4_TMR->COUNT8.PER.reg = 255; \ while (PWM4_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM4_TMR->COUNT8.CTRLA.bit.ENABLE = 1; \ while (PWM4_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ } #define PWM4_DUTYCYCLE (PWM4_TMR->COUNT8.CC[PWM4_CHANNEL].reg) #endif @@ -2217,41 +2217,41 @@ extern bool tud_cdc_n_connected (uint8_t itf); #define PWM5_PMUXVAL (pinmuxval(PWM5_MUX)) #if (PWM5_TIMER < 3) #define PWM5_TMR __helper__(TCC, PWM5_TIMER, ) -#define PWM5_CONFIG \ - { \ +#define PWM5_CONFIG \ + { \ PWM5_TMR->CTRLA.bit.SWRST = 1; \ while (PWM5_TMR->SYNCBUSY.bit.SWRST) \ - ; \ + ; \ PWM5_TMR->CTRLA.bit.PRESCALER = 2; \ PWM5_TMR->WAVE.bit.WAVEGEN = 2; \ while (PWM5_TMR->SYNCBUSY.bit.WAVE) \ - ; \ + ; \ PWM5_TMR->PER.bit.PER = 255; \ while (PWM5_TMR->SYNCBUSY.bit.PER) \ - ; \ + ; \ PWM5_TMR->CTRLA.bit.ENABLE = 1; \ while (PWM5_TMR->SYNCBUSY.bit.ENABLE) \ - ; \ + ; \ } #define PWM5_DUTYCYCLE (PWM5_TMR->CC[PWM5_CHANNEL].bit.CC) #else #define PWM5_TMR __helper__(TC, PWM5_TIMER, ) -#define PWM5_CONFIG \ - { \ +#define PWM5_CONFIG \ + { \ PWM5_TMR->COUNT8.CTRLA.bit.SWRST = 1; \ while (PWM5_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM5_TMR->COUNT8.CTRLA.bit.MODE = 1; \ PWM5_TMR->COUNT8.CTRLA.bit.PRESCALER = 2; \ PWM5_TMR->COUNT8.CTRLA.bit.WAVEGEN = 2; \ while (PWM5_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM5_TMR->COUNT8.PER.reg = 255; \ while (PWM5_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM5_TMR->COUNT8.CTRLA.bit.ENABLE = 1; \ while (PWM5_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ } #define PWM5_DUTYCYCLE (PWM5_TMR->COUNT8.CC[PWM5_CHANNEL].reg) #endif @@ -2267,41 +2267,41 @@ extern bool tud_cdc_n_connected (uint8_t itf); #define PWM6_PMUXVAL (pinmuxval(PWM6_MUX)) #if (PWM6_TIMER < 3) #define PWM6_TMR __helper__(TCC, PWM6_TIMER, ) -#define PWM6_CONFIG \ - { \ +#define PWM6_CONFIG \ + { \ PWM6_TMR->CTRLA.bit.SWRST = 1; \ while (PWM6_TMR->SYNCBUSY.bit.SWRST) \ - ; \ + ; \ PWM6_TMR->CTRLA.bit.PRESCALER = 2; \ PWM6_TMR->WAVE.bit.WAVEGEN = 2; \ while (PWM6_TMR->SYNCBUSY.bit.WAVE) \ - ; \ + ; \ PWM6_TMR->PER.bit.PER = 255; \ while (PWM6_TMR->SYNCBUSY.bit.PER) \ - ; \ + ; \ PWM6_TMR->CTRLA.bit.ENABLE = 1; \ while (PWM6_TMR->SYNCBUSY.bit.ENABLE) \ - ; \ + ; \ } #define PWM6_DUTYCYCLE (PWM6_TMR->CC[PWM6_CHANNEL].bit.CC) #else #define PWM6_TMR __helper__(TC, PWM6_TIMER, ) -#define PWM6_CONFIG \ - { \ +#define PWM6_CONFIG \ + { \ PWM6_TMR->COUNT8.CTRLA.bit.SWRST = 1; \ while (PWM6_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM6_TMR->COUNT8.CTRLA.bit.MODE = 1; \ PWM6_TMR->COUNT8.CTRLA.bit.PRESCALER = 2; \ PWM6_TMR->COUNT8.CTRLA.bit.WAVEGEN = 2; \ while (PWM6_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM6_TMR->COUNT8.PER.reg = 255; \ while (PWM6_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM6_TMR->COUNT8.CTRLA.bit.ENABLE = 1; \ while (PWM6_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ } #define PWM6_DUTYCYCLE (PWM6_TMR->COUNT8.CC[PWM6_CHANNEL].reg) #endif @@ -2317,41 +2317,41 @@ extern bool tud_cdc_n_connected (uint8_t itf); #define PWM7_PMUXVAL (pinmuxval(PWM7_MUX)) #if (PWM7_TIMER < 3) #define PWM7_TMR __helper__(TCC, PWM7_TIMER, ) -#define PWM7_CONFIG \ - { \ +#define PWM7_CONFIG \ + { \ PWM7_TMR->CTRLA.bit.SWRST = 1; \ while (PWM7_TMR->SYNCBUSY.bit.SWRST) \ - ; \ + ; \ PWM7_TMR->CTRLA.bit.PRESCALER = 2; \ PWM7_TMR->WAVE.bit.WAVEGEN = 2; \ while (PWM7_TMR->SYNCBUSY.bit.WAVE) \ - ; \ + ; \ PWM7_TMR->PER.bit.PER = 255; \ while (PWM7_TMR->SYNCBUSY.bit.PER) \ - ; \ + ; \ PWM7_TMR->CTRLA.bit.ENABLE = 1; \ while (PWM7_TMR->SYNCBUSY.bit.ENABLE) \ - ; \ + ; \ } #define PWM7_DUTYCYCLE (PWM7_TMR->CC[PWM7_CHANNEL].bit.CC) #else #define PWM7_TMR __helper__(TC, PWM7_TIMER, ) -#define PWM7_CONFIG \ - { \ +#define PWM7_CONFIG \ + { \ PWM7_TMR->COUNT8.CTRLA.bit.SWRST = 1; \ while (PWM7_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM7_TMR->COUNT8.CTRLA.bit.MODE = 1; \ PWM7_TMR->COUNT8.CTRLA.bit.PRESCALER = 2; \ PWM7_TMR->COUNT8.CTRLA.bit.WAVEGEN = 2; \ while (PWM7_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM7_TMR->COUNT8.PER.reg = 255; \ while (PWM7_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM7_TMR->COUNT8.CTRLA.bit.ENABLE = 1; \ while (PWM7_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ } #define PWM7_DUTYCYCLE (PWM7_TMR->COUNT8.CC[PWM7_CHANNEL].reg) #endif @@ -2367,41 +2367,41 @@ extern bool tud_cdc_n_connected (uint8_t itf); #define PWM8_PMUXVAL (pinmuxval(PWM8_MUX)) #if (PWM8_TIMER < 3) #define PWM8_TMR __helper__(TCC, PWM8_TIMER, ) -#define PWM8_CONFIG \ - { \ +#define PWM8_CONFIG \ + { \ PWM8_TMR->CTRLA.bit.SWRST = 1; \ while (PWM8_TMR->SYNCBUSY.bit.SWRST) \ - ; \ + ; \ PWM8_TMR->CTRLA.bit.PRESCALER = 2; \ PWM8_TMR->WAVE.bit.WAVEGEN = 2; \ while (PWM8_TMR->SYNCBUSY.bit.WAVE) \ - ; \ + ; \ PWM8_TMR->PER.bit.PER = 255; \ while (PWM8_TMR->SYNCBUSY.bit.PER) \ - ; \ + ; \ PWM8_TMR->CTRLA.bit.ENABLE = 1; \ while (PWM8_TMR->SYNCBUSY.bit.ENABLE) \ - ; \ + ; \ } #define PWM8_DUTYCYCLE (PWM8_TMR->CC[PWM8_CHANNEL].bit.CC) #else #define PWM8_TMR __helper__(TC, PWM8_TIMER, ) -#define PWM8_CONFIG \ - { \ +#define PWM8_CONFIG \ + { \ PWM8_TMR->COUNT8.CTRLA.bit.SWRST = 1; \ while (PWM8_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM8_TMR->COUNT8.CTRLA.bit.MODE = 1; \ PWM8_TMR->COUNT8.CTRLA.bit.PRESCALER = 2; \ PWM8_TMR->COUNT8.CTRLA.bit.WAVEGEN = 2; \ while (PWM8_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM8_TMR->COUNT8.PER.reg = 255; \ while (PWM8_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM8_TMR->COUNT8.CTRLA.bit.ENABLE = 1; \ while (PWM8_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ } #define PWM8_DUTYCYCLE (PWM8_TMR->COUNT8.CC[PWM8_CHANNEL].reg) #endif @@ -2417,41 +2417,41 @@ extern bool tud_cdc_n_connected (uint8_t itf); #define PWM9_PMUXVAL (pinmuxval(PWM9_MUX)) #if (PWM9_TIMER < 3) #define PWM9_TMR __helper__(TCC, PWM9_TIMER, ) -#define PWM9_CONFIG \ - { \ +#define PWM9_CONFIG \ + { \ PWM9_TMR->CTRLA.bit.SWRST = 1; \ while (PWM9_TMR->SYNCBUSY.bit.SWRST) \ - ; \ + ; \ PWM9_TMR->CTRLA.bit.PRESCALER = 2; \ PWM9_TMR->WAVE.bit.WAVEGEN = 2; \ while (PWM9_TMR->SYNCBUSY.bit.WAVE) \ - ; \ + ; \ PWM9_TMR->PER.bit.PER = 255; \ while (PWM9_TMR->SYNCBUSY.bit.PER) \ - ; \ + ; \ PWM9_TMR->CTRLA.bit.ENABLE = 1; \ while (PWM9_TMR->SYNCBUSY.bit.ENABLE) \ - ; \ + ; \ } #define PWM9_DUTYCYCLE (PWM9_TMR->CC[PWM9_CHANNEL].bit.CC) #else #define PWM9_TMR __helper__(TC, PWM9_TIMER, ) -#define PWM9_CONFIG \ - { \ +#define PWM9_CONFIG \ + { \ PWM9_TMR->COUNT8.CTRLA.bit.SWRST = 1; \ while (PWM9_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM9_TMR->COUNT8.CTRLA.bit.MODE = 1; \ PWM9_TMR->COUNT8.CTRLA.bit.PRESCALER = 2; \ PWM9_TMR->COUNT8.CTRLA.bit.WAVEGEN = 2; \ while (PWM9_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM9_TMR->COUNT8.PER.reg = 255; \ while (PWM9_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM9_TMR->COUNT8.CTRLA.bit.ENABLE = 1; \ while (PWM9_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ } #define PWM9_DUTYCYCLE (PWM9_TMR->COUNT8.CC[PWM9_CHANNEL].reg) #endif @@ -2467,41 +2467,41 @@ extern bool tud_cdc_n_connected (uint8_t itf); #define PWM10_PMUXVAL (pinmuxval(PWM10_MUX)) #if (PWM10_TIMER < 3) #define PWM10_TMR __helper__(TCC, PWM10_TIMER, ) -#define PWM10_CONFIG \ - { \ +#define PWM10_CONFIG \ + { \ PWM10_TMR->CTRLA.bit.SWRST = 1; \ while (PWM10_TMR->SYNCBUSY.bit.SWRST) \ - ; \ + ; \ PWM10_TMR->CTRLA.bit.PRESCALER = 2; \ PWM10_TMR->WAVE.bit.WAVEGEN = 2; \ while (PWM10_TMR->SYNCBUSY.bit.WAVE) \ - ; \ + ; \ PWM10_TMR->PER.bit.PER = 255; \ while (PWM10_TMR->SYNCBUSY.bit.PER) \ - ; \ + ; \ PWM10_TMR->CTRLA.bit.ENABLE = 1; \ while (PWM10_TMR->SYNCBUSY.bit.ENABLE) \ - ; \ + ; \ } #define PWM10_DUTYCYCLE (PWM10_TMR->CC[PWM10_CHANNEL].bit.CC) #else #define PWM10_TMR __helper__(TC, PWM10_TIMER, ) -#define PWM10_CONFIG \ - { \ +#define PWM10_CONFIG \ + { \ PWM10_TMR->COUNT8.CTRLA.bit.SWRST = 1; \ while (PWM10_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM10_TMR->COUNT8.CTRLA.bit.MODE = 1; \ PWM10_TMR->COUNT8.CTRLA.bit.PRESCALER = 2; \ PWM10_TMR->COUNT8.CTRLA.bit.WAVEGEN = 2; \ while (PWM10_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM10_TMR->COUNT8.PER.reg = 255; \ while (PWM10_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM10_TMR->COUNT8.CTRLA.bit.ENABLE = 1; \ while (PWM10_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ } #define PWM10_DUTYCYCLE (PWM10_TMR->COUNT8.CC[PWM10_CHANNEL].reg) #endif @@ -2517,41 +2517,41 @@ extern bool tud_cdc_n_connected (uint8_t itf); #define PWM11_PMUXVAL (pinmuxval(PWM11_MUX)) #if (PWM11_TIMER < 3) #define PWM11_TMR __helper__(TCC, PWM11_TIMER, ) -#define PWM11_CONFIG \ - { \ +#define PWM11_CONFIG \ + { \ PWM11_TMR->CTRLA.bit.SWRST = 1; \ while (PWM11_TMR->SYNCBUSY.bit.SWRST) \ - ; \ + ; \ PWM11_TMR->CTRLA.bit.PRESCALER = 2; \ PWM11_TMR->WAVE.bit.WAVEGEN = 2; \ while (PWM11_TMR->SYNCBUSY.bit.WAVE) \ - ; \ + ; \ PWM11_TMR->PER.bit.PER = 255; \ while (PWM11_TMR->SYNCBUSY.bit.PER) \ - ; \ + ; \ PWM11_TMR->CTRLA.bit.ENABLE = 1; \ while (PWM11_TMR->SYNCBUSY.bit.ENABLE) \ - ; \ + ; \ } #define PWM11_DUTYCYCLE (PWM11_TMR->CC[PWM11_CHANNEL].bit.CC) #else #define PWM11_TMR __helper__(TC, PWM11_TIMER, ) -#define PWM11_CONFIG \ - { \ +#define PWM11_CONFIG \ + { \ PWM11_TMR->COUNT8.CTRLA.bit.SWRST = 1; \ while (PWM11_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM11_TMR->COUNT8.CTRLA.bit.MODE = 1; \ PWM11_TMR->COUNT8.CTRLA.bit.PRESCALER = 2; \ PWM11_TMR->COUNT8.CTRLA.bit.WAVEGEN = 2; \ while (PWM11_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM11_TMR->COUNT8.PER.reg = 255; \ while (PWM11_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM11_TMR->COUNT8.CTRLA.bit.ENABLE = 1; \ while (PWM11_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ } #define PWM11_DUTYCYCLE (PWM11_TMR->COUNT8.CC[PWM11_CHANNEL].reg) #endif @@ -2567,41 +2567,41 @@ extern bool tud_cdc_n_connected (uint8_t itf); #define PWM12_PMUXVAL (pinmuxval(PWM12_MUX)) #if (PWM12_TIMER < 3) #define PWM12_TMR __helper__(TCC, PWM12_TIMER, ) -#define PWM12_CONFIG \ - { \ +#define PWM12_CONFIG \ + { \ PWM12_TMR->CTRLA.bit.SWRST = 1; \ while (PWM12_TMR->SYNCBUSY.bit.SWRST) \ - ; \ + ; \ PWM12_TMR->CTRLA.bit.PRESCALER = 2; \ PWM12_TMR->WAVE.bit.WAVEGEN = 2; \ while (PWM12_TMR->SYNCBUSY.bit.WAVE) \ - ; \ + ; \ PWM12_TMR->PER.bit.PER = 255; \ while (PWM12_TMR->SYNCBUSY.bit.PER) \ - ; \ + ; \ PWM12_TMR->CTRLA.bit.ENABLE = 1; \ while (PWM12_TMR->SYNCBUSY.bit.ENABLE) \ - ; \ + ; \ } #define PWM12_DUTYCYCLE (PWM12_TMR->CC[PWM12_CHANNEL].bit.CC) #else #define PWM12_TMR __helper__(TC, PWM12_TIMER, ) -#define PWM12_CONFIG \ - { \ +#define PWM12_CONFIG \ + { \ PWM12_TMR->COUNT8.CTRLA.bit.SWRST = 1; \ while (PWM12_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM12_TMR->COUNT8.CTRLA.bit.MODE = 1; \ PWM12_TMR->COUNT8.CTRLA.bit.PRESCALER = 2; \ PWM12_TMR->COUNT8.CTRLA.bit.WAVEGEN = 2; \ while (PWM12_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM12_TMR->COUNT8.PER.reg = 255; \ while (PWM12_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM12_TMR->COUNT8.CTRLA.bit.ENABLE = 1; \ while (PWM12_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ } #define PWM12_DUTYCYCLE (PWM12_TMR->COUNT8.CC[PWM12_CHANNEL].reg) #endif @@ -2617,41 +2617,41 @@ extern bool tud_cdc_n_connected (uint8_t itf); #define PWM13_PMUXVAL (pinmuxval(PWM13_MUX)) #if (PWM13_TIMER < 3) #define PWM13_TMR __helper__(TCC, PWM13_TIMER, ) -#define PWM13_CONFIG \ - { \ +#define PWM13_CONFIG \ + { \ PWM13_TMR->CTRLA.bit.SWRST = 1; \ while (PWM13_TMR->SYNCBUSY.bit.SWRST) \ - ; \ + ; \ PWM13_TMR->CTRLA.bit.PRESCALER = 2; \ PWM13_TMR->WAVE.bit.WAVEGEN = 2; \ while (PWM13_TMR->SYNCBUSY.bit.WAVE) \ - ; \ + ; \ PWM13_TMR->PER.bit.PER = 255; \ while (PWM13_TMR->SYNCBUSY.bit.PER) \ - ; \ + ; \ PWM13_TMR->CTRLA.bit.ENABLE = 1; \ while (PWM13_TMR->SYNCBUSY.bit.ENABLE) \ - ; \ + ; \ } #define PWM13_DUTYCYCLE (PWM13_TMR->CC[PWM13_CHANNEL].bit.CC) #else #define PWM13_TMR __helper__(TC, PWM13_TIMER, ) -#define PWM13_CONFIG \ - { \ +#define PWM13_CONFIG \ + { \ PWM13_TMR->COUNT8.CTRLA.bit.SWRST = 1; \ while (PWM13_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM13_TMR->COUNT8.CTRLA.bit.MODE = 1; \ PWM13_TMR->COUNT8.CTRLA.bit.PRESCALER = 2; \ PWM13_TMR->COUNT8.CTRLA.bit.WAVEGEN = 2; \ while (PWM13_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM13_TMR->COUNT8.PER.reg = 255; \ while (PWM13_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM13_TMR->COUNT8.CTRLA.bit.ENABLE = 1; \ while (PWM13_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ } #define PWM13_DUTYCYCLE (PWM13_TMR->COUNT8.CC[PWM13_CHANNEL].reg) #endif @@ -2667,41 +2667,41 @@ extern bool tud_cdc_n_connected (uint8_t itf); #define PWM14_PMUXVAL (pinmuxval(PWM14_MUX)) #if (PWM14_TIMER < 3) #define PWM14_TMR __helper__(TCC, PWM14_TIMER, ) -#define PWM14_CONFIG \ - { \ +#define PWM14_CONFIG \ + { \ PWM14_TMR->CTRLA.bit.SWRST = 1; \ while (PWM14_TMR->SYNCBUSY.bit.SWRST) \ - ; \ + ; \ PWM14_TMR->CTRLA.bit.PRESCALER = 2; \ PWM14_TMR->WAVE.bit.WAVEGEN = 2; \ while (PWM14_TMR->SYNCBUSY.bit.WAVE) \ - ; \ + ; \ PWM14_TMR->PER.bit.PER = 255; \ while (PWM14_TMR->SYNCBUSY.bit.PER) \ - ; \ + ; \ PWM14_TMR->CTRLA.bit.ENABLE = 1; \ while (PWM14_TMR->SYNCBUSY.bit.ENABLE) \ - ; \ + ; \ } #define PWM14_DUTYCYCLE (PWM14_TMR->CC[PWM14_CHANNEL].bit.CC) #else #define PWM14_TMR __helper__(TC, PWM14_TIMER, ) -#define PWM14_CONFIG \ - { \ +#define PWM14_CONFIG \ + { \ PWM14_TMR->COUNT8.CTRLA.bit.SWRST = 1; \ while (PWM14_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM14_TMR->COUNT8.CTRLA.bit.MODE = 1; \ PWM14_TMR->COUNT8.CTRLA.bit.PRESCALER = 2; \ PWM14_TMR->COUNT8.CTRLA.bit.WAVEGEN = 2; \ while (PWM14_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM14_TMR->COUNT8.PER.reg = 255; \ while (PWM14_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM14_TMR->COUNT8.CTRLA.bit.ENABLE = 1; \ while (PWM14_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ } #define PWM14_DUTYCYCLE (PWM14_TMR->COUNT8.CC[PWM14_CHANNEL].reg) #endif @@ -2717,41 +2717,41 @@ extern bool tud_cdc_n_connected (uint8_t itf); #define PWM15_PMUXVAL (pinmuxval(PWM15_MUX)) #if (PWM15_TIMER < 3) #define PWM15_TMR __helper__(TCC, PWM15_TIMER, ) -#define PWM15_CONFIG \ - { \ +#define PWM15_CONFIG \ + { \ PWM15_TMR->CTRLA.bit.SWRST = 1; \ while (PWM15_TMR->SYNCBUSY.bit.SWRST) \ - ; \ + ; \ PWM15_TMR->CTRLA.bit.PRESCALER = 2; \ PWM15_TMR->WAVE.bit.WAVEGEN = 2; \ while (PWM15_TMR->SYNCBUSY.bit.WAVE) \ - ; \ + ; \ PWM15_TMR->PER.bit.PER = 255; \ while (PWM15_TMR->SYNCBUSY.bit.PER) \ - ; \ + ; \ PWM15_TMR->CTRLA.bit.ENABLE = 1; \ while (PWM15_TMR->SYNCBUSY.bit.ENABLE) \ - ; \ + ; \ } #define PWM15_DUTYCYCLE (PWM15_TMR->CC[PWM15_CHANNEL].bit.CC) #else #define PWM15_TMR __helper__(TC, PWM15_TIMER, ) -#define PWM15_CONFIG \ - { \ +#define PWM15_CONFIG \ + { \ PWM15_TMR->COUNT8.CTRLA.bit.SWRST = 1; \ while (PWM15_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM15_TMR->COUNT8.CTRLA.bit.MODE = 1; \ PWM15_TMR->COUNT8.CTRLA.bit.PRESCALER = 2; \ PWM15_TMR->COUNT8.CTRLA.bit.WAVEGEN = 2; \ while (PWM15_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM15_TMR->COUNT8.PER.reg = 255; \ while (PWM15_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ PWM15_TMR->COUNT8.CTRLA.bit.ENABLE = 1; \ while (PWM15_TMR->COUNT8.STATUS.bit.SYNCBUSY) \ - ; \ + ; \ } #define PWM15_DUTYCYCLE (PWM15_TMR->COUNT8.CC[PWM15_CHANNEL].reg) #endif @@ -3005,31 +3005,31 @@ extern bool tud_cdc_n_connected (uint8_t itf); #define TOGGLEFLAG(x, y) ((x) ^= (y)) #endif -#define mcu_config_output(diopin) \ - { \ +#define mcu_config_output(diopin) \ + { \ SETBIT(__indirect__(diopin, GPIO).DIR.reg, __indirect__(diopin, BIT)); \ __indirect__(diopin, GPIO).PINCFG[__indirect__(diopin, BIT)].reg = 2; \ } -#define mcu_config_input(diopin) \ - { \ +#define mcu_config_input(diopin) \ + { \ CLEARBIT(__indirect__(diopin, GPIO).DIR.reg, __indirect__(diopin, BIT)); \ __indirect__(diopin, GPIO).PINCFG[__indirect__(diopin, BIT)].reg = 2; \ } -#define mcu_config_pullup(diopin) \ - { \ +#define mcu_config_pullup(diopin) \ + { \ SETBIT(__indirect__(diopin, GPIO).PINCFG[__indirect__(diopin, BIT)].reg, 2); \ SETBIT(__indirect__(diopin, GPIO).OUT.reg, __indirect__(diopin, BIT)); \ } -#define mcu_config_altfunc(diopin) \ - { \ +#define mcu_config_altfunc(diopin) \ + { \ SETBIT(__indirect__(diopin, GPIO).PINCFG[__indirect__(diopin, BIT)].reg, 0); \ (__indirect__(diopin, PMUX)) = __indirect__(diopin, PMUXVAL); \ } #define mcu_config_input_isr(diopin) (mcu_config_altfunc(diopin)) -#define mcu_config_pwm(diopin, freq) \ - { \ +#define mcu_config_pwm(diopin, freq) \ + { \ SETBIT(__indirect__(diopin, GPIO).DIR.reg, __indirect__(diopin, BIT)); \ __indirect__(diopin, GPIO).PINCFG[__indirect__(diopin, BIT)].reg = 0; \ SETBIT(__indirect__(diopin, GPIO).PINCFG[__indirect__(diopin, BIT)].reg, 0); \ @@ -3038,16 +3038,16 @@ extern bool tud_cdc_n_connected (uint8_t itf); uint8_t presc = 0; \ while (div > 1) \ { \ - div = ((div + 1) >> 1); \ - presc++; \ - if (presc >= 4) \ - { \ - div = ((div + 1) >> 1); \ - } \ - if (presc == 7) \ - { \ - break; \ - } \ + div = ((div + 1) >> 1); \ + presc++; \ + if (presc >= 4) \ + { \ + div = ((div + 1) >> 1); \ + } \ + if (presc == 7) \ + { \ + break; \ + } \ } \ __indirect__(diopin, CONFIG); \ } @@ -3058,29 +3058,29 @@ extern bool tud_cdc_n_connected (uint8_t itf); #define mcu_clear_output(diopin) (__indirect__(diopin, GPIO).OUTCLR.reg = (1UL << __indirect__(diopin, BIT))) #define mcu_toggle_output(diopin) (__indirect__(diopin, GPIO).OUTTGL.reg = (1UL << __indirect__(diopin, BIT))) -#define mcu_set_pwm(diopin, pwmvalue) \ - { \ +#define mcu_set_pwm(diopin, pwmvalue) \ + { \ (__indirect__(diopin, DUTYCYCLE)) = pwmvalue; \ } -#define mcu_get_analog(diopin) \ - { \ +#define mcu_get_analog(diopin) \ + { \ while (ADC->STATUS.bit.SYNCBUSY) \ - ADC->INTFLAG.reg = ADC_INTFLAG_RESRDY; \ + ADC->INTFLAG.reg = ADC_INTFLAG_RESRDY; \ ; \ while (ADC->STATUS.bit.SYNCBUSY) \ - ; \ + ; \ ADC->INPUTCTRL.bit.MUXPOS = (__indirect__(diopin, CHANNEL)); \ while (ADC->STATUS.bit.SYNCBUSY) \ - ; \ + ; \ ADC->SWTRIG.bit.START = 1; \ while (!(ADC->INTFLAG.bit.RESRDY)) \ - ; \ + ; \ ADC->RESULT.reg; \ } -#define mcu_config_analog(diopin) \ - { \ +#define mcu_config_analog(diopin) \ + { \ CLEARBIT(__indirect__(diopin, GPIO).DIR.reg, __indirect__(diopin, BIT)); \ __indirect__(diopin, GPIO).PINCFG[__indirect__(diopin, BIT)].reg = 0; \ SETBIT(__indirect__(diopin, GPIO).PINCFG[__indirect__(diopin, BIT)].reg, 0); \ @@ -3100,27 +3100,27 @@ extern bool tud_cdc_n_connected (uint8_t itf); #endif */ extern volatile bool samd21_global_isr_enabled; -#define mcu_enable_global_isr() \ - { \ +#define mcu_enable_global_isr() \ + { \ __enable_irq(); \ samd21_global_isr_enabled = true; \ } -#define mcu_disable_global_isr() \ - { \ +#define mcu_disable_global_isr() \ + { \ samd21_global_isr_enabled = false; \ __disable_irq(); \ } #define mcu_get_global_isr() samd21_global_isr_enabled -#define mcu_free_micros() ({(1000UL - (SysTick->VAL * 1000UL / SysTick->LOAD));}) +#define mcu_free_micros() ({ (1000UL - (SysTick->VAL * 1000UL / SysTick->LOAD)); }) #ifdef MCU_HAS_SPI -#define mcu_spi_xmit(X) \ - ({ \ +#define mcu_spi_xmit(X) \ + ({ \ while (SPICOM->SPI.INTFLAG.bit.DRE == 0) \ - ; \ + ; \ SPICOM->SPI.DATA.reg = X; \ while (SPICOM->SPI.INTFLAG.bit.RXC == 0) \ - ; \ + ; \ SPICOM->SPI.DATA.reg; \ }) #endif diff --git a/uCNC/src/hal/mcus/stm32f1x/mcumap_stm32f1x.h b/uCNC/src/hal/mcus/stm32f1x/mcumap_stm32f1x.h index 638b64060..d91b3067e 100644 --- a/uCNC/src/hal/mcus/stm32f1x/mcumap_stm32f1x.h +++ b/uCNC/src/hal/mcus/stm32f1x/mcumap_stm32f1x.h @@ -62,12 +62,12 @@ extern "C" #define MCU_CLOCKS_PER_CYCLE 1 #endif -#define mcu_delay_cycles(X) \ - { \ +#define mcu_delay_cycles(X) \ + { \ DWT->CYCCNT = 0; \ uint32_t t = X; \ while (t > DWT->CYCCNT) \ - ; \ + ; \ } // Helper macros @@ -2953,7 +2953,7 @@ extern "C" #define TX2_CROFF TX2_BIT #define TX2_CR CRL #else -#define TX2_CROFF (TX2_BIT&0x07) +#define TX2_CROFF (TX2_BIT & 0x07) #define TX2_CR CRH #endif #define DIO210 210 @@ -2972,7 +2972,7 @@ extern "C" #define RX2_CROFF RX2_BIT #define RX2_CR CRL #else -#define RX2_CROFF (RX2_BIT&0x07) +#define RX2_CROFF (RX2_BIT & 0x07) #define RX2_CR CRH #endif #define DIO211 211 @@ -2984,7 +2984,6 @@ extern "C" #define DIO211_CROFF RX2_CROFF #endif - #if (defined(TX) && defined(RX)) #define MCU_HAS_UART #endif @@ -2993,9 +2992,9 @@ extern "C" #endif #if (defined(USB_DP) && defined(USB_DM)) #define MCU_HAS_USB -extern uint32_t tud_cdc_n_write_available(uint8_t itf); -extern uint32_t tud_cdc_n_available(uint8_t itf); -extern bool tud_cdc_n_connected (uint8_t itf); + extern uint32_t tud_cdc_n_write_available(uint8_t itf); + extern uint32_t tud_cdc_n_available(uint8_t itf); + extern bool tud_cdc_n_connected(uint8_t itf); #define usb_tx_available() (tud_cdc_n_write_available(0) || !tud_cdc_n_connected(0)) #define usb_rx_available() tud_cdc_n_available(0) #endif @@ -3347,18 +3346,18 @@ extern bool tud_cdc_n_connected (uint8_t itf); #define PWM0_CCMREG CCMR1 #endif #if (PWM0_TIMER == 1) -#define PWM0_ENOUTPUT \ - { \ +#define PWM0_ENOUTPUT \ + { \ TIM1->BDTR |= (1 << 15); \ } #elif (PWM0_TIMER == 8) -#define PWM0_ENOUTPUT \ - { \ +#define PWM0_ENOUTPUT \ + { \ TIM8->BDTR |= (1 << 15); \ } #else #define PWM0_ENOUTPUT \ - { \ + { \ } #endif #define PWM0_CCR __ccr__(PWM0_CHANNEL) @@ -3400,18 +3399,18 @@ extern bool tud_cdc_n_connected (uint8_t itf); #define PWM1_CCMREG CCMR1 #endif #if (PWM1_TIMER == 1) -#define PWM1_ENOUTPUT \ - { \ +#define PWM1_ENOUTPUT \ + { \ TIM1->BDTR |= (1 << 15); \ } #elif (PWM1_TIMER == 8) -#define PWM1_ENOUTPUT \ - { \ +#define PWM1_ENOUTPUT \ + { \ TIM8->BDTR |= (1 << 15); \ } #else #define PWM1_ENOUTPUT \ - { \ + { \ } #endif #define PWM1_CCR __ccr__(PWM1_CHANNEL) @@ -3453,18 +3452,18 @@ extern bool tud_cdc_n_connected (uint8_t itf); #define PWM2_CCMREG CCMR1 #endif #if (PWM2_TIMER == 1) -#define PWM2_ENOUTPUT \ - { \ +#define PWM2_ENOUTPUT \ + { \ TIM1->BDTR |= (1 << 15); \ } #elif (PWM2_TIMER == 8) -#define PWM2_ENOUTPUT \ - { \ +#define PWM2_ENOUTPUT \ + { \ TIM8->BDTR |= (1 << 15); \ } #else #define PWM2_ENOUTPUT \ - { \ + { \ } #endif #define PWM2_CCR __ccr__(PWM2_CHANNEL) @@ -3506,18 +3505,18 @@ extern bool tud_cdc_n_connected (uint8_t itf); #define PWM3_CCMREG CCMR1 #endif #if (PWM3_TIMER == 1) -#define PWM3_ENOUTPUT \ - { \ +#define PWM3_ENOUTPUT \ + { \ TIM1->BDTR |= (1 << 15); \ } #elif (PWM3_TIMER == 8) -#define PWM3_ENOUTPUT \ - { \ +#define PWM3_ENOUTPUT \ + { \ TIM8->BDTR |= (1 << 15); \ } #else #define PWM3_ENOUTPUT \ - { \ + { \ } #endif #define PWM3_CCR __ccr__(PWM3_CHANNEL) @@ -3559,18 +3558,18 @@ extern bool tud_cdc_n_connected (uint8_t itf); #define PWM4_CCMREG CCMR1 #endif #if (PWM4_TIMER == 1) -#define PWM4_ENOUTPUT \ - { \ +#define PWM4_ENOUTPUT \ + { \ TIM1->BDTR |= (1 << 15); \ } #elif (PWM4_TIMER == 8) -#define PWM4_ENOUTPUT \ - { \ +#define PWM4_ENOUTPUT \ + { \ TIM8->BDTR |= (1 << 15); \ } #else #define PWM4_ENOUTPUT \ - { \ + { \ } #endif #define PWM4_CCR __ccr__(PWM4_CHANNEL) @@ -3612,18 +3611,18 @@ extern bool tud_cdc_n_connected (uint8_t itf); #define PWM5_CCMREG CCMR1 #endif #if (PWM5_TIMER == 1) -#define PWM5_ENOUTPUT \ - { \ +#define PWM5_ENOUTPUT \ + { \ TIM1->BDTR |= (1 << 15); \ } #elif (PWM5_TIMER == 8) -#define PWM5_ENOUTPUT \ - { \ +#define PWM5_ENOUTPUT \ + { \ TIM8->BDTR |= (1 << 15); \ } #else #define PWM5_ENOUTPUT \ - { \ + { \ } #endif #define PWM5_CCR __ccr__(PWM5_CHANNEL) @@ -3665,18 +3664,18 @@ extern bool tud_cdc_n_connected (uint8_t itf); #define PWM6_CCMREG CCMR1 #endif #if (PWM6_TIMER == 1) -#define PWM6_ENOUTPUT \ - { \ +#define PWM6_ENOUTPUT \ + { \ TIM1->BDTR |= (1 << 15); \ } #elif (PWM6_TIMER == 8) -#define PWM6_ENOUTPUT \ - { \ +#define PWM6_ENOUTPUT \ + { \ TIM8->BDTR |= (1 << 15); \ } #else #define PWM6_ENOUTPUT \ - { \ + { \ } #endif #define PWM6_CCR __ccr__(PWM6_CHANNEL) @@ -3718,18 +3717,18 @@ extern bool tud_cdc_n_connected (uint8_t itf); #define PWM7_CCMREG CCMR1 #endif #if (PWM7_TIMER == 1) -#define PWM7_ENOUTPUT \ - { \ +#define PWM7_ENOUTPUT \ + { \ TIM1->BDTR |= (1 << 15); \ } #elif (PWM7_TIMER == 8) -#define PWM7_ENOUTPUT \ - { \ +#define PWM7_ENOUTPUT \ + { \ TIM8->BDTR |= (1 << 15); \ } #else #define PWM7_ENOUTPUT \ - { \ + { \ } #endif #define PWM7_CCR __ccr__(PWM7_CHANNEL) @@ -3771,18 +3770,18 @@ extern bool tud_cdc_n_connected (uint8_t itf); #define PWM8_CCMREG CCMR1 #endif #if (PWM8_TIMER == 1) -#define PWM8_ENOUTPUT \ - { \ +#define PWM8_ENOUTPUT \ + { \ TIM1->BDTR |= (1 << 15); \ } #elif (PWM8_TIMER == 8) -#define PWM8_ENOUTPUT \ - { \ +#define PWM8_ENOUTPUT \ + { \ TIM8->BDTR |= (1 << 15); \ } #else #define PWM8_ENOUTPUT \ - { \ + { \ } #endif #define PWM8_CCR __ccr__(PWM8_CHANNEL) @@ -3824,18 +3823,18 @@ extern bool tud_cdc_n_connected (uint8_t itf); #define PWM9_CCMREG CCMR1 #endif #if (PWM9_TIMER == 1) -#define PWM9_ENOUTPUT \ - { \ +#define PWM9_ENOUTPUT \ + { \ TIM1->BDTR |= (1 << 15); \ } #elif (PWM9_TIMER == 8) -#define PWM9_ENOUTPUT \ - { \ +#define PWM9_ENOUTPUT \ + { \ TIM8->BDTR |= (1 << 15); \ } #else #define PWM9_ENOUTPUT \ - { \ + { \ } #endif #define PWM9_CCR __ccr__(PWM9_CHANNEL) @@ -3877,18 +3876,18 @@ extern bool tud_cdc_n_connected (uint8_t itf); #define PWM10_CCMREG CCMR1 #endif #if (PWM10_TIMER == 1) -#define PWM10_ENOUTPUT \ - { \ +#define PWM10_ENOUTPUT \ + { \ TIM1->BDTR |= (1 << 15); \ } #elif (PWM10_TIMER == 8) -#define PWM10_ENOUTPUT \ - { \ +#define PWM10_ENOUTPUT \ + { \ TIM8->BDTR |= (1 << 15); \ } #else #define PWM10_ENOUTPUT \ - { \ + { \ } #endif #define PWM10_CCR __ccr__(PWM10_CHANNEL) @@ -3930,18 +3929,18 @@ extern bool tud_cdc_n_connected (uint8_t itf); #define PWM11_CCMREG CCMR1 #endif #if (PWM11_TIMER == 1) -#define PWM11_ENOUTPUT \ - { \ +#define PWM11_ENOUTPUT \ + { \ TIM1->BDTR |= (1 << 15); \ } #elif (PWM11_TIMER == 8) -#define PWM11_ENOUTPUT \ - { \ +#define PWM11_ENOUTPUT \ + { \ TIM8->BDTR |= (1 << 15); \ } #else #define PWM11_ENOUTPUT \ - { \ + { \ } #endif #define PWM11_CCR __ccr__(PWM11_CHANNEL) @@ -3983,18 +3982,18 @@ extern bool tud_cdc_n_connected (uint8_t itf); #define PWM12_CCMREG CCMR1 #endif #if (PWM12_TIMER == 1) -#define PWM12_ENOUTPUT \ - { \ +#define PWM12_ENOUTPUT \ + { \ TIM1->BDTR |= (1 << 15); \ } #elif (PWM12_TIMER == 8) -#define PWM12_ENOUTPUT \ - { \ +#define PWM12_ENOUTPUT \ + { \ TIM8->BDTR |= (1 << 15); \ } #else #define PWM12_ENOUTPUT \ - { \ + { \ } #endif #define PWM12_CCR __ccr__(PWM12_CHANNEL) @@ -4036,18 +4035,18 @@ extern bool tud_cdc_n_connected (uint8_t itf); #define PWM13_CCMREG CCMR1 #endif #if (PWM13_TIMER == 1) -#define PWM13_ENOUTPUT \ - { \ +#define PWM13_ENOUTPUT \ + { \ TIM1->BDTR |= (1 << 15); \ } #elif (PWM13_TIMER == 8) -#define PWM13_ENOUTPUT \ - { \ +#define PWM13_ENOUTPUT \ + { \ TIM8->BDTR |= (1 << 15); \ } #else #define PWM13_ENOUTPUT \ - { \ + { \ } #endif #define PWM13_CCR __ccr__(PWM13_CHANNEL) @@ -4089,18 +4088,18 @@ extern bool tud_cdc_n_connected (uint8_t itf); #define PWM14_CCMREG CCMR1 #endif #if (PWM14_TIMER == 1) -#define PWM14_ENOUTPUT \ - { \ +#define PWM14_ENOUTPUT \ + { \ TIM1->BDTR |= (1 << 15); \ } #elif (PWM14_TIMER == 8) -#define PWM14_ENOUTPUT \ - { \ +#define PWM14_ENOUTPUT \ + { \ TIM8->BDTR |= (1 << 15); \ } #else #define PWM14_ENOUTPUT \ - { \ + { \ } #endif #define PWM14_CCR __ccr__(PWM14_CHANNEL) @@ -4142,18 +4141,18 @@ extern bool tud_cdc_n_connected (uint8_t itf); #define PWM15_CCMREG CCMR1 #endif #if (PWM15_TIMER == 1) -#define PWM15_ENOUTPUT \ - { \ +#define PWM15_ENOUTPUT \ + { \ TIM1->BDTR |= (1 << 15); \ } #elif (PWM15_TIMER == 8) -#define PWM15_ENOUTPUT \ - { \ +#define PWM15_ENOUTPUT \ + { \ TIM8->BDTR |= (1 << 15); \ } #else #define PWM15_ENOUTPUT \ - { \ + { \ } #endif #define PWM15_CCR __ccr__(PWM15_CHANNEL) @@ -4465,8 +4464,8 @@ extern bool tud_cdc_n_connected (uint8_t itf); #ifndef I2C_PORT #define I2C_PORT 1 #endif -#define I2C_IRQ __helper__(I2C,I2C_PORT,_EV_IRQn) -#define I2C_ISR __helper__(I2C,I2C_PORT,_EV_IRQHandler) +#define I2C_IRQ __helper__(I2C, I2C_PORT, _EV_IRQn) +#define I2C_ISR __helper__(I2C, I2C_PORT, _EV_IRQHandler) #define I2C_APBEN __helper__(RCC_APB1ENR_I2C, I2C_PORT, EN) #define I2C_REG __helper__(I2C, I2C_PORT, ) @@ -4635,45 +4634,45 @@ extern bool tud_cdc_n_connected (uint8_t itf); #define TOGGLEFLAG(x, y) ((x) ^= (y)) #endif -#define mcu_config_input(diopin) \ - { \ +#define mcu_config_input(diopin) \ + { \ RCC->APB2ENR |= __indirect__(diopin, APB2EN); \ __indirect__(diopin, GPIO)->__indirect__(diopin, CR) &= ~(GPIO_RESET << (__indirect__(diopin, CROFF) << 2U)); \ __indirect__(diopin, GPIO)->__indirect__(diopin, CR) |= (GPIO_IN_FLOAT << (__indirect__(diopin, CROFF) << 2U)); \ } -#define mcu_config_output(diopin) \ - { \ +#define mcu_config_output(diopin) \ + { \ RCC->APB2ENR |= __indirect__(diopin, APB2EN); \ __indirect__(diopin, GPIO)->__indirect__(diopin, CR) &= ~(GPIO_RESET << (__indirect__(diopin, CROFF) << 2U)); \ __indirect__(diopin, GPIO)->__indirect__(diopin, CR) |= (GPIO_OUT_PP_50MHZ << (__indirect__(diopin, CROFF) << 2U)); \ } -#define mcu_config_output_af(diopin, mode) \ - { \ +#define mcu_config_output_af(diopin, mode) \ + { \ RCC->APB2ENR |= RCC_APB2ENR_AFIOEN; \ RCC->APB2ENR |= __indirect__(diopin, APB2EN); \ __indirect__(diopin, GPIO)->__indirect__(diopin, CR) &= ~(GPIO_RESET << (__indirect__(diopin, CROFF) << 2U)); \ __indirect__(diopin, GPIO)->__indirect__(diopin, CR) |= (mode << (__indirect__(diopin, CROFF) << 2U)); \ } -#define mcu_config_input_af(diopin) \ - { \ +#define mcu_config_input_af(diopin) \ + { \ RCC->APB2ENR |= RCC_APB2ENR_AFIOEN; \ RCC->APB2ENR |= __indirect__(diopin, APB2EN); \ __indirect__(diopin, GPIO)->__indirect__(diopin, CR) &= ~(GPIO_RESET << (__indirect__(diopin, CROFF) << 2U)); \ __indirect__(diopin, GPIO)->__indirect__(diopin, CR) |= (GPIO_IN_FLOAT << (__indirect__(diopin, CROFF) << 2U)); \ } -#define mcu_config_pullup(diopin) \ - { \ +#define mcu_config_pullup(diopin) \ + { \ __indirect__(diopin, GPIO)->__indirect__(diopin, CR) &= ~(GPIO_RESET << (__indirect__(diopin, CROFF) << 2U)); \ __indirect__(diopin, GPIO)->__indirect__(diopin, CR) |= (GPIO_IN_PUP << (__indirect__(diopin, CROFF) << 2U)); \ __indirect__(diopin, GPIO)->BSRR = (1U << __indirect__(diopin, BIT)); \ } -#define mcu_config_pwm(diopin, freq) \ - { \ +#define mcu_config_pwm(diopin, freq) \ + { \ RCC->APB2ENR |= 0x1U; \ __indirect__(diopin, ENREG) |= __indirect__(diopin, APBEN); \ __indirect__(diopin, GPIO)->__indirect__(diopin, CR) &= ~(GPIO_RESET << ((__indirect__(diopin, CROFF)) << 2U)); \ @@ -4689,8 +4688,8 @@ extern bool tud_cdc_n_connected (uint8_t itf); __indirect__(diopin, ENOUTPUT); \ } -#define mcu_config_input_isr(diopin) \ - { \ +#define mcu_config_input_isr(diopin) \ + { \ RCC->APB2ENR |= 0x1U; \ AFIO->EXTICR[(__indirect__(diopin, EXTIREG))] &= ~(0xF << (((__indirect__(diopin, BIT)) & 0x03) << 2)); \ AFIO->EXTICR[(__indirect__(diopin, EXTIREG))] |= (__indirect__(diopin, EXTIVAL)); \ @@ -4702,8 +4701,8 @@ extern bool tud_cdc_n_connected (uint8_t itf); NVIC_EnableIRQ(__indirect__(diopin, IRQ)); \ } -#define mcu_config_analog(diopin) \ - { \ +#define mcu_config_analog(diopin) \ + { \ RCC->CFGR &= ~(RCC_CFGR_ADCPRE); \ RCC->CFGR |= RCC_CFGR_ADCPRE_DIV8; \ RCC->APB2ENR |= (RCC_APB2ENR_ADC1EN | __indirect__(diopin, APB2EN) | 0x1U); \ @@ -4715,10 +4714,10 @@ extern bool tud_cdc_n_connected (uint8_t itf); ADC1->CR2 |= ADC_CR2_ADON; /*enable adc*/ \ ADC1->CR2 |= ADC_CR2_RSTCAL; /*reset calibration*/ \ while (ADC1->CR2 & ADC_CR2_RSTCAL) \ - ; \ + ; \ ADC1->CR2 |= ADC_CR2_CAL; /*start calibration*/ \ while (ADC1->CR2 & ADC_CR2_CAL) \ - ; \ + ; \ ADC1->CR2 |= (ADC_CR2_EXTSEL | ADC_CR2_EXTTRIG); /*external start trigger software*/ \ } @@ -4727,31 +4726,31 @@ extern bool tud_cdc_n_connected (uint8_t itf); #define mcu_set_output(diopin) (__indirect__(diopin, GPIO)->BSRR = (1U << __indirect__(diopin, BIT))) #define mcu_clear_output(diopin) (__indirect__(diopin, GPIO)->BRR = (1U << __indirect__(diopin, BIT))) #define mcu_toggle_output(diopin) (TOGGLEBIT(__indirect__(diopin, GPIO)->ODR, __indirect__(diopin, BIT))) -#define mcu_set_pwm(diopin, pwmvalue) \ - { \ +#define mcu_set_pwm(diopin, pwmvalue) \ + { \ __indirect__(diopin, TIMREG)->__indirect__(diopin, CCR) = (uint16_t)((((uint32_t)__indirect__(diopin, TIMREG)->ARR) * pwmvalue) / 255); \ } #define mcu_get_pwm(diopin) ((uint8_t)((((uint32_t)__indirect__(diopin, TIMREG)->__indirect__(diopin, CCR)) * 255) / ((uint32_t)__indirect__(diopin, TIMREG)->ARR))) -#define mcu_get_analog(diopin) \ - ({ \ +#define mcu_get_analog(diopin) \ + ({ \ ADC1->SQR3 = __indirect__(diopin, CHANNEL); \ ADC1->CR2 |= ADC_CR2_SWSTART; \ ADC1->CR2 &= ~ADC_CR2_SWSTART; \ while (!(ADC1->SR & ADC_SR_EOS)) \ - ; \ + ; \ ADC1->SR &= ~ADC_SR_EOS; \ - (0x3FF & (ADC1->DR >> 2)); \ + (0x3FF & (ADC1->DR >> 2)); \ }) -#define mcu_spi_xmit(X) \ - ({ \ +#define mcu_spi_xmit(X) \ + ({ \ SPI_REG->DR = X; \ while (!(SPI1->SR & SPI_SR_TXE) && !(SPI1->SR & SPI_SR_RXNE)) \ - ; \ + ; \ uint8_t data = SPI_REG->DR; \ while (SPI1->SR & SPI_SR_BSY) \ - ; \ + ; \ data; \ }) @@ -4766,18 +4765,18 @@ extern bool tud_cdc_n_connected (uint8_t itf); #endif extern volatile bool stm32_global_isr_enabled; -#define mcu_enable_global_isr() \ - { \ +#define mcu_enable_global_isr() \ + { \ stm32_global_isr_enabled = true; \ __enable_irq(); \ } -#define mcu_disable_global_isr() \ - { \ +#define mcu_disable_global_isr() \ + { \ stm32_global_isr_enabled = false; \ __disable_irq(); \ } #define mcu_get_global_isr() stm32_global_isr_enabled -#define mcu_free_micros() ({(1000UL - (SysTick->VAL * 1000UL / SysTick->LOAD));}) +#define mcu_free_micros() ({ (1000UL - (SysTick->VAL * 1000UL / SysTick->LOAD)); }) #define GPIO_RESET 0xfU #define GPIO_OUT_PP_50MHZ 0x3U @@ -4792,8 +4791,8 @@ extern bool tud_cdc_n_connected (uint8_t itf); /** * starts the timeout. Once hit the the respective callback is called * */ -#define mcu_start_timeout() \ - ({ \ +#define mcu_start_timeout() \ + ({ \ ONESHOT_TIMER_REG->SR = 0; \ ONESHOT_TIMER_REG->CNT = 0; \ ONESHOT_TIMER_REG->DIER |= 1; \ diff --git a/uCNC/src/hal/mcus/stm32f4x/mcumap_stm32f4x.h b/uCNC/src/hal/mcus/stm32f4x/mcumap_stm32f4x.h index 3d100dc82..f60f5526c 100644 --- a/uCNC/src/hal/mcus/stm32f4x/mcumap_stm32f4x.h +++ b/uCNC/src/hal/mcus/stm32f4x/mcumap_stm32f4x.h @@ -63,12 +63,12 @@ extern "C" #ifndef MCU_CLOCKS_PER_CYCLE #define MCU_CLOCKS_PER_CYCLE 1 #endif -#define mcu_delay_cycles(X) \ - { \ +#define mcu_delay_cycles(X) \ + { \ DWT->CYCCNT = 0; \ uint32_t t = X; \ while (t > DWT->CYCCNT) \ - ; \ + ; \ } // Helper macros @@ -2117,18 +2117,18 @@ extern "C" #define PWM0_CCMREG CCMR1 #endif #if (PWM0_TIMER == 1) -#define PWM0_ENOUTPUT \ - { \ +#define PWM0_ENOUTPUT \ + { \ TIM1->BDTR |= (1 << 15); \ } #elif (PWM0_TIMER == 8) -#define PWM0_ENOUTPUT \ - { \ +#define PWM0_ENOUTPUT \ + { \ TIM8->BDTR |= (1 << 15); \ } #else #define PWM0_ENOUTPUT \ - { \ + { \ } #endif #if (PWM0_TIMER >= 1) && (PWM0_TIMER <= 2) @@ -2178,18 +2178,18 @@ extern "C" #define PWM1_CCMREG CCMR1 #endif #if (PWM1_TIMER == 1) -#define PWM1_ENOUTPUT \ - { \ +#define PWM1_ENOUTPUT \ + { \ TIM1->BDTR |= (1 << 15); \ } #elif (PWM1_TIMER == 8) -#define PWM1_ENOUTPUT \ - { \ +#define PWM1_ENOUTPUT \ + { \ TIM8->BDTR |= (1 << 15); \ } #else #define PWM1_ENOUTPUT \ - { \ + { \ } #endif #if (PWM1_TIMER >= 1) && (PWM1_TIMER <= 2) @@ -2239,18 +2239,18 @@ extern "C" #define PWM2_CCMREG CCMR1 #endif #if (PWM2_TIMER == 1) -#define PWM2_ENOUTPUT \ - { \ +#define PWM2_ENOUTPUT \ + { \ TIM1->BDTR |= (1 << 15); \ } #elif (PWM2_TIMER == 8) -#define PWM2_ENOUTPUT \ - { \ +#define PWM2_ENOUTPUT \ + { \ TIM8->BDTR |= (1 << 15); \ } #else #define PWM2_ENOUTPUT \ - { \ + { \ } #endif #if (PWM2_TIMER >= 1) && (PWM2_TIMER <= 2) @@ -2300,18 +2300,18 @@ extern "C" #define PWM3_CCMREG CCMR1 #endif #if (PWM3_TIMER == 1) -#define PWM3_ENOUTPUT \ - { \ +#define PWM3_ENOUTPUT \ + { \ TIM1->BDTR |= (1 << 15); \ } #elif (PWM3_TIMER == 8) -#define PWM3_ENOUTPUT \ - { \ +#define PWM3_ENOUTPUT \ + { \ TIM8->BDTR |= (1 << 15); \ } #else #define PWM3_ENOUTPUT \ - { \ + { \ } #endif #if (PWM3_TIMER >= 1) && (PWM3_TIMER <= 2) @@ -2361,18 +2361,18 @@ extern "C" #define PWM4_CCMREG CCMR1 #endif #if (PWM4_TIMER == 1) -#define PWM4_ENOUTPUT \ - { \ +#define PWM4_ENOUTPUT \ + { \ TIM1->BDTR |= (1 << 15); \ } #elif (PWM4_TIMER == 8) -#define PWM4_ENOUTPUT \ - { \ +#define PWM4_ENOUTPUT \ + { \ TIM8->BDTR |= (1 << 15); \ } #else #define PWM4_ENOUTPUT \ - { \ + { \ } #endif #if (PWM4_TIMER >= 1) && (PWM4_TIMER <= 2) @@ -2422,18 +2422,18 @@ extern "C" #define PWM5_CCMREG CCMR1 #endif #if (PWM5_TIMER == 1) -#define PWM5_ENOUTPUT \ - { \ +#define PWM5_ENOUTPUT \ + { \ TIM1->BDTR |= (1 << 15); \ } #elif (PWM5_TIMER == 8) -#define PWM5_ENOUTPUT \ - { \ +#define PWM5_ENOUTPUT \ + { \ TIM8->BDTR |= (1 << 15); \ } #else #define PWM5_ENOUTPUT \ - { \ + { \ } #endif #if (PWM5_TIMER >= 1) && (PWM5_TIMER <= 2) @@ -2483,18 +2483,18 @@ extern "C" #define PWM6_CCMREG CCMR1 #endif #if (PWM6_TIMER == 1) -#define PWM6_ENOUTPUT \ - { \ +#define PWM6_ENOUTPUT \ + { \ TIM1->BDTR |= (1 << 15); \ } #elif (PWM6_TIMER == 8) -#define PWM6_ENOUTPUT \ - { \ +#define PWM6_ENOUTPUT \ + { \ TIM8->BDTR |= (1 << 15); \ } #else #define PWM6_ENOUTPUT \ - { \ + { \ } #endif #if (PWM6_TIMER >= 1) && (PWM6_TIMER <= 2) @@ -2544,18 +2544,18 @@ extern "C" #define PWM7_CCMREG CCMR1 #endif #if (PWM7_TIMER == 1) -#define PWM7_ENOUTPUT \ - { \ +#define PWM7_ENOUTPUT \ + { \ TIM1->BDTR |= (1 << 15); \ } #elif (PWM7_TIMER == 8) -#define PWM7_ENOUTPUT \ - { \ +#define PWM7_ENOUTPUT \ + { \ TIM8->BDTR |= (1 << 15); \ } #else #define PWM7_ENOUTPUT \ - { \ + { \ } #endif #if (PWM7_TIMER >= 1) && (PWM7_TIMER <= 2) @@ -2605,18 +2605,18 @@ extern "C" #define PWM8_CCMREG CCMR1 #endif #if (PWM8_TIMER == 1) -#define PWM8_ENOUTPUT \ - { \ +#define PWM8_ENOUTPUT \ + { \ TIM1->BDTR |= (1 << 15); \ } #elif (PWM8_TIMER == 8) -#define PWM8_ENOUTPUT \ - { \ +#define PWM8_ENOUTPUT \ + { \ TIM8->BDTR |= (1 << 15); \ } #else #define PWM8_ENOUTPUT \ - { \ + { \ } #endif #if (PWM8_TIMER >= 1) && (PWM8_TIMER <= 2) @@ -2666,18 +2666,18 @@ extern "C" #define PWM9_CCMREG CCMR1 #endif #if (PWM9_TIMER == 1) -#define PWM9_ENOUTPUT \ - { \ +#define PWM9_ENOUTPUT \ + { \ TIM1->BDTR |= (1 << 15); \ } #elif (PWM9_TIMER == 8) -#define PWM9_ENOUTPUT \ - { \ +#define PWM9_ENOUTPUT \ + { \ TIM8->BDTR |= (1 << 15); \ } #else #define PWM9_ENOUTPUT \ - { \ + { \ } #endif #if (PWM9_TIMER >= 1) && (PWM9_TIMER <= 2) @@ -2727,18 +2727,18 @@ extern "C" #define PWM10_CCMREG CCMR1 #endif #if (PWM10_TIMER == 1) -#define PWM10_ENOUTPUT \ - { \ +#define PWM10_ENOUTPUT \ + { \ TIM1->BDTR |= (1 << 15); \ } #elif (PWM10_TIMER == 8) -#define PWM10_ENOUTPUT \ - { \ +#define PWM10_ENOUTPUT \ + { \ TIM8->BDTR |= (1 << 15); \ } #else #define PWM10_ENOUTPUT \ - { \ + { \ } #endif #if (PWM10_TIMER >= 1) && (PWM10_TIMER <= 2) @@ -2788,18 +2788,18 @@ extern "C" #define PWM11_CCMREG CCMR1 #endif #if (PWM11_TIMER == 1) -#define PWM11_ENOUTPUT \ - { \ +#define PWM11_ENOUTPUT \ + { \ TIM1->BDTR |= (1 << 15); \ } #elif (PWM11_TIMER == 8) -#define PWM11_ENOUTPUT \ - { \ +#define PWM11_ENOUTPUT \ + { \ TIM8->BDTR |= (1 << 15); \ } #else #define PWM11_ENOUTPUT \ - { \ + { \ } #endif #if (PWM11_TIMER >= 1) && (PWM11_TIMER <= 2) @@ -2849,18 +2849,18 @@ extern "C" #define PWM12_CCMREG CCMR1 #endif #if (PWM12_TIMER == 1) -#define PWM12_ENOUTPUT \ - { \ +#define PWM12_ENOUTPUT \ + { \ TIM1->BDTR |= (1 << 15); \ } #elif (PWM12_TIMER == 8) -#define PWM12_ENOUTPUT \ - { \ +#define PWM12_ENOUTPUT \ + { \ TIM8->BDTR |= (1 << 15); \ } #else #define PWM12_ENOUTPUT \ - { \ + { \ } #endif #if (PWM12_TIMER >= 1) && (PWM12_TIMER <= 2) @@ -2910,18 +2910,18 @@ extern "C" #define PWM13_CCMREG CCMR1 #endif #if (PWM13_TIMER == 1) -#define PWM13_ENOUTPUT \ - { \ +#define PWM13_ENOUTPUT \ + { \ TIM1->BDTR |= (1 << 15); \ } #elif (PWM13_TIMER == 8) -#define PWM13_ENOUTPUT \ - { \ +#define PWM13_ENOUTPUT \ + { \ TIM8->BDTR |= (1 << 15); \ } #else #define PWM13_ENOUTPUT \ - { \ + { \ } #endif #if (PWM13_TIMER >= 1) && (PWM13_TIMER <= 2) @@ -2971,18 +2971,18 @@ extern "C" #define PWM14_CCMREG CCMR1 #endif #if (PWM14_TIMER == 1) -#define PWM14_ENOUTPUT \ - { \ +#define PWM14_ENOUTPUT \ + { \ TIM1->BDTR |= (1 << 15); \ } #elif (PWM14_TIMER == 8) -#define PWM14_ENOUTPUT \ - { \ +#define PWM14_ENOUTPUT \ + { \ TIM8->BDTR |= (1 << 15); \ } #else #define PWM14_ENOUTPUT \ - { \ + { \ } #endif #if (PWM14_TIMER >= 1) && (PWM14_TIMER <= 2) @@ -3032,18 +3032,18 @@ extern "C" #define PWM15_CCMREG CCMR1 #endif #if (PWM15_TIMER == 1) -#define PWM15_ENOUTPUT \ - { \ +#define PWM15_ENOUTPUT \ + { \ TIM1->BDTR |= (1 << 15); \ } #elif (PWM15_TIMER == 8) -#define PWM15_ENOUTPUT \ - { \ +#define PWM15_ENOUTPUT \ + { \ TIM8->BDTR |= (1 << 15); \ } #else #define PWM15_ENOUTPUT \ - { \ + { \ } #endif #if (PWM15_TIMER >= 1) && (PWM15_TIMER <= 2) @@ -3651,47 +3651,47 @@ extern "C" #define TOGGLEFLAG(x, y) ((x) ^= (y)) #endif -#define mcu_config_input(diopin) \ - { \ +#define mcu_config_input(diopin) \ + { \ RCC->AHB1ENR |= __indirect__(diopin, AHB1EN); \ __indirect__(diopin, GPIO)->MODER &= ~(GPIO_RESET << ((__indirect__(diopin, BIT)) << 1)); /*reset dir (defaults to input)*/ \ } -#define mcu_config_output(diopin) \ - { \ +#define mcu_config_output(diopin) \ + { \ RCC->AHB1ENR |= __indirect__(diopin, AHB1EN); \ __indirect__(diopin, GPIO)->MODER &= ~(GPIO_RESET << ((__indirect__(diopin, BIT)) << 1)); /*reset dir*/ \ __indirect__(diopin, GPIO)->MODER |= (GPIO_OUTPUT << ((__indirect__(diopin, BIT)) << 1)); /*output mode*/ \ - __indirect__(diopin, GPIO)->OSPEEDR |= (0x02 << ((__indirect__(diopin, BIT)) << 1)); /*output mode*/ \ + __indirect__(diopin, GPIO)->OSPEEDR |= (0x02 << ((__indirect__(diopin, BIT)) << 1)); /*output mode*/ \ } -#define mcu_config_af(diopin, afrval) \ - { \ +#define mcu_config_af(diopin, afrval) \ + { \ RCC->AHB1ENR |= __indirect__(diopin, AHB1EN); \ __indirect__(diopin, GPIO)->MODER &= ~(GPIO_RESET << ((__indirect__(diopin, BIT)) << 1)); /*reset dir*/ \ - __indirect__(diopin, GPIO)->MODER |= (GPIO_AF << ((__indirect__(diopin, BIT)) << 1)); /*af mode*/ \ + __indirect__(diopin, GPIO)->MODER |= (GPIO_AF << ((__indirect__(diopin, BIT)) << 1)); /*af mode*/ \ __indirect__(diopin, GPIO)->AFR[(__indirect__(diopin, BIT) >> 3)] &= ~(0xf << ((__indirect__(diopin, BIT) & 0x07) << 2)); \ __indirect__(diopin, GPIO)->AFR[(__indirect__(diopin, BIT) >> 3)] |= (afrval << ((__indirect__(diopin, BIT) & 0x07) << 2)); /*af mode*/ \ - __indirect__(diopin, GPIO)->OSPEEDR |= (0x03 << ((__indirect__(diopin, BIT)) << 1)); /*output mode*/ \ + __indirect__(diopin, GPIO)->OSPEEDR |= (0x03 << ((__indirect__(diopin, BIT)) << 1)); /*output mode*/ \ } -#define mcu_config_pullup(diopin) \ - { \ +#define mcu_config_pullup(diopin) \ + { \ __indirect__(diopin, GPIO)->PUPDR &= ~(GPIO_RESET << ((__indirect__(diopin, BIT)) << 1)); \ __indirect__(diopin, GPIO)->PUPDR |= (GPIO_IN_PULLUP << ((__indirect__(diopin, BIT)) << 1)); \ } -#define mcu_config_opendrain(diopin) \ - { \ +#define mcu_config_opendrain(diopin) \ + { \ __indirect__(diopin, GPIO)->OTYPER |= (1 << ((__indirect__(diopin, BIT)))); \ } -#define mcu_config_pwm(diopin, freq) \ - { \ +#define mcu_config_pwm(diopin, freq) \ + { \ RCC->AHB1ENR |= __indirect__(diopin, AHB1EN); \ __indirect__(diopin, ENREG) |= __indirect__(diopin, APBEN); \ __indirect__(diopin, GPIO)->MODER &= ~(GPIO_RESET << ((__indirect__(diopin, BIT)) << 1)); /*reset dir*/ \ - __indirect__(diopin, GPIO)->MODER |= (GPIO_AF << ((__indirect__(diopin, BIT)) << 1)); /*af mode*/ \ + __indirect__(diopin, GPIO)->MODER |= (GPIO_AF << ((__indirect__(diopin, BIT)) << 1)); /*af mode*/ \ __indirect__(diopin, GPIO)->AFR[(__indirect__(diopin, BIT) >> 3)] &= ~(0xf << ((__indirect__(diopin, BIT) & 0x07) << 2)); \ __indirect__(diopin, GPIO)->AFR[(__indirect__(diopin, BIT) >> 3)] |= ((__indirect__(diopin, AF) << ((__indirect__(diopin, BIT) & 0x07) << 2))); /*af mode*/ \ __indirect__(diopin, TIMREG)->CR1 = 0; \ @@ -3705,8 +3705,8 @@ extern "C" __indirect__(diopin, ENOUTPUT); \ } -#define mcu_config_input_isr(diopin) \ - { \ +#define mcu_config_input_isr(diopin) \ + { \ RCC->APB2ENR |= RCC_APB2ENR_SYSCFGEN; \ SYSCFG->EXTICR[(__indirect__(diopin, EXTIREG))] &= ~(0xF << (((__indirect__(diopin, BIT)) & 0x03) << 2)); \ SYSCFG->EXTICR[(__indirect__(diopin, EXTIREG))] |= (__indirect__(diopin, EXTIVAL)); \ @@ -3726,8 +3726,8 @@ extern "C" #define ADC_COMMON ADC123_COMMON #endif -#define mcu_config_analog(diopin) \ - { \ +#define mcu_config_analog(diopin) \ + { \ ADC_COMMON->CCR &= ~(ADC_CCR_ADCPRE); \ ADC_COMMON->CCR |= (ADC_CCR_ADCPRE_0 | ADC_CCR_ADCPRE_1); \ RCC->APB2ENR |= (RCC_APB2ENR_ADC1EN); \ @@ -3735,11 +3735,11 @@ extern "C" ADC1->SQR1 = 1; /*one conversion*/ \ ADC1->SMPR1 = 0x00ffffff & 0x36DB6DB6; \ ADC1->SMPR2 = 0x36DB6DB6; \ - ADC1->CR2 &= ~ADC_CR2_CONT; /*single conversion mode*/ \ + ADC1->CR2 &= ~ADC_CR2_CONT; /*single conversion mode*/ \ __indirect__(diopin, GPIO)->MODER &= ~(GPIO_RESET << ((__indirect__(diopin, BIT)) << 1)); /*reset dir*/ \ __indirect__(diopin, GPIO)->MODER |= (GPIO_ANALOG << ((__indirect__(diopin, BIT)) << 1)); /*analog mode*/ \ - ADC1->CR2 |= ADC_CR2_ADON; /*enable adc*/ \ - ADC1->CR2 |= (ADC_CR2_EXTEN_0 | ADC_CR2_EXTEN_1); /*external start trigger software*/ \ + ADC1->CR2 |= ADC_CR2_ADON; /*enable adc*/ \ + ADC1->CR2 |= (ADC_CR2_EXTEN_0 | ADC_CR2_EXTEN_1); /*external start trigger software*/ \ } #define mcu_get_input(diopin) (CHECKBIT(__indirect__(diopin, GPIO)->IDR, __indirect__(diopin, BIT))) @@ -3747,32 +3747,32 @@ extern "C" #define mcu_set_output(diopin) (__indirect__(diopin, GPIO)->BSRR = (1UL << __indirect__(diopin, BIT))) #define mcu_clear_output(diopin) (__indirect__(diopin, GPIO)->BSRR = ((1UL << 16) << __indirect__(diopin, BIT))) #define mcu_toggle_output(diopin) (TOGGLEBIT(__indirect__(diopin, GPIO)->ODR, __indirect__(diopin, BIT))) -#define mcu_set_pwm(diopin, pwmvalue) \ - { \ +#define mcu_set_pwm(diopin, pwmvalue) \ + { \ __indirect__(diopin, TIMREG)->__indirect__(diopin, CCR) = (uint16_t)((__indirect__(diopin, TIMREG)->ARR * pwmvalue) / 255); \ } #define mcu_get_pwm(diopin) ((uint8_t)((((uint32_t)__indirect__(diopin, TIMREG)->__indirect__(diopin, CCR)) * 255) / ((uint32_t)__indirect__(diopin, TIMREG)->ARR))) -#define mcu_get_analog(diopin) \ - ({ \ +#define mcu_get_analog(diopin) \ + ({ \ ADC1->SQR3 = __indirect__(diopin, CHANNEL); \ ADC1->CR2 |= ADC_CR2_SWSTART; \ ADC1->CR2 &= ~ADC_CR2_SWSTART; \ while (!(ADC1->SR & ADC_SR_EOC)) \ - ; \ + ; \ ADC1->SR &= ~ADC_SR_EOC; \ (0x3FF & (ADC1->DR >> 2)); \ }) -#define mcu_spi_xmit(X) \ - ({ \ +#define mcu_spi_xmit(X) \ + ({ \ SPI_REG->DR = X; \ while (!(SPI1->SR & SPI_SR_TXE) && !(SPI1->SR & SPI_SR_RXNE)) \ - ; \ + ; \ uint8_t data = SPI_REG->DR; \ while (SPI1->SR & SPI_SR_BSY) \ - ; \ + ; \ data; \ }) #ifdef PROBE @@ -3786,13 +3786,13 @@ extern "C" #endif extern volatile bool stm32_global_isr_enabled; -#define mcu_enable_global_isr() \ - { \ +#define mcu_enable_global_isr() \ + { \ __enable_irq(); \ stm32_global_isr_enabled = true; \ } -#define mcu_disable_global_isr() \ - { \ +#define mcu_disable_global_isr() \ + { \ stm32_global_isr_enabled = false; \ __disable_irq(); \ } @@ -3816,8 +3816,8 @@ extern "C" /** * starts the timeout. Once hit the the respective callback is called * */ -#define mcu_start_timeout() \ - ({ \ +#define mcu_start_timeout() \ + ({ \ ONESHOT_TIMER_REG->SR = 0; \ ONESHOT_TIMER_REG->CNT = 0; \ ONESHOT_TIMER_REG->DIER |= 1; \ diff --git a/uCNC/src/hal/mcus/virtual/mcumap_virtual.h b/uCNC/src/hal/mcus/virtual/mcumap_virtual.h index eb94b6a59..91586b07c 100644 --- a/uCNC/src/hal/mcus/virtual/mcumap_virtual.h +++ b/uCNC/src/hal/mcus/virtual/mcumap_virtual.h @@ -40,7 +40,7 @@ #define INT8_MIN (-128) #define INT16_MIN (-32768) #define INT32_MIN (-2147483647 - 1) -#define INT64_MIN (-9223372036854775807LL - 1) +#define INT64_MIN (-9223372036854775807LL - 1) #define INT8_MAX 127 #define INT16_MAX 32767 @@ -49,10 +49,10 @@ #define UINT8_MAX 255 #define UINT16_MAX 65535 -#define UINT32_MAX 0xffffffffU /* 4294967295U */ +#define UINT32_MAX 0xffffffffU /* 4294967295U */ #define UINT64_MAX 0xffffffffffffffffULL /* 18446744073709551615ULL */ -//needed by software delays +// needed by software delays #ifndef MCU_CLOCKS_PER_CYCLE #define MCU_CLOCKS_PER_CYCLE 1 #endif @@ -70,7 +70,7 @@ #define MCU_HAS_UART2 -//#define EMULATE_74HC595 +// #define EMULATE_74HC595 // joints step/dir pins #ifndef EMULATE_74HC595 @@ -148,7 +148,7 @@ #define STEP5_EN_IO_OFFSET 21 #define STEP6_EN_IO_OFFSET 22 #define STEP7_EN_IO_OFFSET 23 -//#define PWM0_IO_OFFSET 24 +// #define PWM0_IO_OFFSET 24 #endif #define PWM0 25 #define DIO25 25 diff --git a/uCNC/src/hal/tools/tool.h b/uCNC/src/hal/tools/tool.h index ed4ebd0f0..45ffc4325 100644 --- a/uCNC/src/hal/tools/tool.h +++ b/uCNC/src/hal/tools/tool.h @@ -38,24 +38,24 @@ extern "C" typedef struct { - tool_func startup_code; /*runs any custom code after the tool is loaded*/ - tool_func shutdown_code; /*runs any custom code before the tool is unloaded*/ - tool_func pid_update; /*runs de PID update code needed to keep the tool at the desired speed/power*/ + tool_func startup_code; /*runs any custom code after the tool is loaded*/ + tool_func shutdown_code; /*runs any custom code before the tool is unloaded*/ + tool_func pid_update; /*runs de PID update code needed to keep the tool at the desired speed/power*/ tool_range_speed_func range_speed; /*converts core speed to tool speed*/ - tool_get_speed_func get_speed; /*gets the tool speed/power (converts from tool speed to core speed)*/ - tool_set_speed_func set_speed; /*sets the speed/power of the tool*/ - tool_coolant_func set_coolant; /*enables/disables the coolant*/ + tool_get_speed_func get_speed; /*gets the tool speed/power (converts from tool speed to core speed)*/ + tool_set_speed_func set_speed; /*sets the speed/power of the tool*/ + tool_coolant_func set_coolant; /*enables/disables the coolant*/ } tool_t; - void tool_init(void); // initializes tool inside µCNC - void tool_change(uint8_t tool); // executes a tool change µCNC. This runs the shutdown code of the current tool and then runs the startup code of the next tool - void tool_pid_update(void); // if tool PID option is enabled this function is called in the main loop to update the tool or make some adjustment - int16_t tool_get_setpoint(void); // return the current tool setpoint. That is the value set with S parameter in gcode + void tool_init(void); // initializes tool inside µCNC + void tool_change(uint8_t tool); // executes a tool change µCNC. This runs the shutdown code of the current tool and then runs the startup code of the next tool + void tool_pid_update(void); // if tool PID option is enabled this function is called in the main loop to update the tool or make some adjustment + int16_t tool_get_setpoint(void); // return the current tool setpoint. That is the value set with S parameter in gcode int16_t tool_range_speed(int16_t value, uint8_t conv); // this function converts from GCode S to tool speed and back. For example if using PWM will convert from tool speed S to a PWM value 0-255 if conv=0 or vice-versa if conv=1 - uint16_t tool_get_speed(void); // this function returns the current tool speed. Always returns the setpoint value, unless the tool has a custom get_speed function (for example to return the true speed of a feedback sensor) - void tool_set_speed(int16_t value); // this sets the tool speed. The value passed to this function is the actual IO value needed (for example a PWM value). On M5 or tool shutdown, this value is always 0. - void tool_set_coolant(uint8_t value); // this gets a maks with the coolant outputs to enable(1) or disable(0) - void tool_stop(void); // this stops the tool and coolant + uint16_t tool_get_speed(void); // this function returns the current tool speed. Always returns the setpoint value, unless the tool has a custom get_speed function (for example to return the true speed of a feedback sensor) + void tool_set_speed(int16_t value); // this sets the tool speed. The value passed to this function is the actual IO value needed (for example a PWM value). On M5 or tool shutdown, this value is always 0. + void tool_set_coolant(uint8_t value); // this gets a maks with the coolant outputs to enable(1) or disable(0) + void tool_stop(void); // this stops the tool and coolant #ifdef __cplusplus } diff --git a/uCNC/src/hal/tools/tool_helper.h b/uCNC/src/hal/tools/tool_helper.h index 44c1a5924..938e2e9ef 100644 --- a/uCNC/src/hal/tools/tool_helper.h +++ b/uCNC/src/hal/tools/tool_helper.h @@ -36,18 +36,18 @@ extern "C" * */ #define SET_SPINDLE(X, Y, W, Z) \ - { \ - io_set_pinvalue(Y, Z); \ - io_set_pwm(X, W); \ + { \ + io_set_pinvalue(Y, Z); \ + io_set_pwm(X, W); \ } /** * X - PWM pin * Y - pwm value * */ -#define SET_LASER(X, Y) \ +#define SET_LASER(X, Y) \ { \ - io_set_pwm(X, Y); \ + io_set_pwm(X, Y); \ } /** @@ -55,8 +55,8 @@ extern "C" * Y - mist pin * z - mask value * */ -#define SET_COOLANT(X, Y, Z) \ - { \ +#define SET_COOLANT(X, Y, Z) \ + { \ io_set_pinvalue(X, (Z & COOLANT_MASK)); \ io_set_pinvalue(Y, (Z & MIST_MASK)); \ } diff --git a/uCNC/src/interface/defaults.h b/uCNC/src/interface/defaults.h index 681524214..6ef14c51c 100644 --- a/uCNC/src/interface/defaults.h +++ b/uCNC/src/interface/defaults.h @@ -25,66 +25,66 @@ extern "C" #endif #define DEFAULT_ARRAY_0(y) \ - { \ + { \ } #define DEFAULT_ARRAY_1(y) \ - { \ - y \ + { \ + y \ } #define DEFAULT_ARRAY_2(y) \ - { \ - y, y \ + { \ + y, y \ } #define DEFAULT_ARRAY_3(y) \ - { \ - y, y, y \ + { \ + y, y, y \ } #define DEFAULT_ARRAY_4(y) \ - { \ - y, y, y, y \ + { \ + y, y, y, y \ } #define DEFAULT_ARRAY_5(y) \ - { \ - y, y, y, y, y \ + { \ + y, y, y, y, y \ } #define DEFAULT_ARRAY_6(y) \ - { \ - y, y, y, y, y, y \ + { \ + y, y, y, y, y, y \ } -#define DEFAULT_ARRAY_7(y) \ - { \ - y, y, y, y, y, y, y \ +#define DEFAULT_ARRAY_7(y) \ + { \ + y, y, y, y, y, y, y \ } -#define DEFAULT_ARRAY_8(y) \ - { \ +#define DEFAULT_ARRAY_8(y) \ + { \ y, y, y, y, y, y, y, y \ } -#define DEFAULT_ARRAY_9(y) \ - { \ +#define DEFAULT_ARRAY_9(y) \ + { \ y, y, y, y, y, y, y, y, y \ } -#define DEFAULT_ARRAY_10(y) \ - { \ +#define DEFAULT_ARRAY_10(y) \ + { \ y, y, y, y, y, y, y, y, y, y \ } -#define DEFAULT_ARRAY_11(y) \ - { \ +#define DEFAULT_ARRAY_11(y) \ + { \ y, y, y, y, y, y, y, y, y, y, y \ } -#define DEFAULT_ARRAY_12(y) \ - { \ +#define DEFAULT_ARRAY_12(y) \ + { \ y, y, y, y, y, y, y, y, y, y, y, y \ } -#define DEFAULT_ARRAY_13(y) \ - { \ +#define DEFAULT_ARRAY_13(y) \ + { \ y, y, y, y, y, y, y, y, y, y, y, y, y \ } -#define DEFAULT_ARRAY_14(y) \ - { \ +#define DEFAULT_ARRAY_14(y) \ + { \ y, y, y, y, y, y, y, y, y, y, y, y, y, y \ } -#define DEFAULT_ARRAY_15(y) \ - { \ +#define DEFAULT_ARRAY_15(y) \ + { \ y, y, y, y, y, y, y, y, y, y, y, y, y, y, y \ } #define _DEFAULT_ARRAY(x, y) DEFAULT_ARRAY_##x(y) diff --git a/uCNC/src/interface/grbl_interface.h b/uCNC/src/interface/grbl_interface.h index 4567b2284..37b0eadfa 100644 --- a/uCNC/src/interface/grbl_interface.h +++ b/uCNC/src/interface/grbl_interface.h @@ -83,9 +83,9 @@ extern "C" #define STATUS_GCODE_INVALID_TARGET 33 #define STATUS_GCODE_ARC_RADIUS_ERROR 34 #define STATUS_GCODE_NO_OFFSETS_IN_PLANE 35 -#define STATUS_GCODE_UNUSED_WORDS 36 // +#define STATUS_GCODE_UNUSED_WORDS 36 // #define STATUS_GCODE_G43_DYNAMIC_AXIS_ERROR 37 // -#define STATUS_GCODE_MAX_VALUE_EXCEEDED 38 // +#define STATUS_GCODE_MAX_VALUE_EXCEEDED 38 // // additional codes #define STATUS_BAD_COMMENT_FORMAT 39 #define STATUS_INVALID_TOOL 40 @@ -101,7 +101,7 @@ extern "C" #define STATUS_SPINDLE_STOPPED 50 #define STATUS_TMC_CMD_MISSING_ARGS 51 #define STATUS_VFD_COMMUNICATION_FAILED 52 -#define STATUS_EXTERNAL_SETTINGS_OK 53 //deprecated +#define STATUS_EXTERNAL_SETTINGS_OK 53 // deprecated #define STATUS_LASER_PPI_MODE_DISABLED 54 #define STATUS_TOOL_FAILURE 55 #define STATUS_INVALID_PLANE_SELECTED 56 @@ -140,19 +140,19 @@ extern "C" #define EXEC_ALARM_EMERGENCY_STOP -1 #define EXEC_ALARM_NOALARM 0 // Grbl alarm codes. Valid values (1-255). Zero is reserved for the reset alarm. -#define EXEC_ALARM_HARD_LIMIT 1 // hard limits hit while in motion other then homing -#define EXEC_ALARM_SOFT_LIMIT 2 // target is off bounds of the machine kinematics -#define EXEC_ALARM_ABORT_CYCLE 3 // an abort command was issued -#define EXEC_ALARM_PROBE_FAIL_INITIAL 4 // probe was already triggered and was not able to initialize probing -#define EXEC_ALARM_PROBE_FAIL_CONTACT 5 // probe failed to triggered before reaching the limit target -#define EXEC_ALARM_HOMING_FAIL_RESET 6 // homing was aborted by a reset command -#define EXEC_ALARM_HOMING_FAIL_DOOR 7 // door was opened during homing motion -#define EXEC_ALARM_HOMING_FAIL_PULLOFF 8 // homing limits failed to normalize after retract by pull-distance -#define EXEC_ALARM_HOMING_FAIL_APPROACH 9 // homing limits failed make initial contact -#define EXEC_ALARM_HOMING_FAIL_DUAL_APPROACH 10 // homing limits failed make initial contact (self squaring) -#define EXEC_ALARM_HOMING_FAIL_LIMIT_ACTIVE 11 // homing could not start since one of the limits was already triggered -#define EXEC_ALARM_SPINDLE_SYNC_FAIL 12 // failed to achieve spindle sync speed -#define EXEC_ALARM_HARD_LIMIT_NOMOTION 13 // hard limits were triggered without any motion (position was not lost) +#define EXEC_ALARM_HARD_LIMIT 1 // hard limits hit while in motion other then homing +#define EXEC_ALARM_SOFT_LIMIT 2 // target is off bounds of the machine kinematics +#define EXEC_ALARM_ABORT_CYCLE 3 // an abort command was issued +#define EXEC_ALARM_PROBE_FAIL_INITIAL 4 // probe was already triggered and was not able to initialize probing +#define EXEC_ALARM_PROBE_FAIL_CONTACT 5 // probe failed to triggered before reaching the limit target +#define EXEC_ALARM_HOMING_FAIL_RESET 6 // homing was aborted by a reset command +#define EXEC_ALARM_HOMING_FAIL_DOOR 7 // door was opened during homing motion +#define EXEC_ALARM_HOMING_FAIL_PULLOFF 8 // homing limits failed to normalize after retract by pull-distance +#define EXEC_ALARM_HOMING_FAIL_APPROACH 9 // homing limits failed make initial contact +#define EXEC_ALARM_HOMING_FAIL_DUAL_APPROACH 10 // homing limits failed make initial contact (self squaring) +#define EXEC_ALARM_HOMING_FAIL_LIMIT_ACTIVE 11 // homing could not start since one of the limits was already triggered +#define EXEC_ALARM_SPINDLE_SYNC_FAIL 12 // failed to achieve spindle sync speed +#define EXEC_ALARM_HARD_LIMIT_NOMOTION 13 // hard limits were triggered without any motion (position was not lost) #define EXEC_ALARM_PLASMA_THC_ARC_START_FAILURE 14 // failed to start arc with plasma THC // formated messages @@ -189,7 +189,7 @@ extern "C" #define MSG_FEEDBACK_8 __romstr__("Pgm End") #define MSG_FEEDBACK_9 __romstr__("Restoring defaults") #define MSG_FEEDBACK_10 __romstr__("Restoring spindle") -//#define MSG_FEEDBACK_11 __romstr__("Sleeping") not implemented +// #define MSG_FEEDBACK_11 __romstr__("Sleeping") not implemented /*NEW*/ #define MSG_FEEDBACK_12 __romstr__("Check Emergency stop") #define MSG_FEEDBACK_13 __romstr__("Settings saved") @@ -216,9 +216,9 @@ extern "C" #define MSG_STATUS_PIN __romstr__("|Pn:") #define MSG_STATUS_BUF __romstr__("|Buf:") - //#define MSG_INT "%d" - //#define MSG_FLT "%0.3f" - //#define MSG_FLT_IMPERIAL "%0.5f" + // #define MSG_INT "%d" + // #define MSG_FLT "%0.3f" + // #define MSG_FLT_IMPERIAL "%0.5f" #ifdef __cplusplus } diff --git a/uCNC/src/interface/serial.h b/uCNC/src/interface/serial.h index b128e01d1..3c0a5921b 100644 --- a/uCNC/src/interface/serial.h +++ b/uCNC/src/interface/serial.h @@ -91,11 +91,11 @@ extern "C" #ifdef ENABLE_DEBUG_STREAM #ifndef DEBUG_STREAM -extern serial_stream_t *default_stream; + extern serial_stream_t *default_stream; #define DEBUG_STREAM default_stream #endif -extern void debug_putc(char c); + extern void debug_putc(char c); #define DEBUG_PUTC(c) debug_putc(c) #define DEBUG_STR(__s) print_str(debug_putc, __s) #define DEBUG_BYTES(data, count) print_bytes(debug_putc, data, count) diff --git a/uCNC/src/interface/settings.h b/uCNC/src/interface/settings.h index e227f2faa..b0c136b8b 100644 --- a/uCNC/src/interface/settings.h +++ b/uCNC/src/interface/settings.h @@ -178,111 +178,111 @@ typedef uint16_t setting_offset_t; * These allow custom settings setup of simple settings * * **/ -#define __DECL_EXTENDED_SETTING__(ID, var, type, count, print_cb) \ - static uint32_t set##ID##_settings_address; \ - bool set##ID##_settings_load(void *args) \ - { \ +#define __DECL_EXTENDED_SETTING__(ID, var, type, count, print_cb) \ + static uint32_t set##ID##_settings_address; \ + bool set##ID##_settings_load(void *args) \ + { \ settings_load(set##ID##_settings_address, (uint8_t *)var, sizeof(type) * count); \ return EVENT_CONTINUE; \ - } \ - bool set##ID##_settings_save(void *args) \ - { \ + } \ + bool set##ID##_settings_save(void *args) \ + { \ settings_save(set##ID##_settings_address, (uint8_t *)var, sizeof(type) * count); \ return EVENT_CONTINUE; \ - } \ - bool set##ID##_settings_change(void *args) \ - { \ + } \ + bool set##ID##_settings_change(void *args) \ + { \ setting_args_t *set = (setting_args_t *)args; \ type *ptr = var; \ if (set->id >= ID && set->id < (ID + count)) \ { \ - ptr[set->id - ID] = (type)set->value; \ - return EVENT_HANDLED; \ + ptr[set->id - ID] = (type)set->value; \ + return EVENT_HANDLED; \ } \ return EVENT_CONTINUE; \ - } \ - bool set##ID##_settings_erase(void *args) \ - { \ + } \ + bool set##ID##_settings_erase(void *args) \ + { \ memset(var, 0, sizeof(type) * count); \ return EVENT_CONTINUE; \ - } \ - bool set##ID##_protocol_send_cnc_settings(void *args) \ - { \ + } \ + bool set##ID##_protocol_send_cnc_settings(void *args) \ + { \ type *ptr = var; \ for (uint8_t i = 0; i < count; i++) \ { \ - print_cb(ID + i, ptr[i]); \ + print_cb(ID + i, ptr[i]); \ } \ return EVENT_CONTINUE; \ - } \ - CREATE_EVENT_LISTENER(settings_extended_load, set##ID##_settings_load); \ - CREATE_EVENT_LISTENER(settings_extended_save, set##ID##_settings_save); \ - CREATE_EVENT_LISTENER(settings_change, set##ID##_settings_change); \ - CREATE_EVENT_LISTENER(settings_extended_erase, set##ID##_settings_erase); \ + } \ + CREATE_EVENT_LISTENER(settings_extended_load, set##ID##_settings_load); \ + CREATE_EVENT_LISTENER(settings_extended_save, set##ID##_settings_save); \ + CREATE_EVENT_LISTENER(settings_change, set##ID##_settings_change); \ + CREATE_EVENT_LISTENER(settings_extended_erase, set##ID##_settings_erase); \ CREATE_EVENT_LISTENER(protocol_send_cnc_settings, set##ID##_protocol_send_cnc_settings) #define DECL_EXTENDED_SETTING(ID, var, type, count, print_cb) __DECL_EXTENDED_SETTING__(ID, var, type, count, print_cb) -#define __DECL_EXTENDED_STRING_SETTING__(ID, var, count) \ - static uint32_t set##ID##_settings_address; \ - bool set##ID##_settings_load(void *args) \ - { \ - settings_load(set##ID##_settings_address, (uint8_t *)var, sizeof(char) * count); \ - return EVENT_CONTINUE; \ - } \ - bool set##ID##_settings_save(void *args) \ - { \ - return EVENT_CONTINUE; \ - } \ - bool set##ID##_settings_change(void *args) \ - { \ - setting_args_t *set = (setting_args_t *)args; \ - if (set->id == ID) \ - { \ +#define __DECL_EXTENDED_STRING_SETTING__(ID, var, count) \ + static uint32_t set##ID##_settings_address; \ + bool set##ID##_settings_load(void *args) \ + { \ + settings_load(set##ID##_settings_address, (uint8_t *)var, sizeof(char) * count); \ + return EVENT_CONTINUE; \ + } \ + bool set##ID##_settings_save(void *args) \ + { \ + return EVENT_CONTINUE; \ + } \ + bool set##ID##_settings_change(void *args) \ + { \ + setting_args_t *set = (setting_args_t *)args; \ + if (set->id == ID) \ + { \ settings_load(set##ID##_settings_address, (uint8_t *)var, sizeof(char) * count); \ for (uint8_t i = 0; i < count; i++) \ { \ - char c = serial_getc(); \ - if (c == EOL || c == '\n') \ - { \ - var[i] = EOL; \ - break; \ - } \ - var[i] = c; \ + char c = serial_getc(); \ + if (c == EOL || c == '\n') \ + { \ + var[i] = EOL; \ + break; \ + } \ + var[i] = c; \ } \ settings_save(set##ID##_settings_address, (uint8_t *)var, sizeof(char) * count); \ return EVENT_HANDLED; \ - } \ - return EVENT_CONTINUE; \ - } \ - bool set##ID##_settings_erase(void *args) \ - { \ - memset(var, 0, sizeof(char) * count); \ - settings_save(set##ID##_settings_address, (uint8_t *)var, sizeof(char) * count); \ - return EVENT_CONTINUE; \ - } \ - bool set##ID##_protocol_send_cnc_settings(void *args) \ - { \ - memset(var, 0, sizeof(char) * count); \ - settings_load(set##ID##_settings_address, (uint8_t *)var, sizeof(char) * count); \ - serial_putc('$'); \ - serial_print_int(ID); \ - serial_putc('='); \ - for (uint8_t i = 0; i < count; i++) \ - { \ + } \ + return EVENT_CONTINUE; \ + } \ + bool set##ID##_settings_erase(void *args) \ + { \ + memset(var, 0, sizeof(char) * count); \ + settings_save(set##ID##_settings_address, (uint8_t *)var, sizeof(char) * count); \ + return EVENT_CONTINUE; \ + } \ + bool set##ID##_protocol_send_cnc_settings(void *args) \ + { \ + memset(var, 0, sizeof(char) * count); \ + settings_load(set##ID##_settings_address, (uint8_t *)var, sizeof(char) * count); \ + serial_putc('$'); \ + serial_print_int(ID); \ + serial_putc('='); \ + for (uint8_t i = 0; i < count; i++) \ + { \ char c = var[i]; \ if (c < 20 || c > 127) \ { \ - protocol_send_string(MSG_EOL); \ - return EVENT_CONTINUE; \ + protocol_send_string(MSG_EOL); \ + return EVENT_CONTINUE; \ } \ serial_putc(c); \ - } \ - return EVENT_CONTINUE; \ - } \ - CREATE_EVENT_LISTENER(settings_extended_load, set##ID##_settings_load); \ - CREATE_EVENT_LISTENER(settings_extended_save, set##ID##_settings_save); \ - CREATE_EVENT_LISTENER(settings_change, set##ID##_settings_change); \ - CREATE_EVENT_LISTENER(settings_extended_erase, set##ID##_settings_erase); \ + } \ + return EVENT_CONTINUE; \ + } \ + CREATE_EVENT_LISTENER(settings_extended_load, set##ID##_settings_load); \ + CREATE_EVENT_LISTENER(settings_extended_save, set##ID##_settings_save); \ + CREATE_EVENT_LISTENER(settings_change, set##ID##_settings_change); \ + CREATE_EVENT_LISTENER(settings_extended_erase, set##ID##_settings_erase); \ CREATE_EVENT_LISTENER(protocol_send_cnc_settings, set##ID##_protocol_send_cnc_settings) #define DECL_EXTENDED_STRING_SETTING(ID, var, count) __DECL_EXTENDED_STRING_SETTING__(ID, var, count) @@ -290,10 +290,10 @@ typedef uint16_t setting_offset_t; #define __EXTENDED_SETTING_ADDRESS__(ID) set##ID##_settings_address #define EXTENDED_SETTING_ADDRESS(ID) __EXTENDED_SETTING_ADDRESS__(ID) -#define __EXTENDED_SETTING_INIT__(ID, var) \ - static bool set##ID##_init = false; \ - if (!set##ID##_init) \ - { \ +#define __EXTENDED_SETTING_INIT__(ID, var) \ + static bool set##ID##_init = false; \ + if (!set##ID##_init) \ + { \ set##ID##_settings_address = settings_register_external_setting(sizeof(var)); \ ADD_EVENT_LISTENER(settings_extended_load, set##ID##_settings_load); \ ADD_EVENT_LISTENER(settings_extended_save, set##ID##_settings_save); \ diff --git a/uCNC/src/module.h b/uCNC/src/module.h index 269b79169..55379c247 100644 --- a/uCNC/src/module.h +++ b/uCNC/src/module.h @@ -34,39 +34,39 @@ extern "C" #define EVENT_HANDLED true #define DECL_MODULE(name) void name##_init(void) -#define LOAD_MODULE(name) \ +#define LOAD_MODULE(name) \ extern void name##_init(void); \ name##_init() // definitions to create events and event listeners -#define EVENT(name) \ - typedef struct name##_delegate_event_ \ - { \ +#define EVENT(name) \ + typedef struct name##_delegate_event_ \ + { \ name##_delegate fptr; \ bool fplock; \ struct name##_delegate_event_ *next; \ - } name##_delegate_event_t; \ + } name##_delegate_event_t; \ extern name##_delegate_event_t * #define EVENT_HANDLER_NAME(name) event_##name##_handler #define EVENT_INVOKE(name, args) EVENT_HANDLER_NAME(name)(args) #define CREATE_EVENT_LISTENER(name, handler) __attribute__((used)) name##_delegate_event_t name##_delegate_##handler = {&handler, false, NULL} -#define ADD_EVENT_LISTENER(name, handler) \ - { \ +#define ADD_EVENT_LISTENER(name, handler) \ + { \ extern name##_delegate_event_t name##_delegate_##handler; \ if (name##_event == NULL) \ { \ - name##_event = &name##_delegate_##handler; \ - name##_event->next = NULL; \ + name##_event = &name##_delegate_##handler; \ + name##_event->next = NULL; \ } \ else \ { \ - name##_delegate_event_t *p = name##_event; \ - while (p->next != NULL) \ - { \ - p = p->next; \ - } \ - p->next = &name##_delegate_##handler; \ - p->next->next = NULL; \ + name##_delegate_event_t *p = name##_event; \ + while (p->next != NULL) \ + { \ + p = p->next; \ + } \ + p->next = &name##_delegate_##handler; \ + p->next->next = NULL; \ } \ } @@ -74,59 +74,59 @@ extern "C" // the resulting handles is named event__handler and can be placed inside any point in the core code // for example DECL_EVENT_HANDLER() will create a function declaration equivalent to uint8_t event__handler(void* args) // event__handler can then be placed inside the core code to run the hook code -#define DECL_EVENT_HANDLER(name) \ +#define DECL_EVENT_HANDLER(name) \ typedef bool (*name##_delegate)(void *); \ EVENT(name) \ name##_event; \ bool EVENT_HANDLER_NAME(name)(void *args) -#define WEAK_EVENT_HANDLER(name) \ +#define WEAK_EVENT_HANDLER(name) \ name##_delegate_event_t *name##_event; \ bool __attribute__((weak)) EVENT_HANDLER_NAME(name)(void *args) #define OVERRIDE_EVENT_HANDLER(name) bool EVENT_HANDLER_NAME(name)(void *args) -#define DEFAULT_EVENT_HANDLER(name) \ - { \ - static name##_delegate_event_t *start = NULL; \ - name##_delegate_event_t *ptr = start; \ - if (!ptr) \ - { \ - ptr = name##_event; \ - } \ - while (ptr != NULL) \ - { \ - start = ptr->next; \ - if (ptr->fptr != NULL && !ptr->fplock) \ - { \ - ptr->fplock = true; \ - if (ptr->fptr(args)) \ - { \ +#define DEFAULT_EVENT_HANDLER(name) \ + { \ + static name##_delegate_event_t *start = NULL; \ + name##_delegate_event_t *ptr = start; \ + if (!ptr) \ + { \ + ptr = name##_event; \ + } \ + while (ptr != NULL) \ + { \ + start = ptr->next; \ + if (ptr->fptr != NULL && !ptr->fplock) \ + { \ + ptr->fplock = true; \ + if (ptr->fptr(args)) \ + { \ ptr->fplock = false; \ start = name##_event; /*handled. restart.*/ \ return true; \ - } \ - ptr->fplock = false; \ - } \ - ptr = start; \ - } \ - return false; \ + } \ + ptr->fplock = false; \ + } \ + ptr = start; \ + } \ + return false; \ } void mod_init(void); // uses VARADIC MACRO available since C99 -#define DECL_HOOK(name, ...) \ +#define DECL_HOOK(name, ...) \ typedef void (*name##_delegate_t)(__VA_ARGS__); \ extern name##_delegate_t name##_cb #define CREATE_HOOK(name) name##_delegate_t name##_cb #define HOOK_ATTACH_CALLBACK(name, cb) name##_cb = &cb #define HOOK_RELEASE(name) name##_cb = NULL -#define HOOK_INVOKE(name, ...) \ - if (name##_cb) \ - { \ - name##_cb(__VA_ARGS__); \ +#define HOOK_INVOKE(name, ...) \ + if (name##_cb) \ + { \ + name##_cb(__VA_ARGS__); \ } -#define RUNONCE \ +#define RUNONCE \ static bool runonce = false; \ if (!runonce) diff --git a/uCNC/src/modules/endpoint.h b/uCNC/src/modules/endpoint.h index 4d08e193e..a42b157e0 100644 --- a/uCNC/src/modules/endpoint.h +++ b/uCNC/src/modules/endpoint.h @@ -56,7 +56,7 @@ extern "C" void endpoint_add(const char *uri, uint8_t method, endpoint_delegate request_handler, endpoint_delegate file_handler); int endpoint_request_hasargs(void); - void endpoint_request_uri(char* uri, size_t maxlen); + void endpoint_request_uri(char *uri, size_t maxlen); bool endpoint_request_arg(const char *argname, char *argvalue, size_t maxlen); void endpoint_send(int code, const char *content_type, const char *data); void endpoint_send_header(const char *name, const char *data, bool first); diff --git a/uCNC/src/modules/language/language_en.h b/uCNC/src/modules/language/language_en.h index 559f4ee2b..3047582bf 100644 --- a/uCNC/src/modules/language/language_en.h +++ b/uCNC/src/modules/language/language_en.h @@ -44,12 +44,12 @@ extern "C" #define STR_FAST_FEED "Fast feed:" #define STR_DEBOUNCEMS "Debounce(ms):" #define STR_OFFSET "Offset:" -#define STR_STEPMM(X) X" step/mm:" -#define STR_VMAX(X) X" v-max:" -#define STR_ACCEL(X) X" accel:" -#define STR_MAX_DIST(X) X" max dist:" -#define STR_BACKLASH(X) X" backlash:" -#define STR_SKEW_FACTOR(X) X" factor:" +#define STR_STEPMM(X) X " step/mm:" +#define STR_VMAX(X) X " v-max:" +#define STR_ACCEL(X) X " accel:" +#define STR_MAX_DIST(X) X " max dist:" +#define STR_BACKLASH(X) X " backlash:" +#define STR_SKEW_FACTOR(X) X " factor:" #define STR_ARM_LEN "Arm len:" #define STR_BASE_RAD "Base rad:" #define STR_EFF_RAD "Eff rad:" diff --git a/uCNC/src/modules/modbus.h b/uCNC/src/modules/modbus.h index 83a5b0e7b..c4ccd372a 100644 --- a/uCNC/src/modules/modbus.h +++ b/uCNC/src/modules/modbus.h @@ -42,27 +42,27 @@ extern "C" #define MODBUS_PRESET_MULTIPLE_REGISTERS 0x10 #define MODBUS_READ_WRITE_MULTIPLE_REGISTERS 0x017 -typedef struct modbus_request -{ - uint8_t address; - uint8_t fcode; - uint8_t startaddress[2]; - uint8_t value[2]; - uint8_t datalen; - uint8_t data[MODBUS_DATA_MAX_LEN]; - uint16_t crc; -} modbus_request_t; + typedef struct modbus_request + { + uint8_t address; + uint8_t fcode; + uint8_t startaddress[2]; + uint8_t value[2]; + uint8_t datalen; + uint8_t data[MODBUS_DATA_MAX_LEN]; + uint16_t crc; + } modbus_request_t; -typedef struct modbus_response -{ - uint8_t address; - uint8_t fcode; - uint8_t data[MODBUS_DATA_MAX_LEN]; - uint16_t crc; -} modbus_response_t; + typedef struct modbus_response + { + uint8_t address; + uint8_t fcode; + uint8_t data[MODBUS_DATA_MAX_LEN]; + uint16_t crc; + } modbus_response_t; -void send_request(modbus_request_t request, uint8_t len, softuart_port_t *port); -bool read_response(modbus_response_t *response, uint8_t len, softuart_port_t *port, uint32_t ms_timeout); + void send_request(modbus_request_t request, uint8_t len, softuart_port_t *port); + bool read_response(modbus_response_t *response, uint8_t len, softuart_port_t *port, uint32_t ms_timeout); #ifdef __cplusplus } diff --git a/uCNC/src/modules/pid.h b/uCNC/src/modules/pid.h index efab2bb6a..f188cac78 100644 --- a/uCNC/src/modules/pid.h +++ b/uCNC/src/modules/pid.h @@ -30,7 +30,7 @@ extern "C" #include #include -#define HZ_TO_MS(hz) (1000/(hz)) +#define HZ_TO_MS(hz) (1000 / (hz)) typedef struct pid_data_ { diff --git a/uCNC/src/modules/softi2c.h b/uCNC/src/modules/softi2c.h index 31cac22f6..29435e51f 100644 --- a/uCNC/src/modules/softi2c.h +++ b/uCNC/src/modules/softi2c.h @@ -47,44 +47,44 @@ extern "C" #define I2C_DELAY(FREQ) CLAMP(0, ((2500000UL / FREQ) - 1), 255) #define SOFTI2C(NAME, FREQ, SCLPIN, SDAPIN) \ - void NAME##_scl(bool state) \ - { \ - if (state) \ - { \ - io_config_input(SCLPIN); \ - io_config_pullup(SCLPIN); \ - } \ - else \ - { \ - io_clear_output(SCLPIN); \ - io_config_output(SCLPIN); \ - } \ - } \ - void NAME##_sda(bool state) \ - { \ - if (state) \ - { \ - io_config_input(SDAPIN); \ - io_config_pullup(SDAPIN); \ - } \ - else \ - { \ - io_clear_output(SDAPIN); \ - io_config_output(SDAPIN); \ - } \ - } \ - bool NAME##_get_sda(void) \ - { \ - io_config_input(SDAPIN); \ - io_config_pullup(SDAPIN); \ - return io_get_input(SDAPIN); \ - } \ - bool NAME##_get_scl(void) \ - { \ - io_config_input(SCLPIN); \ - io_config_pullup(SCLPIN); \ - return io_get_input(SCLPIN); \ - } \ + void NAME##_scl(bool state) \ + { \ + if (state) \ + { \ + io_config_input(SCLPIN); \ + io_config_pullup(SCLPIN); \ + } \ + else \ + { \ + io_clear_output(SCLPIN); \ + io_config_output(SCLPIN); \ + } \ + } \ + void NAME##_sda(bool state) \ + { \ + if (state) \ + { \ + io_config_input(SDAPIN); \ + io_config_pullup(SDAPIN); \ + } \ + else \ + { \ + io_clear_output(SDAPIN); \ + io_config_output(SDAPIN); \ + } \ + } \ + bool NAME##_get_sda(void) \ + { \ + io_config_input(SDAPIN); \ + io_config_pullup(SDAPIN); \ + return io_get_input(SDAPIN); \ + } \ + bool NAME##_get_scl(void) \ + { \ + io_config_input(SCLPIN); \ + io_config_pullup(SCLPIN); \ + return io_get_input(SCLPIN); \ + } \ softi2c_port_t NAME = {.i2cdelay = I2C_DELAY(FREQ), .scl = &NAME##_scl, .sda = &NAME##_sda, .get_sda = &NAME##_get_sda, .get_scl = &NAME##_get_scl}; uint8_t softi2c_send(softi2c_port_t *port, uint8_t address, uint8_t *data, uint8_t len, bool release, uint32_t ms_timeout); diff --git a/uCNC/src/modules/softspi.h b/uCNC/src/modules/softspi.h index 91a705b35..dd94e278f 100644 --- a/uCNC/src/modules/softspi.h +++ b/uCNC/src/modules/softspi.h @@ -39,30 +39,30 @@ extern "C" #define SPI_DELAY(FREQ) CLAMP(0, ((2500000UL / FREQ) - 1), 255) -#define SOFTSPI(NAME, FREQ, MODE, MOSIPIN, MISOPIN, CLKPIN) \ - void NAME##_clk(bool state) \ - { \ - if (state) \ - { \ - io_set_output(CLKPIN); \ - } \ - else \ - { \ - io_clear_output(CLKPIN); \ - } \ - } \ - void NAME##_mosi(bool state) \ - { \ - if (state) \ - { \ - io_set_output(MOSIPIN); \ - } \ - else \ - { \ - io_clear_output(MOSIPIN); \ - } \ - } \ - bool NAME##_miso(void) { return io_get_input(MISOPIN); } \ +#define SOFTSPI(NAME, FREQ, MODE, MOSIPIN, MISOPIN, CLKPIN) \ + void NAME##_clk(bool state) \ + { \ + if (state) \ + { \ + io_set_output(CLKPIN); \ + } \ + else \ + { \ + io_clear_output(CLKPIN); \ + } \ + } \ + void NAME##_mosi(bool state) \ + { \ + if (state) \ + { \ + io_set_output(MOSIPIN); \ + } \ + else \ + { \ + io_clear_output(MOSIPIN); \ + } \ + } \ + bool NAME##_miso(void) { return io_get_input(MISOPIN); } \ __attribute__((used)) softspi_port_t NAME = {.spimode = MODE, .spidelay = SPI_DELAY(FREQ), .clk = &NAME##_clk, .mosi = &NAME##_mosi, .miso = &NAME##_miso}; void softspi_config(softspi_port_t *port, uint8_t mode, uint32_t frequency); diff --git a/uCNC/src/modules/softuart.h b/uCNC/src/modules/softuart.h index c2b90ea51..e20f105c6 100644 --- a/uCNC/src/modules/softuart.h +++ b/uCNC/src/modules/softuart.h @@ -43,44 +43,43 @@ extern "C" #define SOFTUART_HW_RX_FALLBACK mcu_uart2_getc #endif - -#define SOFTUART(NAME, BAUD, TXPIN, RXPIN) \ +#define SOFTUART(NAME, BAUD, TXPIN, RXPIN) \ void NAME##_tx(bool state) \ { \ - if (state) \ - { \ - io_set_output(TXPIN); \ - } \ - else \ - { \ - io_clear_output(TXPIN); \ - } \ + if (state) \ + { \ + io_set_output(TXPIN); \ + } \ + else \ + { \ + io_clear_output(TXPIN); \ + } \ } \ bool NAME##_rx(void) \ { \ - return io_get_input(RXPIN); \ + return io_get_input(RXPIN); \ } \ void NAME##_wait(void) { mcu_delay_cycles(F_CPU / BAUD); } \ void NAME##_waithalf(void) { mcu_delay_cycles(F_CPU / 2 / BAUD); } \ __attribute__((used)) softuart_port_t NAME = {.wait = &NAME##_wait, .waithalf = &NAME##_waithalf, .tx = &NAME##_tx, .rx = &NAME##_rx}; -#define ONEWIRE(NAME, BAUD, TRXPIN) \ +#define ONEWIRE(NAME, BAUD, TRXPIN) \ void NAME##_tx(bool state) \ { \ - if (state) \ - { \ - io_config_input(TRXPIN); \ - io_config_pullup(TRXPIN); \ - } \ - else \ - { \ - io_clear_output(TRXPIN); \ - io_config_output(TRXPIN); \ - } \ + if (state) \ + { \ + io_config_input(TRXPIN); \ + io_config_pullup(TRXPIN); \ + } \ + else \ + { \ + io_clear_output(TRXPIN); \ + io_config_output(TRXPIN); \ + } \ } \ bool NAME##_rx(void) \ { \ - return io_get_input(TRXPIN); \ + return io_get_input(TRXPIN); \ } \ void NAME##_wait(void) { mcu_delay_cycles(F_CPU / BAUD); } \ void NAME##_waithalf(void) { mcu_delay_cycles(F_CPU / 2 / BAUD); } \ diff --git a/uCNC/src/modules/system_menu.h b/uCNC/src/modules/system_menu.h index 00042446f..7de8f8176 100644 --- a/uCNC/src/modules/system_menu.h +++ b/uCNC/src/modules/system_menu.h @@ -134,7 +134,7 @@ extern "C" } system_menu_t; #define MENU_ENTRY(name) ((system_menu_item_t *)&name) -#define DECL_MENU_ENTRY(menu_id, name, strvalue, arg_ptr, display_cb, display_cb_arg, action_cb, action_cb_arg) \ +#define DECL_MENU_ENTRY(menu_id, name, strvalue, arg_ptr, display_cb, display_cb_arg, action_cb, action_cb_arg) \ static const system_menu_item_t name##_item __rom__ = {.label = strvalue, .argptr = arg_ptr, .item_render = display_cb, .render_arg = display_cb_arg, .item_action = action_cb, .action_arg = action_cb_arg}; \ static system_menu_index_t name = {.menu_item = &name##_item, .next = NULL}; \ system_menu_append_item(menu_id, &name) @@ -149,11 +149,11 @@ extern "C" #define DECL_MENU_VAR_CUSTOM_EDIT(menu_id, name, strvalue, varptr, vartype, actioncb, actioncb_arg) DECL_MENU_ENTRY(menu_id, name, strvalue, varptr, system_menu_item_render_var_arg, CONST_VARG(vartype), actioncb, actioncb_arg) #define DECL_MENU_ACTION(menu_id, name, strvalue, action_cb, action_cb_arg) DECL_MENU_ENTRY(menu_id, name, strvalue, NULL, NULL, NULL, action_cb, action_cb_arg) -#define DECL_MENU(id, parentid, label) \ +#define DECL_MENU(id, parentid, label) \ static const char m##id##_label[] __rom__ = label; \ static system_menu_page_t m##id = {.menu_id = id, .parent_id = parentid, .page_label = m##id##_label, .page_render = NULL, .page_action = NULL, .items_index = NULL, .extended = NULL}; \ system_menu_append(&m##id) -#define DECL_DYNAMIC_MENU(id, parentid, render_cb, action_cb) \ +#define DECL_DYNAMIC_MENU(id, parentid, render_cb, action_cb) \ static system_menu_page_t m##id = {.menu_id = id, .parent_id = parentid, .page_label = NULL, .page_render = render_cb, .page_action = action_cb, .items_index = NULL, .extended = NULL}; \ system_menu_append(&m##id) #define MENU(id) (&m##id) @@ -217,10 +217,10 @@ extern "C" void system_menu_var_to_str_set_buffer(char *ptr); void system_menu_var_to_str(char c); -#define system_menu_int_to_str(buf_ptr, var) \ +#define system_menu_int_to_str(buf_ptr, var) \ system_menu_var_to_str_set_buffer(buf_ptr); \ print_int(system_menu_var_to_str, (uint32_t)var) -#define system_menu_flt_to_str(buf_ptr, var) \ +#define system_menu_flt_to_str(buf_ptr, var) \ system_menu_var_to_str_set_buffer(buf_ptr); \ print_flt(system_menu_var_to_str, (float)var) diff --git a/uCNC/src/utils.h b/uCNC/src/utils.h index 9410b7ccc..94e90a12b 100644 --- a/uCNC/src/utils.h +++ b/uCNC/src/utils.h @@ -31,14 +31,14 @@ extern "C" #ifndef BYTE_OPS #define BYTE_OPS -#define SETBIT(x, y) ((x) |= (1U << (y))) /* Set bit y in byte x*/ +#define SETBIT(x, y) ((x) |= (1U << (y))) /* Set bit y in byte x*/ #define CLEARBIT(x, y) ((x) &= ~(1U << (y))) /* Clear bit y in byte x*/ #define CHECKBIT(x, y) ((x) & (1U << (y))) /* Check bit y in byte x*/ #define TOGGLEBIT(x, y) ((x) ^= (1U << (y))) /* Toggle bit y in byte x*/ -#define SETFLAG(x, y) ((x) |= (y)) /* Set byte y in byte x*/ +#define SETFLAG(x, y) ((x) |= (y)) /* Set byte y in byte x*/ #define CLEARFLAG(x, y) ((x) &= ~(y)) /* Clear byte y in byte x*/ -#define CHECKFLAG(x, y) ((x) & (y)) /* Check byte y in byte x*/ +#define CHECKFLAG(x, y) ((x) & (y)) /* Check byte y in byte x*/ #define TOGGLEFLAG(x, y) ((x) ^= (y)) /* Toggle byte y in byte x*/ #endif @@ -71,84 +71,84 @@ extern "C" int32_t i; } flt_t; -#define fast_flt_div2(x) \ - ({ \ - flt_t res; \ - res.f = (x); \ - if (res.i & 0x7f800000) \ - res.i -= 0x00800000; \ - else \ - res.i = 0; \ - res.f; \ +#define fast_flt_div2(x) \ + ({ \ + flt_t res; \ + res.f = (x); \ + if (res.i & 0x7f800000) \ + res.i -= 0x00800000; \ + else \ + res.i = 0; \ + res.f; \ }) -#define fast_flt_div4(x) \ - ({ \ - flt_t res; \ - res.f = (x); \ - if (res.i & 0x7f000000) \ - res.i -= 0x01000000; \ - else \ - res.i = 0; \ - res.f; \ +#define fast_flt_div4(x) \ + ({ \ + flt_t res; \ + res.f = (x); \ + if (res.i & 0x7f000000) \ + res.i -= 0x01000000; \ + else \ + res.i = 0; \ + res.f; \ }) -#define fast_flt_mul2(x) \ - ({ \ +#define fast_flt_mul2(x) \ + ({ \ flt_t res; \ res.f = (x); \ if ((res.i & 0x7f800000) != 0x7f800000) \ - res.i += 0x00800000; \ + res.i += 0x00800000; \ res.f; \ }) -#define fast_flt_mul4(x) \ - ({ \ +#define fast_flt_mul4(x) \ + ({ \ flt_t res; \ res.f = (x); \ if ((res.i & 0x7f000000) != 0x7f000000) \ - res.i += 0x01000000; \ + res.i += 0x01000000; \ res.f; \ }) // Quake III based fast sqrt calculation // fast_flt_sqrt takes about 19 clock cycles on AVR instead of +/-482 if using normal sqrt (x25 faster). The error of this shortcut should be under 4~5%. -#define fast_flt_sqrt(x) \ - ({ \ - flt_t res; \ - res.f = (x); \ - if (res.i) \ +#define fast_flt_sqrt(x) \ + ({ \ + flt_t res; \ + res.f = (x); \ + if (res.i) \ res.i = ((res.i >> 1) - 0xe041a9fb); \ - res.f; \ + res.f; \ }) // fast_flt_invsqrt takes about 18 clock cycles on AVR instead of +/-960 if using normal 1/sqrt (x53 faster). The error of this shortcut should be under 4~5%. -#define fast_flt_invsqrt(x) \ - ({ \ +#define fast_flt_invsqrt(x) \ + ({ \ flt_t res; \ res.f = (x); \ res.i = (0x5f3759df - (res.i >> 1)); \ res.f; \ }) // fast_flt_pow2 takes about 25 clock cycles on AVR instead of 144 if using normal pow or muliply by itself (x~5.5 faster). The error of this shortcut should be under 4~5%. -#define fast_flt_pow2(x) \ - ({ \ - flt_t res; \ - res.f = ABS((x)); \ - if (res.f != 0) \ - { \ +#define fast_flt_pow2(x) \ + ({ \ + flt_t res; \ + res.f = ABS((x)); \ + if (res.f != 0) \ + { \ res.i = ((res.i << 1) + 0xc0858106); \ if (res.i < 0) \ - res.i = 0; \ - } \ - res.f; \ + res.i = 0; \ + } \ + res.f; \ }) -#define fast_flt_inv(x) \ - ({ \ +#define fast_flt_inv(x) \ + ({ \ flt_t res; \ res.f = (x); \ res.i = (0x7EF0624D - res.i); \ res.f; \ }) -#define fast_flt_div(y, x) \ - ({ \ +#define fast_flt_div(y, x) \ + ({ \ flt_t res; \ res.f = (x); \ res.i = (0x7EF0624D - res.i); \ @@ -235,7 +235,7 @@ extern "C" volatile uint8_t tail; } ring_buffer_t; -#define DECL_BUFFER(T, N, S) \ +#define DECL_BUFFER(T, N, S) \ static T N##_bufferdata[S]; \ static const uint8_t N##_size = S; \ static ring_buffer_t N @@ -245,201 +245,203 @@ extern "C" #define BUFFER_EMPTY(buffer) (!buffer.count) #define BUFFER_FULL(buffer) (buffer.count == buffer##_size) #define BUFFER_PEEK(buffer) (buffer##_bufferdata[buffer.tail]) -#define BUFFER_REMOVE(buffer) \ - { \ - uint8_t tail; \ - __ATOMIC__ \ - { \ +#define BUFFER_REMOVE(buffer) \ + { \ + uint8_t tail; \ + __ATOMIC__ \ + { \ tail = buffer.tail; \ - } \ - if (!BUFFER_EMPTY(buffer)) \ - { \ + } \ + if (!BUFFER_EMPTY(buffer)) \ + { \ tail++; \ if (tail >= buffer##_size) \ { \ - tail = 0; \ + tail = 0; \ } \ __ATOMIC__ \ { \ - buffer.tail = tail; \ - buffer.count--; \ + buffer.tail = tail; \ + buffer.count--; \ } \ - } \ + } \ } -#define BUFFER_DEQUEUE(buffer, ptr) \ - { \ - if (!BUFFER_EMPTY(buffer)) \ - { \ +#define BUFFER_DEQUEUE(buffer, ptr) \ + { \ + if (!BUFFER_EMPTY(buffer)) \ + { \ uint8_t tail; \ __ATOMIC__ \ { \ - tail = buffer.tail; \ + tail = buffer.tail; \ } \ memcpy(ptr, &buffer##_bufferdata[tail], sizeof(buffer##_bufferdata[0])); \ tail++; \ if (tail >= buffer##_size) \ { \ - tail = 0; \ + tail = 0; \ } \ __ATOMIC__ \ { \ - buffer.tail = tail; \ - buffer.count--; \ + buffer.tail = tail; \ + buffer.count--; \ } \ - } \ + } \ } -#define BUFFER_STORE(buffer) \ - { \ - if (!BUFFER_FULL(buffer)) \ - { \ +#define BUFFER_STORE(buffer) \ + { \ + if (!BUFFER_FULL(buffer)) \ + { \ uint8_t head; \ __ATOMIC__ \ { \ - head = buffer.head; \ + head = buffer.head; \ } \ head++; \ if (head >= buffer##_size) \ { \ - head = 0; \ + head = 0; \ } \ __ATOMIC__ \ { \ - buffer.head = head; \ - buffer.count++; \ + buffer.head = head; \ + buffer.count++; \ } \ - } \ + } \ } -#define BUFFER_ENQUEUE(buffer, ptr) \ - { \ - if (!BUFFER_FULL(buffer)) \ - { \ +#define BUFFER_ENQUEUE(buffer, ptr) \ + { \ + if (!BUFFER_FULL(buffer)) \ + { \ uint8_t head; \ __ATOMIC__ \ { \ - head = buffer.head; \ + head = buffer.head; \ } \ memcpy(&buffer##_bufferdata[head], ptr, sizeof(buffer##_bufferdata[0])); \ head++; \ if (head >= buffer##_size) \ { \ - head = 0; \ + head = 0; \ } \ __ATOMIC__ \ { \ - buffer.head = head; \ - buffer.count++; \ + buffer.head = head; \ + buffer.count++; \ } \ - } \ + } \ } #define BUFFER_NEXT_FREE(buffer) (&buffer##_bufferdata[buffer.head]) -#define BUFFER_WRITE(buffer, ptr, len, written) ({ \ - uint8_t count, head; \ - __ATOMIC__ \ - { \ - head = buffer.head; \ - count = buffer.count; \ - } \ - count = MIN(buffer##_size - count, len); \ - written = 0; \ - if (count) \ - { \ - uint8_t avail = (buffer##_size - head); \ - if (avail < count && avail) \ - { \ +#define BUFFER_WRITE(buffer, ptr, len, written) ({ \ + uint8_t count, head; \ + __ATOMIC__ \ + { \ + head = buffer.head; \ + count = buffer.count; \ + } \ + count = MIN(buffer##_size - count, len); \ + written = 0; \ + if (count) \ + { \ + uint8_t avail = (buffer##_size - head); \ + if (avail < count && avail) \ + { \ memcpy(&buffer##_bufferdata[head], ptr, avail * sizeof(buffer##_bufferdata[0])); \ written = avail; \ count -= avail; \ head = 0; \ - } \ - else \ - { \ + } \ + else \ + { \ avail = 0; \ - } \ - if (count) \ - { \ + } \ + if (count) \ + { \ memcpy(&buffer##_bufferdata[head], &ptr[avail], count * sizeof(buffer##_bufferdata[0])); \ written += count; \ __ATOMIC__ \ { \ - head += count; \ - if (head == buffer##_size) \ - { \ - head = 0; \ - } \ - buffer.head = head; \ - buffer.count += written; \ + head += count; \ + if (head == buffer##_size) \ + { \ + head = 0; \ + } \ + buffer.head = head; \ + buffer.count += written; \ } \ - } \ - } \ + } \ + } \ }) -#define BUFFER_READ(buffer, ptr, len, read) ({ \ - uint8_t count, tail; \ - __ATOMIC__ \ - { \ - tail = buffer.tail; \ - count = buffer.count; \ - } \ - if (count > len) \ - { \ - count = len; \ - } \ - read = 0; \ - if (count) \ - { \ - uint8_t avail = buffer##_size - tail; \ - if (avail < count && avail) \ - { \ +#define BUFFER_READ(buffer, ptr, len, read) ({ \ + uint8_t count, tail; \ + __ATOMIC__ \ + { \ + tail = buffer.tail; \ + count = buffer.count; \ + } \ + if (count > len) \ + { \ + count = len; \ + } \ + read = 0; \ + if (count) \ + { \ + uint8_t avail = buffer##_size - tail; \ + if (avail < count && avail) \ + { \ memcpy(ptr, &buffer##_bufferdata[tail], avail * sizeof(buffer##_bufferdata[0])); \ read = avail; \ count -= avail; \ tail = 0; \ - } \ - else \ - { \ + } \ + else \ + { \ avail = 0; \ - } \ - if (count) \ - { \ + } \ + if (count) \ + { \ memcpy(&ptr[avail], &buffer##_bufferdata[tail], count * sizeof(buffer##_bufferdata[0])); \ read += count; \ __ATOMIC__ \ { \ - tail += count; \ - if (tail == buffer##_size) \ - { \ - tail = 0; \ - } \ - buffer.tail = tail; \ - buffer.count -= read; \ + tail += count; \ + if (tail == buffer##_size) \ + { \ + tail = 0; \ + } \ + buffer.tail = tail; \ + buffer.count -= read; \ } \ - } \ - } \ + } \ + } \ }) -#define BUFFER_CLEAR(buffer) \ - { \ - __ATOMIC__ \ - { \ +#define BUFFER_CLEAR(buffer) \ + { \ + __ATOMIC__ \ + { \ buffer##_bufferdata[0] = 0; \ buffer.tail = 0; \ buffer.head = 0; \ buffer.count = 0; \ - } \ + } \ } #define __TIMEOUT_US__(timeout) for (int32_t elap_us_##timeout, curr_us_##timeout = mcu_free_micros(); ((int32_t)timeout) >= 0; elap_us_##timeout = mcu_free_micros() - curr_us_##timeout, timeout -= ABS(elap_us_##timeout), curr_us_##timeout = mcu_free_micros()) -#define __TIMEOUT_MS__(timeout) timeout*=1000; __TIMEOUT_US__(timeout) -#define __TIMEOUT_ASSERT__(timeout) if(((int32_t)timeout) < 0) +#define __TIMEOUT_MS__(timeout) \ + timeout *= 1000; \ + __TIMEOUT_US__(timeout) +#define __TIMEOUT_ASSERT__(timeout) if (((int32_t)timeout) < 0) #if defined(__GNUC__) && __GNUC__ >= 7 - #define __FALL_THROUGH__ __attribute__ ((fallthrough)); +#define __FALL_THROUGH__ __attribute__((fallthrough)); #else - #define __FALL_THROUGH__ +#define __FALL_THROUGH__ #endif /* __GNUC__ >= 7 */ #ifdef __cplusplus