From 5ec70ed97006085e8e693f388128dfe349c6368b Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Wed, 14 Dec 2016 09:04:19 -0600 Subject: [PATCH 001/193] Making dev-168-gquintic to point to Motate sams70-port --- Motate | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Motate b/Motate index a11381a0a..a6d7e1f75 160000 --- a/Motate +++ b/Motate @@ -1 +1 @@ -Subproject commit a11381a0a17ced68d07cdfcafb6bb62fc1550cbd +Subproject commit a6d7e1f754471d517b0fdeb2fcc89a2c1fb11243 From e0b0db659655c218834091f987d76b1954ce6faf Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Thu, 15 Dec 2016 17:07:56 -0600 Subject: [PATCH 002/193] Update Motate for various fixes (mostly sams70) --- Motate | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Motate b/Motate index a6d7e1f75..c76270ee9 160000 --- a/Motate +++ b/Motate @@ -1 +1 @@ -Subproject commit a6d7e1f754471d517b0fdeb2fcc89a2c1fb11243 +Subproject commit c76270ee9899f43abc413d9555d4827ffba2ca9f From eceb69f36c9c415846d6ed6290296be88ab318e5 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Thu, 15 Dec 2016 17:11:02 -0600 Subject: [PATCH 003/193] Removed unnecessary FREQUENCY_SGI --- g2core/board/Archim/hardware.h | 1 - g2core/board/ArduinoDue/hardware.h | 1 - g2core/board/G2v9/hardware.h | 1 - g2core/board/gquadratic/hardware.h | 1 - g2core/board/gquintic/hardware.h | 1 - g2core/board/printrboardg2/hardware.h | 1 - g2core/board/sbv300/hardware.h | 1 - 7 files changed, 7 deletions(-) diff --git a/g2core/board/Archim/hardware.h b/g2core/board/Archim/hardware.h index 6da178709..77f01ebcb 100644 --- a/g2core/board/Archim/hardware.h +++ b/g2core/board/Archim/hardware.h @@ -120,7 +120,6 @@ using Motate::OutputPin; //#define FREQUENCY_DDA 200000UL // Hz step frequency. Interrupts actually fire at 2x (400 KHz) #define FREQUENCY_DDA 150000UL // Hz step frequency. Interrupts actually fire at 2x (300 KHz) #define FREQUENCY_DWELL 1000UL -#define FREQUENCY_SGI 200000UL // 200,000 Hz means software interrupts will fire 5 uSec after being called /**** Motate Definitions ****/ diff --git a/g2core/board/ArduinoDue/hardware.h b/g2core/board/ArduinoDue/hardware.h index e01e70d4b..3bb1dcfe2 100644 --- a/g2core/board/ArduinoDue/hardware.h +++ b/g2core/board/ArduinoDue/hardware.h @@ -122,7 +122,6 @@ using Motate::OutputPin; //#define FREQUENCY_DDA 200000UL // Hz step frequency. Interrupts actually fire at 2x (400 KHz) #define FREQUENCY_DDA 150000UL // Hz step frequency. Interrupts actually fire at 2x (300 KHz) #define FREQUENCY_DWELL 1000UL -#define FREQUENCY_SGI 200000UL // 200,000 Hz means software interrupts will fire 5 uSec after being called /**** Motate Definitions ****/ diff --git a/g2core/board/G2v9/hardware.h b/g2core/board/G2v9/hardware.h index 260ed18a9..6c86a3668 100644 --- a/g2core/board/G2v9/hardware.h +++ b/g2core/board/G2v9/hardware.h @@ -122,7 +122,6 @@ using Motate::OutputPin; //#define FREQUENCY_DDA 200000UL // Hz step frequency. Interrupts actually fire at 2x (400 KHz) #define FREQUENCY_DDA 150000UL // Hz step frequency. Interrupts actually fire at 2x (300 KHz) #define FREQUENCY_DWELL 1000UL -#define FREQUENCY_SGI 200000UL // 200,000 Hz means software interrupts will fire 5 uSec after being called /**** Motate Definitions ****/ diff --git a/g2core/board/gquadratic/hardware.h b/g2core/board/gquadratic/hardware.h index a28bf8583..9aebf4527 100644 --- a/g2core/board/gquadratic/hardware.h +++ b/g2core/board/gquadratic/hardware.h @@ -123,7 +123,6 @@ using Motate::OutputPin; //#define FREQUENCY_DDA 200000UL // Hz step frequency. Interrupts actually fire at 2x (400 KHz) #define FREQUENCY_DDA 150000UL // Hz step frequency. Interrupts actually fire at 2x (300 KHz) #define FREQUENCY_DWELL 1000UL -#define FREQUENCY_SGI 200000UL // 200,000 Hz means software interrupts will fire 5 uSec after being called /**** Motate Definitions ****/ diff --git a/g2core/board/gquintic/hardware.h b/g2core/board/gquintic/hardware.h index e7fb56ba1..c0d2a500d 100755 --- a/g2core/board/gquintic/hardware.h +++ b/g2core/board/gquintic/hardware.h @@ -121,7 +121,6 @@ using Motate::OutputPin; //#define FREQUENCY_DDA 200000UL // Hz step frequency. Interrupts actually fire at 2x (400 KHz) #define FREQUENCY_DDA 300000UL // Hz step frequency. Interrupts actually fire at 2x (300 KHz) #define FREQUENCY_DWELL 1000UL -#define FREQUENCY_SGI 200000UL // 200,000 Hz means software interrupts will fire 5 uSec after being called /**** Motate Definitions ****/ diff --git a/g2core/board/printrboardg2/hardware.h b/g2core/board/printrboardg2/hardware.h index 244a26816..60d5c1514 100755 --- a/g2core/board/printrboardg2/hardware.h +++ b/g2core/board/printrboardg2/hardware.h @@ -120,7 +120,6 @@ using Motate::OutputPin; //#define FREQUENCY_DDA 200000UL // Hz step frequency. Interrupts actually fire at 2x (400 KHz) #define FREQUENCY_DDA 150000UL // Hz step frequency. Interrupts actually fire at 2x (300 KHz) #define FREQUENCY_DWELL 1000UL -#define FREQUENCY_SGI 200000UL // 200,000 Hz means software interrupts will fire 5 uSec after being called /**** Motate Definitions ****/ diff --git a/g2core/board/sbv300/hardware.h b/g2core/board/sbv300/hardware.h index 5ded07eb4..47ee2b32a 100755 --- a/g2core/board/sbv300/hardware.h +++ b/g2core/board/sbv300/hardware.h @@ -120,7 +120,6 @@ using Motate::OutputPin; //#define FREQUENCY_DDA 200000UL // Hz step frequency. Interrupts actually fire at 2x (400 KHz) #define FREQUENCY_DDA 150000UL // Hz step frequency. Interrupts actually fire at 2x (300 KHz) #define FREQUENCY_DWELL 1000UL -#define FREQUENCY_SGI 200000UL // 200,000 Hz means software interrupts will fire 5 uSec after being called /**** Motate Definitions ****/ From 0c8af6953a43dab77967b47e760512b95d47bdb5 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Thu, 15 Dec 2016 17:11:15 -0600 Subject: [PATCH 004/193] Debugging: enable semihosting --- g2core/board/gquintic.gdb | 2 ++ 1 file changed, 2 insertions(+) diff --git a/g2core/board/gquintic.gdb b/g2core/board/gquintic.gdb index 864a9f89a..bd2e88282 100644 --- a/g2core/board/gquintic.gdb +++ b/g2core/board/gquintic.gdb @@ -1,6 +1,8 @@ # Open and connect to openocd with the ATMEL-ICE target remote | /usr/local/bin/openocd -c "set CHIPNAME ${CHIP}" -f ${MOTATE_PATH}/openocd.cfg -f ${MOTATE_PATH}/platform/atmel_sam/atmel_sam.cfg -c "gdb_port pipe; log_output openocd.log" +monitor arm semihosting enable + source ./board/g2_default.gdb define boot_from_flash From 91300cd9766916d1fa4f9acfdaa3ce5eb337f79d Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Thu, 15 Dec 2016 18:01:49 -0600 Subject: [PATCH 005/193] Adjustments to trinamic SPI message handling --- g2core/device/trinamic/tmc2130.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/g2core/device/trinamic/tmc2130.h b/g2core/device/trinamic/tmc2130.h index 9c541851f..96f3083bd 100644 --- a/g2core/device/trinamic/tmc2130.h +++ b/g2core/device/trinamic/tmc2130.h @@ -634,7 +634,7 @@ struct Trinamic2130 final : Stepper { IOIN_needs_read = true; CHOPCONF_needs_read = true; DRV_STATUS_needs_read = true; - _startNextReadWrite(); } + _startNextReadWrite(); }; }; From bc951217644f1f8733285dc811a0d6e3beac0645 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Thu, 15 Dec 2016 18:02:08 -0600 Subject: [PATCH 006/193] Update motate for sams70 USB connection sequence --- Motate | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Motate b/Motate index c76270ee9..1cd20f410 160000 --- a/Motate +++ b/Motate @@ -1 +1 @@ -Subproject commit c76270ee9899f43abc413d9555d4827ffba2ca9f +Subproject commit 1cd20f410d688d7e4bbfedcd87a77fa0dce56cf3 From ba2364846426951f610fd3a210888e8659df6280 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Fri, 16 Dec 2016 12:35:46 -0600 Subject: [PATCH 007/193] Update Motate reference for new sys calls and fix the sam3x builds --- Motate | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Motate b/Motate index 1cd20f410..2dcd1e22f 160000 --- a/Motate +++ b/Motate @@ -1 +1 @@ -Subproject commit 1cd20f410d688d7e4bbfedcd87a77fa0dce56cf3 +Subproject commit 2dcd1e22fdf1a574972e6c2a345f2cbec0e4ea46 From 0cce90bf8898e22e73fa44a60e26d1277cdd7e0f Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Fri, 6 Jan 2017 15:38:02 -0600 Subject: [PATCH 008/193] Make Neopixel support in gQuadratic non-default. Turn on by changing the define of EXPERIMENTAL_NEOPIXEL_SUPPORT to 1 in board/gquadratic/hardware.cpp --- g2core/board/gquadratic/hardware.cpp | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/g2core/board/gquadratic/hardware.cpp b/g2core/board/gquadratic/hardware.cpp index f40a7928a..494a9dab4 100755 --- a/g2core/board/gquadratic/hardware.cpp +++ b/g2core/board/gquadratic/hardware.cpp @@ -39,6 +39,9 @@ //Motate::ClockOutputPin external_clk_pin {16000000}; // 16MHz optimally //Motate::OutputPin external_clk_pin {Motate::kStartLow}; +#define EXPERIMENTAL_NEOPIXEL_SUPPORT 0 + +#if EXPERIMENTAL_NEOPIXEL_SUPPORT == 1 #include "neopixel.h" #include "canonical_machine.h" @@ -68,6 +71,7 @@ namespace LEDs { cmMachineState last_see_machine_state; float old_x_pos = 0.0; } +#endif // EXPERIMENTAL_NEOPIXEL_SUPPORT /* * hardware_init() - lowest level hardware init @@ -78,11 +82,13 @@ void hardware_init() board_hardware_init(); // external_clk_pin = 0; // Force external clock to 0 for now. +#if EXPERIMENTAL_NEOPIXEL_SUPPORT == 1 for (uint8_t pixel = 0; pixel < LEDs::rgbw_leds.count; pixel++) { LEDs::display_color[pixel].startTransition(100, 0, 0, 0); LEDs::rgbw_leds.setPixel(pixel, LEDs::display_color[pixel]); } LEDs::rgbw_leds.update(); +#endif // EXPERIMENTAL_NEOPIXEL_SUPPORT } /* @@ -91,6 +97,7 @@ void hardware_init() stat_t hardware_periodic() { +#if EXPERIMENTAL_NEOPIXEL_SUPPORT == 1 float x_pos = cm_get_work_position(ACTIVE_MODEL, AXIS_X); if (fabs(LEDs::old_x_pos - x_pos) > 0.01) { LEDs::old_x_pos = x_pos; @@ -120,6 +127,7 @@ stat_t hardware_periodic() } LEDs::rgbw_leds.update(); +#endif // EXPERIMENTAL_NEOPIXEL_SUPPORT return STAT_OK; } From f73bdb182db9a4834aae97deafe9f96cfe929098 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Sun, 8 Jan 2017 14:13:14 -0600 Subject: [PATCH 009/193] Disabling broken (for a long time) debugging code in zoid. --- g2core/plan_zoid.cpp | 28 ++++++++++++++-------------- 1 file changed, 14 insertions(+), 14 deletions(-) diff --git a/g2core/plan_zoid.cpp b/g2core/plan_zoid.cpp index 4c0a18301..12f85d3fa 100644 --- a/g2core/plan_zoid.cpp +++ b/g2core/plan_zoid.cpp @@ -34,21 +34,21 @@ //+++++ DIAGNOSTICS -#if IN_DEBUGGER < 1 +//#if IN_DEBUGGER < 1 #define LOG_RETURN(msg) // LOG_RETURN with no action (production) -#else -#include "xio.h" -static char logbuf[128]; -static void _logger(const char *msg, const mpBuf_t *bf) // LOG_RETURN with full state dump -{ - sprintf(logbuf, "[%2d] %s (%d) mt:%5.2f, L:%1.3f [%1.3f, %1.3f, %1.3f] V:[%1.2f, %1.2f, %1.2f]\n", - bf->buffer_number, msg, bf->hint, (bf->block_time * 60000), - bf->length, bf->head_length, bf->body_length, bf->tail_length, - bf->pv->exit_velocity, bf->cruise_velocity, bf->exit_velocity); - xio_writeline(logbuf); -} -#define LOG_RETURN(msg) { _logger(msg, bf); } -#endif +//#else +//#include "xio.h" +//static char logbuf[128]; +//static void _logger(const char *msg, const mpBuf_t *bf) // LOG_RETURN with full state dump +//{ +// sprintf(logbuf, "[%2d] %s (%d) mt:%5.2f, L:%1.3f [%1.3f, %1.3f, %1.3f] V:[%1.2f, %1.2f, %1.2f]\n", +// bf->buffer_number, msg, bf->hint, (bf->block_time * 60000), +// bf->length, bf->head_length, bf->body_length, bf->tail_length, +// bf->pv->exit_velocity, bf->cruise_velocity, bf->exit_velocity); +// xio_writeline(logbuf); +//} +//#define LOG_RETURN(msg) { _logger(msg, bf); } +//#endif #if IN_DEBUGGER < 1 #define TRAP_ZERO(t,m) From 01b004b7673211fd609a8f282dae3432bf68447a Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Sun, 8 Jan 2017 14:13:58 -0600 Subject: [PATCH 010/193] Adjusting the Quintic board to use all timers for planning/step generation (no SysCalls). --- g2core/board/gquintic/hardware.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/g2core/board/gquintic/hardware.h b/g2core/board/gquintic/hardware.h index 2e6a5c305..83d9b0ae4 100644 --- a/g2core/board/gquintic/hardware.h +++ b/g2core/board/gquintic/hardware.h @@ -127,9 +127,9 @@ using Motate::OutputPin; // Timer definitions. See stepper.h and other headers for setup typedef TimerChannel<9, 0> dda_timer_type; // stepper pulse generation in stepper.cpp -typedef TimerChannel<10, 0> load_timer_type; // request load timer in stepper.cpp -typedef ServiceCall<1> exec_timer_type; // request exec timer in stepper.cpp -typedef ServiceCall<2> fwd_plan_timer_type; // request exec timer in stepper.cpp +//typedef TimerChannel<10, 0> load_timer_type; // request load timer in stepper.cpp +typedef TimerChannel<10, 0> exec_timer_type; // request exec timer in stepper.cpp +typedef TimerChannel<11, 0> fwd_plan_timer_type; // request exec timer in stepper.cpp Motate::service_call_number kSPI_ServiceCallNumber = 3; From 5d8f3615ec9b4dd8aa21bd82b2f68bc46dc4c076 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Sun, 8 Jan 2017 14:14:39 -0600 Subject: [PATCH 011/193] Moving the load_move call outside of a syscall/timer. --- g2core/stepper.cpp | 27 ++++++++++++++------------- 1 file changed, 14 insertions(+), 13 deletions(-) diff --git a/g2core/stepper.cpp b/g2core/stepper.cpp index 43c50ec6d..0b1c8f8c6 100644 --- a/g2core/stepper.cpp +++ b/g2core/stepper.cpp @@ -76,7 +76,7 @@ extern OutputPin debug_pin3; //extern OutputPin debug_pin4; dda_timer_type dda_timer {kTimerUpToMatch, FREQUENCY_DDA}; // stepper pulse generation -load_timer_type load_timer; // triggers load of next stepper segment +//load_timer_type load_timer; // triggers load of next stepper segment exec_timer_type exec_timer; // triggers calculation of next+1 stepper segment fwd_plan_timer_type fwd_plan_timer; // triggers planning of next block @@ -126,7 +126,7 @@ void stepper_init() dda_timer.setInterrupts(kInterruptOnOverflow | kInterruptPriorityHighest); // setup software interrupt load timer - load_timer.setInterrupts(kInterruptOnSoftwareTrigger | kInterruptPriorityHigh); +// load_timer.setInterrupts(kInterruptOnSoftwareTrigger | kInterruptPriorityHigh); // setup software interrupt exec timer & initial condition exec_timer.setInterrupts(kInterruptOnSoftwareTrigger | kInterruptPriorityMedium); @@ -417,20 +417,21 @@ void st_request_load_move() stepper_debug("l"); if (st_pre.buffer_state == PREP_BUFFER_OWNED_BY_LOADER) { // bother interrupting stepper_debug("_"); - load_timer.setInterruptPending(); +// load_timer.setInterruptPending(); + _load_move(); } } -namespace Motate { // Define timer inside Motate namespace - template<> - void load_timer_type::interrupt() - { - load_timer.getInterruptCause(); // read SR to clear interrupt condition - stepper_debug("L>"); - _load_move(); - stepper_debug("L+\n"); - } -} // namespace Motate +//namespace Motate { // Define timer inside Motate namespace +// template<> +// void load_timer_type::interrupt() +// { +// load_timer.getInterruptCause(); // read SR to clear interrupt condition +// stepper_debug("L>"); +// _load_move(); +// stepper_debug("L+\n"); +// } +//} // namespace Motate /**************************************************************************************** * _load_move() - Dequeue move and load into stepper runtime structure From eb80e1e17b16c5236e5fe87b66fbb16d2a12dc1f Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Thu, 16 Feb 2017 12:02:41 -0600 Subject: [PATCH 012/193] Added support for AxiDrawv3, and cleaned up some other code --- Motate | 2 +- g2core/board/gquadratic/hardware.h | 9 +- g2core/board/gquintic/hardware.h | 1 - g2core/boards.mk | 6 + g2core/canonical_machine.cpp | 9 + g2core/g2core.xcodeproj/project.pbxproj | 40 +++ .../G2 gQuadratic AxiDrawv3.xcscheme | 80 +++++ .../G2 gQuadratic Test copy.xcscheme | 80 +++++ g2core/settings/settings_axidraw_v3.h | 329 ++++++++++++++++++ g2core/settings/settings_eggbot.h | 2 +- g2core/settings/settings_watercolorbot_v2.h | 2 +- 11 files changed, 551 insertions(+), 9 deletions(-) create mode 100644 g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 gQuadratic AxiDrawv3.xcscheme create mode 100644 g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 gQuadratic Test copy.xcscheme create mode 100755 g2core/settings/settings_axidraw_v3.h diff --git a/Motate b/Motate index 2bccbe874..db22af8c3 160000 --- a/Motate +++ b/Motate @@ -1 +1 @@ -Subproject commit 2bccbe87433b9f773f90c196f037067d471b9501 +Subproject commit db22af8c3cd5af5d11cb97c70fece51259dc9f38 diff --git a/g2core/board/gquadratic/hardware.h b/g2core/board/gquadratic/hardware.h index 68942e7a7..265555ffc 100644 --- a/g2core/board/gquadratic/hardware.h +++ b/g2core/board/gquadratic/hardware.h @@ -58,7 +58,7 @@ enum hwPlatform { #define AXES 6 // number of axes supported in this version #define HOMING_AXES 4 // number of axes that can be homed (assumes Zxyabc sequence) -#define MOTORS 2 // number of motors on the board +#define MOTORS 3 // number of motors on the board #define COORDS 6 // number of supported coordinate systems (index starts at 1) #define PWMS 2 // number of supported PWM channels #define TOOLS 32 // number of entries in tool table (index starts at 1) @@ -127,10 +127,9 @@ using Motate::OutputPin; /**** Motate Definitions ****/ // Timer definitions. See stepper.h and other headers for setup -typedef TimerChannel<9, 0> dda_timer_type; // stepper pulse generation in stepper.cpp -typedef TimerChannel<10, 0> load_timer_type; // request load timer in stepper.cpp -typedef ServiceCall<1> exec_timer_type; // request exec timer in stepper.cpp -typedef ServiceCall<2> fwd_plan_timer_type; // request exec timer in stepper.cpp +typedef TimerChannel<9, 0> dda_timer_type; // stepper pulse generation in stepper.cpp +typedef TimerChannel<10, 0> exec_timer_type; // request exec timer in stepper.cpp +typedef TimerChannel<11, 0> fwd_plan_timer_type; // request exec timer in stepper.cpp // Pin assignments diff --git a/g2core/board/gquintic/hardware.h b/g2core/board/gquintic/hardware.h index 83d9b0ae4..42a789eb3 100644 --- a/g2core/board/gquintic/hardware.h +++ b/g2core/board/gquintic/hardware.h @@ -127,7 +127,6 @@ using Motate::OutputPin; // Timer definitions. See stepper.h and other headers for setup typedef TimerChannel<9, 0> dda_timer_type; // stepper pulse generation in stepper.cpp -//typedef TimerChannel<10, 0> load_timer_type; // request load timer in stepper.cpp typedef TimerChannel<10, 0> exec_timer_type; // request exec timer in stepper.cpp typedef TimerChannel<11, 0> fwd_plan_timer_type; // request exec timer in stepper.cpp diff --git a/g2core/boards.mk b/g2core/boards.mk index f51eca4d1..222ddf679 100644 --- a/g2core/boards.mk +++ b/g2core/boards.mk @@ -153,6 +153,12 @@ ifeq ("$(CONFIG)","EggBot") endif SETTINGS_FILE="settings_eggbot.h" endif +ifeq ("$(CONFIG)","AxiDrawv3") + ifeq ("$(BOARD)","NONE") + BOARD=gquadratic-b + endif + SETTINGS_FILE="settings_axidraw_v3.h" +endif include $(wildcard ./board/$(STAR).mk) diff --git a/g2core/canonical_machine.cpp b/g2core/canonical_machine.cpp index 1d07d2ae8..34ccbae99 100644 --- a/g2core/canonical_machine.cpp +++ b/g2core/canonical_machine.cpp @@ -709,6 +709,15 @@ void canonical_machine_reset_rotation() { cm.rotation_matrix[1][1] = 1.0; cm.rotation_matrix[2][2] = 1.0; cm.rotation_z_offset = 0.0; + +#ifdef ROTATION_ABOUT_Z + float cos_z = cos(ROTATION_ABOUT_Z); + float sin_z = sin(ROTATION_ABOUT_Z); + cm.rotation_matrix[0][0] = -cos_z; + cm.rotation_matrix[0][1] = sin_z; + cm.rotation_matrix[1][0] = -sin_z; + cm.rotation_matrix[1][1] = -cos_z; +#endif } void canonical_machine_reset() diff --git a/g2core/g2core.xcodeproj/project.pbxproj b/g2core/g2core.xcodeproj/project.pbxproj index 670d7df0b..de6f522f5 100644 --- a/g2core/g2core.xcodeproj/project.pbxproj +++ b/g2core/g2core.xcodeproj/project.pbxproj @@ -283,6 +283,20 @@ passBuildSettingsInEnvironment = 1; productName = g3_due; }; + D492E5AE1E54C2B4005ED97D /* G2 gQuadratic AxiDraw v3 */ = { + isa = PBXLegacyTarget; + buildArgumentsString = "$(ACTION) VERBOSE=1 COLOR=0 CONFIG=AxiDrawv3 DEBUG=2"; + buildConfigurationList = D492E5AF1E54C2B4005ED97D /* Build configuration list for PBXLegacyTarget "G2 gQuadratic AxiDraw v3" */; + buildPhases = ( + ); + buildToolPath = /usr/bin/make; + buildWorkingDirectory = .; + dependencies = ( + ); + name = "G2 gQuadratic AxiDraw v3"; + passBuildSettingsInEnvironment = 1; + productName = g3_due; + }; D4AC391A1C7BAB8E0098D685 /* G2 sbv300 */ = { isa = PBXLegacyTarget; buildArgumentsString = "$(ACTION) VERBOSE=1 COLOR=0 CONFIG=sbv300 DEBUG=2"; @@ -406,6 +420,7 @@ D4782AAE1D9B16BE00B32136 /* G2 Probotix */, D457112317053BFB00EA19A8 /* index */, D4782AB61D9E39EC00B32136 /* G2 EggBot */, + D492E5AE1E54C2B4005ED97D /* G2 gQuadratic AxiDraw v3 */, ); }; /* End PBXProject section */ @@ -679,6 +694,22 @@ }; name = Release; }; + D492E5B01E54C2B4005ED97D /* Debug */ = { + isa = XCBuildConfiguration; + buildSettings = { + PATH = "$PATH:/usr/local/gcc-arm-none-eabi/bin"; + PRODUCT_NAME = "$(TARGET_NAME)"; + }; + name = Debug; + }; + D492E5B11E54C2B4005ED97D /* Release */ = { + isa = XCBuildConfiguration; + buildSettings = { + PATH = "$PATH:/usr/local/gcc-arm-none-eabi/bin"; + PRODUCT_NAME = "$(TARGET_NAME)"; + }; + name = Release; + }; D4AC391C1C7BAB8E0098D685 /* Debug */ = { isa = XCBuildConfiguration; buildSettings = { @@ -834,6 +865,15 @@ defaultConfigurationIsVisible = 0; defaultConfigurationName = Release; }; + D492E5AF1E54C2B4005ED97D /* Build configuration list for PBXLegacyTarget "G2 gQuadratic AxiDraw v3" */ = { + isa = XCConfigurationList; + buildConfigurations = ( + D492E5B01E54C2B4005ED97D /* Debug */, + D492E5B11E54C2B4005ED97D /* Release */, + ); + defaultConfigurationIsVisible = 0; + defaultConfigurationName = Release; + }; D4AC391B1C7BAB8E0098D685 /* Build configuration list for PBXLegacyTarget "G2 sbv300" */ = { isa = XCConfigurationList; buildConfigurations = ( diff --git a/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 gQuadratic AxiDrawv3.xcscheme b/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 gQuadratic AxiDrawv3.xcscheme new file mode 100644 index 000000000..e21407543 --- /dev/null +++ b/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 gQuadratic AxiDrawv3.xcscheme @@ -0,0 +1,80 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 gQuadratic Test copy.xcscheme b/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 gQuadratic Test copy.xcscheme new file mode 100644 index 000000000..e21407543 --- /dev/null +++ b/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 gQuadratic Test copy.xcscheme @@ -0,0 +1,80 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/g2core/settings/settings_axidraw_v3.h b/g2core/settings/settings_axidraw_v3.h new file mode 100755 index 000000000..0421ebb5c --- /dev/null +++ b/g2core/settings/settings_axidraw_v3.h @@ -0,0 +1,329 @@ +/* + * settings_watercolorbot_v2.h - settings for the WaterColorBot v2 (http://watercolorbot.com/) + * This file is part of the g2core project + * + * Copyright (c) 2016 Alden S. Hart Jr. + * Copyright (c) 2016 Robert Giseburt + * + * This file ("the software") is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License, version 2 as published by the + * Free Software Foundation. You should have received a copy of the GNU General Public + * License, version 2 along with the software. If not, see . + * + * As a special exception, you may use this file as part of a software library without + * restriction. Specifically, if other files instantiate templates or use macros or + * inline functions from this file, or you compile this file and link it with other + * files to produce an executable, this file does not by itself cause the resulting + * executable to be covered by the GNU General Public License. This exception does not + * however invalidate any other reasons why the executable file might be covered by the + * GNU General Public License. + * + * THE SOFTWARE IS DISTRIBUTED IN THE HOPE THAT IT WILL BE USEFUL, BUT WITHOUT ANY + * WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES + * OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT + * SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF + * OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + */ + +/***********************************************************************/ +/**** TestV9 profile - naked board *************************************/ +/***********************************************************************/ + +// ***> NOTE: The init message must be a single line with no CRs or LFs +#define INIT_MESSAGE "Initializing configs to WaterColorBot v2 settings" + +#define JUNCTION_INTEGRATION_TIME 1.50 // cornering - usually between 0.5 and 2.0 (higher is faster) +#define CHORDAL_TOLERANCE 0.01 // chordal accuracy for arc drawing (in mm) + +#define SOFT_LIMIT_ENABLE 0 // 0=off, 1=on +#define HARD_LIMIT_ENABLE 1 // 0=off, 1=on +#define SAFETY_INTERLOCK_ENABLE 1 // 0=off, 1=on + +#define SPINDLE_ENABLE_POLARITY 1 // 0=active low, 1=active high +#define SPINDLE_DIR_POLARITY 0 // 0=clockwise is low, 1=clockwise is high +#define SPINDLE_PAUSE_ON_HOLD true +#define SPINDLE_DWELL_TIME 1.0 + +#define COOLANT_MIST_POLARITY 1 // 0=active low, 1=active high +#define COOLANT_FLOOD_POLARITY 1 // 0=active low, 1=active high +#define COOLANT_PAUSE_ON_HOLD false + +// Communications and reporting settings + +#define COMM_MODE JSON_MODE // one of: TEXT_MODE, JSON_MODE +#define XIO_ENABLE_FLOW_CONTROL FLOW_CONTROL_RTS // FLOW_CONTROL_OFF, FLOW_CONTROL_RTS + +#define TEXT_VERBOSITY TV_VERBOSE // one of: TV_SILENT, TV_VERBOSE +#define JSON_VERBOSITY JV_MESSAGES // one of: JV_SILENT, JV_FOOTER, JV_CONFIGS, JV_MESSAGES, JV_LINENUM, JV_VERBOSE +#define QUEUE_REPORT_VERBOSITY QR_OFF // one of: QR_OFF, QR_SINGLE, QR_TRIPLE + +#define STATUS_REPORT_VERBOSITY SR_FILTERED // one of: SR_OFF, SR_FILTERED, SR_VERBOSE +#define STATUS_REPORT_MIN_MS 100 // milliseconds - enforces a viable minimum +#define STATUS_REPORT_INTERVAL_MS 250 // milliseconds - set $SV=0 to disable + +//#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","bcr","feed","vel","unit","coor","dist","admo","frmo","momo","stat" +#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","feed","vel","momo","stat" + +// Alternate SRs +//#define STATUS_REPORT_DEFAULTS "line","vel","mpox","mpoy","mpoz","mpoa","coor","ofsa","ofsx","ofsy","ofsz","dist","unit","stat","homz","homy","homx","momo" +//#define STATUS_REPORT_DEFAULTS "_ts1","_cs1","_es1","_xs1","_fe1","line","posx","posy","posz","vel","stat" +//#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","vel","_cs1","_es1","_xs1","_fe1","_cs2","_es2","_xs2","_fe2" +//#define STATUS_REPORT_DEFAULTS "mpox","mpoy","mpoz","mpoa","ofsx","ofsy","ofsz","ofsa","unit","stat","coor","momo","dist","home","hold","macs","cycs","mots","plan","feed" +//#define STATUS_REPORT_DEFAULTS "line","mpox","mpoy","mpoz","mpoa","ofsx","ofsy","ofsz","ofsa","stat","_cs1","_es1","_fe0","_fe1","_fe2","_fe3" +//#define STATUS_REPORT_DEFAULTS "line","mpox","mpoy","mpoz","stat","_ts2","_ps2","_cs2","_es2","_fe2" +//#define STATUS_REPORT_DEFAULTS "line","mpox","mpoy","mpoz","_cs3","_es3","_fe3","_xs3","_cs2","_es2","_fe2","_xs2","stat" +//#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","feed","vel","unit","coor","dist","frmo","momo","stat","_cs1","_es1","_xs1","_fe1" + +// Gcode startup defaults +#define GCODE_DEFAULT_UNITS MILLIMETERS // MILLIMETERS or INCHES +#define GCODE_DEFAULT_PLANE CANON_PLANE_XY // CANON_PLANE_XY, CANON_PLANE_XZ, or CANON_PLANE_YZ +#define GCODE_DEFAULT_COORD_SYSTEM G54 // G54, G55, G56, G57, G58 or G59 +#define GCODE_DEFAULT_PATH_CONTROL PATH_CONTINUOUS +#define GCODE_DEFAULT_DISTANCE_MODE ABSOLUTE_DISTANCE_MODE + +// *** motor settings ************************************************************************************ + +#define MOTOR_POWER_MODE MOTOR_POWERED_IN_CYCLE // default motor power mode (see cmMotorPowerMode in stepper.h) +#define MOTOR_POWER_TIMEOUT 2.00 // motor power timeout in seconds + +#define MOTOR_POWER_MODE MOTOR_POWERED_IN_CYCLE // default motor power mode (see cmMotorPowerMode in stepper.h) +#define MOTOR_POWER_TIMEOUT 2.00 // motor power timeout in seconds + +#define M1_MOTOR_MAP AXIS_Y // 1ma +#define M1_STEP_ANGLE 1.8 // 1sa +// According to the EiBB settings here: +// https://github.com/evil-mad/axidraw/blob/master/inkscape%20driver/axidraw_conf.py +// At 16x microstepping, it's 2032 steps per INCH, which is ((16/2032)*25.4) = 0.2mm per FULL step +// With a 200 step/revolution (1.8º/step) motor, that's 0.2*200=40mm per revolution +#define M1_TRAVEL_PER_REV 40 // 1tr +#define M1_MICROSTEPS 32 // 1mi 1,2,4,8 +#define M1_POLARITY 0 // 1po 0=normal, 1=reversed +#define M1_POWER_MODE MOTOR_POWER_MODE // 1pm standard +#define M1_POWER_LEVEL 0.4 + +#define M2_MOTOR_MAP AXIS_X +#define M2_STEP_ANGLE 1.8 +#define M2_TRAVEL_PER_REV 40 +#define M2_MICROSTEPS 32 +#define M2_POLARITY 1 +#define M2_POWER_MODE MOTOR_POWER_MODE +#define M2_POWER_LEVEL 0.4 + +#define M3_MOTOR_MAP AXIS_Z + // This "stepper" is a hobby servo. Note that all hobby + // servo settings are per full servo range, instead of + // per revolution. +#define M3_STEP_ANGLE 1.8 // hobby servos are simulated with 200 "full steps" +#define M3_TRAVEL_PER_REV 26 // this is actually the full travel of the servo, not + // necessarily covering a revolution +#define M3_MICROSTEPS 32 // the max step resolution for a hobby servo is 1/32 +#define M3_POLARITY 1 +#define M3_POWER_MODE MOTOR_ALWAYS_POWERED +#define M3_POWER_LEVEL 0.50 // this is ignored + + +// *** axis settings ********************************************************************************** + +#define JERK_MAX 20000 + +#define X_AXIS_MODE AXIS_STANDARD // xam see canonical_machine.h cmAxisMode for valid values +#define X_VELOCITY_MAX 50000 // xvm G0 max velocity in mm/min +#define X_FEEDRATE_MAX X_VELOCITY_MAX // xfr G1 max feed rate in mm/min +#define X_TRAVEL_MIN 0 // xtn minimum travel - used by soft limits and homing +#define X_TRAVEL_MAX 400 // xtm maximum travel - used by soft limits and homing +#define X_JERK_MAX JERK_MAX // xjm +#define X_JERK_HIGH_SPEED X_JERK_MAX // xjh +#define X_HOMING_INPUT 1 // xhi input used for homing or 0 to disable +#define X_HOMING_DIRECTION 0 // xhd 0=search moves negative, 1= search moves positive +#define X_SEARCH_VELOCITY 1000 // xsv move in negative direction +#define X_LATCH_VELOCITY 100 // xlv mm/min +#define X_LATCH_BACKOFF 10 // xlb mm +#define X_ZERO_BACKOFF 2 // xzb mm + +#define Y_AXIS_MODE AXIS_STANDARD +#define Y_VELOCITY_MAX 50000 +#define Y_FEEDRATE_MAX Y_VELOCITY_MAX +#define Y_TRAVEL_MIN 0 +#define Y_TRAVEL_MAX 175 +#define Y_JERK_MAX JERK_MAX +#define Y_JERK_HIGH_SPEED Y_JERK_MAX +#define Y_HOMING_INPUT 3 +#define Y_HOMING_DIRECTION 0 +#define Y_SEARCH_VELOCITY 1000 +#define Y_LATCH_VELOCITY 100 +#define Y_LATCH_BACKOFF 10 +#define Y_ZERO_BACKOFF 2 + +#define Z_AXIS_MODE AXIS_STANDARD +#define Z_VELOCITY_MAX 15000 +#define Z_FEEDRATE_MAX Z_VELOCITY_MAX +#define Z_TRAVEL_MIN 0 +#define Z_TRAVEL_MAX 75 +#define Z_JERK_MAX 5000 +#define Z_JERK_HIGH_SPEED Z_JERK_MAX +#define Z_HOMING_INPUT 6 +#define Z_HOMING_DIRECTION 1 +#define Z_SEARCH_VELOCITY 600 +#define Z_LATCH_VELOCITY 100 +#define Z_LATCH_BACKOFF 10 +#define Z_ZERO_BACKOFF 2 + +//*** Input / output settings *** +/* + IO_MODE_DISABLED + IO_ACTIVE_LOW aka NORMALLY_OPEN + IO_ACTIVE_HIGH aka NORMALLY_CLOSED + + INPUT_ACTION_NONE + INPUT_ACTION_STOP + INPUT_ACTION_FAST_STOP + INPUT_ACTION_HALT + INPUT_ACTION_RESET + + INPUT_FUNCTION_NONE + INPUT_FUNCTION_LIMIT + INPUT_FUNCTION_INTERLOCK + INPUT_FUNCTION_SHUTDOWN + INPUT_FUNCTION_PANIC +*/ +// Inputs are defined for the g2ref(a) board +// Xmn (board label) +#define DI1_MODE IO_ACTIVE_HIGH +#define DI1_ACTION INPUT_ACTION_NONE +#define DI1_FUNCTION INPUT_FUNCTION_NONE + +// Xmax +#define DI2_MODE IO_MODE_DISABLED +#define DI2_ACTION INPUT_ACTION_NONE +#define DI2_FUNCTION INPUT_FUNCTION_NONE + +// Ymin +#define DI3_MODE IO_MODE_DISABLED +#define DI3_ACTION INPUT_ACTION_NONE +#define DI3_FUNCTION INPUT_FUNCTION_NONE + +// Ymax +#define DI4_MODE IO_ACTIVE_HIGH +#define DI4_ACTION INPUT_ACTION_NONE +#define DI4_FUNCTION INPUT_FUNCTION_NONE + +// Zmin +#define DI5_MODE IO_ACTIVE_LOW // Z probe +#define DI5_ACTION INPUT_ACTION_NONE +#define DI5_FUNCTION INPUT_FUNCTION_NONE + +// Zmax +#define DI6_MODE IO_MODE_DISABLED +#define DI6_ACTION INPUT_ACTION_STOP +#define DI6_FUNCTION INPUT_FUNCTION_NONE + +// Shutdown (Amin on v9 board) +#define DI7_MODE IO_MODE_DISABLED +#define DI7_ACTION INPUT_ACTION_NONE +#define DI7_FUNCTION INPUT_FUNCTION_NONE + +// High Voltage Z Probe In (Amax on v9 board) +#define DI8_MODE IO_ACTIVE_LOW +#define DI8_ACTION INPUT_ACTION_NONE +#define DI8_FUNCTION INPUT_FUNCTION_NONE + +// Hardware interlock input +#define DI9_MODE IO_MODE_DISABLED +#define DI9_ACTION INPUT_ACTION_NONE +#define DI9_FUNCTION INPUT_FUNCTION_NONE + +//Extruder1_PWM +#define DO1_MODE IO_ACTIVE_HIGH + +//Extruder2_PWM +#define DO2_MODE IO_ACTIVE_HIGH + +//Fan1A_PWM +#define DO3_MODE IO_ACTIVE_HIGH + +//Fan1B_PWM +#define DO4_MODE IO_ACTIVE_HIGH + +#define DO5_MODE IO_ACTIVE_HIGH +#define DO6_MODE IO_ACTIVE_HIGH +#define DO7_MODE IO_ACTIVE_HIGH +#define DO8_MODE IO_ACTIVE_HIGH + +//SAFEin (Output) signal +#define DO9_MODE IO_ACTIVE_HIGH + +#define DO10_MODE IO_ACTIVE_HIGH + +//Header Bed FET +#define DO11_MODE IO_ACTIVE_HIGH + +//Indicator_LED +#define DO12_MODE IO_ACTIVE_HIGH + +#define DO13_MODE IO_ACTIVE_HIGH + + +// *** PWM SPINDLE CONTROL *** + +#define P1_PWM_FREQUENCY 100 // in Hz +#define P1_CW_SPEED_LO 1000 // in RPM (arbitrary units) +#define P1_CW_SPEED_HI 2000 +#define P1_CW_PHASE_LO 0.125 // phase [0..1] +#define P1_CW_PHASE_HI 0.2 +#define P1_CCW_SPEED_LO 1000 +#define P1_CCW_SPEED_HI 2000 +#define P1_CCW_PHASE_LO 0.125 +#define P1_CCW_PHASE_HI 0.2 +#define P1_PWM_PHASE_OFF 0.1 + +// *** DEFAULT COORDINATE SYSTEM OFFSETS *** + +#define G54_X_OFFSET 0 // G54 is traditionally set to all zeros +#define G54_Y_OFFSET 0 +#define G54_Z_OFFSET 0 +#define G54_A_OFFSET 0 +#define G54_B_OFFSET 0 +#define G54_C_OFFSET 0 + +#define G55_X_OFFSET (X_TRAVEL_MAX/2) // set to middle of table +#define G55_Y_OFFSET (Y_TRAVEL_MAX/2) +#define G55_Z_OFFSET 0 +#define G55_A_OFFSET 0 +#define G55_B_OFFSET 0 +#define G55_C_OFFSET 0 + +#define G56_X_OFFSET 0 +#define G56_Y_OFFSET 0 +#define G56_Z_OFFSET 0 +#define G56_A_OFFSET 0 +#define G56_B_OFFSET 0 +#define G56_C_OFFSET 0 + +#define G57_X_OFFSET 0 +#define G57_Y_OFFSET 0 +#define G57_Z_OFFSET 0 +#define G57_A_OFFSET 0 +#define G57_B_OFFSET 0 +#define G57_C_OFFSET 0 + +#define G58_X_OFFSET 0 +#define G58_Y_OFFSET 0 +#define G58_Z_OFFSET 0 +#define G58_A_OFFSET 0 +#define G58_B_OFFSET 0 +#define G58_C_OFFSET 0 + +#define G59_X_OFFSET 0 +#define G59_Y_OFFSET 0 +#define G59_Z_OFFSET 0 +#define G59_A_OFFSET 0 +#define G59_B_OFFSET 0 +#define G59_C_OFFSET 0 + +// *** DEFAULT COORDINATE SYSTEM ROTATION *** + +// values are in radians, and are floating point values +#define ROTATION_ABOUT_X 0.0 +#define ROTATION_ABOUT_Y 0.0 +#define ROTATION_ABOUT_Z -0.7853981634 // ((2pi)/360)*45 diff --git a/g2core/settings/settings_eggbot.h b/g2core/settings/settings_eggbot.h index 4527a339a..25303fdc0 100755 --- a/g2core/settings/settings_eggbot.h +++ b/g2core/settings/settings_eggbot.h @@ -80,7 +80,7 @@ #define GCODE_DEFAULT_PLANE CANON_PLANE_XY // CANON_PLANE_XY, CANON_PLANE_XZ, or CANON_PLANE_YZ #define GCODE_DEFAULT_COORD_SYSTEM G54 // G54, G55, G56, G57, G58 or G59 #define GCODE_DEFAULT_PATH_CONTROL PATH_CONTINUOUS -#define GCODE_DEFAULT_DISTANCE_MODE ABSOLUTE_MODE +#define GCODE_DEFAULT_DISTANCE_MODE ABSOLUTE_DISTANCE_MODE // *** motor settings ************************************************************************************ diff --git a/g2core/settings/settings_watercolorbot_v2.h b/g2core/settings/settings_watercolorbot_v2.h index 2eb170a91..3dc87ec8b 100755 --- a/g2core/settings/settings_watercolorbot_v2.h +++ b/g2core/settings/settings_watercolorbot_v2.h @@ -80,7 +80,7 @@ #define GCODE_DEFAULT_PLANE CANON_PLANE_XY // CANON_PLANE_XY, CANON_PLANE_XZ, or CANON_PLANE_YZ #define GCODE_DEFAULT_COORD_SYSTEM G54 // G54, G55, G56, G57, G58 or G59 #define GCODE_DEFAULT_PATH_CONTROL PATH_CONTINUOUS -#define GCODE_DEFAULT_DISTANCE_MODE ABSOLUTE_MODE +#define GCODE_DEFAULT_DISTANCE_MODE ABSOLUTE_DISTANCE_MODE // *** motor settings ************************************************************************************ From 62919b06627e4a1c06a6d3127e7bfa8b366c8076 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Sat, 18 Feb 2017 08:55:20 -0600 Subject: [PATCH 013/193] Removing ROTATION_ABOUT_Z, in prep for adding proper Kinematics for CoreXY --- g2core/canonical_machine.cpp | 10 +--------- g2core/settings/settings_axidraw_v3.h | 7 ------- 2 files changed, 1 insertion(+), 16 deletions(-) diff --git a/g2core/canonical_machine.cpp b/g2core/canonical_machine.cpp index 34ccbae99..ad1c132ca 100644 --- a/g2core/canonical_machine.cpp +++ b/g2core/canonical_machine.cpp @@ -106,6 +106,7 @@ #include "temperature.h" #include "hardware.h" #include "util.h" +#include "settings.h" #include "xio.h" // for serial queue flush /*********************************************************************************** @@ -709,15 +710,6 @@ void canonical_machine_reset_rotation() { cm.rotation_matrix[1][1] = 1.0; cm.rotation_matrix[2][2] = 1.0; cm.rotation_z_offset = 0.0; - -#ifdef ROTATION_ABOUT_Z - float cos_z = cos(ROTATION_ABOUT_Z); - float sin_z = sin(ROTATION_ABOUT_Z); - cm.rotation_matrix[0][0] = -cos_z; - cm.rotation_matrix[0][1] = sin_z; - cm.rotation_matrix[1][0] = -sin_z; - cm.rotation_matrix[1][1] = -cos_z; -#endif } void canonical_machine_reset() diff --git a/g2core/settings/settings_axidraw_v3.h b/g2core/settings/settings_axidraw_v3.h index 0421ebb5c..18daeba20 100755 --- a/g2core/settings/settings_axidraw_v3.h +++ b/g2core/settings/settings_axidraw_v3.h @@ -320,10 +320,3 @@ #define G59_A_OFFSET 0 #define G59_B_OFFSET 0 #define G59_C_OFFSET 0 - -// *** DEFAULT COORDINATE SYSTEM ROTATION *** - -// values are in radians, and are floating point values -#define ROTATION_ABOUT_X 0.0 -#define ROTATION_ABOUT_Y 0.0 -#define ROTATION_ABOUT_Z -0.7853981634 // ((2pi)/360)*45 From 91f7793f86a8b3a72a9b9b82677746bb9a42c6d0 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Sat, 18 Feb 2017 08:57:19 -0600 Subject: [PATCH 014/193] Added CoreXY Kinematics, and set AxiDraw settings to use it. --- g2core/g2core.h | 4 +- g2core/kinematics.cpp | 62 ++++++++++++++++++++++++--- g2core/settings/settings_axidraw_v3.h | 8 ++-- g2core/settings/settings_default.h | 9 ++++ 4 files changed, 73 insertions(+), 10 deletions(-) diff --git a/g2core/g2core.h b/g2core/g2core.h index a575e29b9..d3b194689 100644 --- a/g2core/g2core.h +++ b/g2core/g2core.h @@ -69,7 +69,9 @@ typedef enum { AXIS_C, AXIS_U, // reserved AXIS_V, // reserved - AXIS_W // reserved + AXIS_W, // reserved + AXIS_COREXY_A = AXIS_X, // CoreXY uses A and B + AXIS_COREXY_B = AXIS_Y, } cmAxes; typedef enum { diff --git a/g2core/kinematics.cpp b/g2core/kinematics.cpp index db55679a1..05395b9dc 100755 --- a/g2core/kinematics.cpp +++ b/g2core/kinematics.cpp @@ -31,6 +31,7 @@ #include "stepper.h" #include "kinematics.h" #include "util.h" +#include "settings.h" static void _inverse_kinematics(const float travel[], float joint[]); @@ -113,11 +114,46 @@ void kn_inverse_kinematics(const float travel[], float steps[]) { * size or performance penalty for breaking this out */ static void _inverse_kinematics(const float travel[], float joint[]) { - memcpy(joint, travel, sizeof(float) * AXES); // just do a memcpy for Cartesian machines +#if KINEMATICS==KINE_CARTESIAN + joint[AXIS_X]=travel[AXIS_X]; + joint[AXIS_Y]=travel[AXIS_Y]; +#endif +#if KINEMATICS==KINE_CORE_XY + /* CoreXY Kinematics - http://corexy.com/ + deltaA=deltaX+deltaY + deltaB=deltaX-deltaY + + Note: Don't confuse axis A with CoreXY deltaA, they are different! + */ + joint[AXIS_COREXY_A]=travel[AXIS_X]+travel[AXIS_Y]; + joint[AXIS_COREXY_B]=travel[AXIS_X]-travel[AXIS_Y]; +#endif - // for (uint8_t i=0; i 2 + joint[3]=travel[3]; +#endif +#if AXES > 3 + joint[4]=travel[4]; +#endif +#if AXES > 4 + joint[5]=travel[5]; +#endif +#if AXES > 5 + joint[6]=travel[6]; +#endif +#if AXES > 6 + joint[7]=travel[7]; +#endif +#if AXES > 7 + joint[8]=travel[8]; +#endif +#if AXES > 8 + joint[9]=travel[9]; +#endif +#endif } /* @@ -152,11 +188,27 @@ void kn_forward_kinematics(const float steps[], float travel[]) { best_steps_per_unit[axis] = st_cfg.mot[motor].steps_per_unit; travel[axis] = steps[motor] * st_cfg.mot[motor].units_per_step; - // If a econd motor has the same reolution for the same axis, we'll average their values + // If a second motor has the same reolution for the same axis, we'll average their values } else if (fp_EQ(best_steps_per_unit[axis], st_cfg.mot[motor].steps_per_unit)) { travel[axis] = (travel[axis] + (steps[motor] * st_cfg.mot[motor].units_per_step)) / 2.0; } } } } + +#if KINEMATICS==KINE_CORE_XY + /* CoreXY Kinematics - http://corexy.com/ + deltaX=1/2(deltaA+deltaB) + deltaY=1/2(deltaA-deltaB) + + At this moment, travel[0] = deltaA, and travel[1] = deltaB. + We want travel[0] = deltaX, and travel[1] = deltaY. + */ + + float deltaA = travel[AXIS_COREXY_A]; + float deltaB = travel[AXIS_COREXY_B]; + + travel[AXIS_X] = 0.5 * (deltaA + deltaB); + travel[AXIS_Y] = 0.5 * (deltaA - deltaB); +#endif } diff --git a/g2core/settings/settings_axidraw_v3.h b/g2core/settings/settings_axidraw_v3.h index 18daeba20..a27c4b408 100755 --- a/g2core/settings/settings_axidraw_v3.h +++ b/g2core/settings/settings_axidraw_v3.h @@ -87,10 +87,10 @@ #define MOTOR_POWER_MODE MOTOR_POWERED_IN_CYCLE // default motor power mode (see cmMotorPowerMode in stepper.h) #define MOTOR_POWER_TIMEOUT 2.00 // motor power timeout in seconds -#define MOTOR_POWER_MODE MOTOR_POWERED_IN_CYCLE // default motor power mode (see cmMotorPowerMode in stepper.h) -#define MOTOR_POWER_TIMEOUT 2.00 // motor power timeout in seconds +#define KINEMATICS KINE_CORE_XY // X and Y MUST use the same settings! + -#define M1_MOTOR_MAP AXIS_Y // 1ma +#define M1_MOTOR_MAP AXIS_COREXY_A // 1ma #define M1_STEP_ANGLE 1.8 // 1sa // According to the EiBB settings here: // https://github.com/evil-mad/axidraw/blob/master/inkscape%20driver/axidraw_conf.py @@ -102,7 +102,7 @@ #define M1_POWER_MODE MOTOR_POWER_MODE // 1pm standard #define M1_POWER_LEVEL 0.4 -#define M2_MOTOR_MAP AXIS_X +#define M2_MOTOR_MAP AXIS_COREXY_B #define M2_STEP_ANGLE 1.8 #define M2_TRAVEL_PER_REV 40 #define M2_MICROSTEPS 32 diff --git a/g2core/settings/settings_default.h b/g2core/settings/settings_default.h index 37ad78484..e6aeebed9 100644 --- a/g2core/settings/settings_default.h +++ b/g2core/settings/settings_default.h @@ -198,6 +198,15 @@ //*** Motor Settings ********************************************************** //***************************************************************************** +// KINEMATICS (which may later change the following values) +#define KINE_CARTESIAN 0 +#define KINE_CORE_XY 1 + +#ifndef KINEMATICS +#define KINEMATICS KINE_CARTESIAN +#endif + + // MOTOR 1 #ifndef M1_MOTOR_MAP #define M1_MOTOR_MAP AXIS_X // {1ma: AXIS_X, AXIS_Y... From 5c97d8aa14a5c6146a5def004c12f0e046d86180 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Sat, 18 Feb 2017 09:00:52 -0600 Subject: [PATCH 015/193] Make MIN_SEGMENT_MS settable in the board hardware.h file --- g2core/board/gquadratic/hardware.h | 3 ++- g2core/planner.h | 7 +++++-- 2 files changed, 7 insertions(+), 3 deletions(-) diff --git a/g2core/board/gquadratic/hardware.h b/g2core/board/gquadratic/hardware.h index 265555ffc..166f24298 100644 --- a/g2core/board/gquadratic/hardware.h +++ b/g2core/board/gquadratic/hardware.h @@ -124,6 +124,8 @@ using Motate::OutputPin; #define FREQUENCY_DDA 150000UL // Hz step frequency. Interrupts actually fire at 2x (300 KHz) #define FREQUENCY_DWELL 1000UL +#define MIN_SEGMENT_MS ((float)0.125) // S70 can handle much much smaller segements + /**** Motate Definitions ****/ // Timer definitions. See stepper.h and other headers for setup @@ -132,7 +134,6 @@ typedef TimerChannel<10, 0> exec_timer_type; // request exec timer in step typedef TimerChannel<11, 0> fwd_plan_timer_type; // request exec timer in stepper.cpp // Pin assignments - pin_number indicator_led_pin_num = Motate::kLEDPWM_PinNumber; static OutputPin IndicatorLed; diff --git a/g2core/planner.h b/g2core/planner.h index 9a1da4164..d7562d922 100644 --- a/g2core/planner.h +++ b/g2core/planner.h @@ -150,6 +150,7 @@ #define PLANNER_H_ONCE #include "canonical_machine.h" // used for GCodeState_t +#include "hardware.h" // for MIN_SEGMENT_MS using Motate::Timeout; @@ -250,9 +251,11 @@ typedef enum { #define JUNCTION_INTEGRATION_MIN (0.05) // minimum allowable setting #define JUNCTION_INTEGRATION_MAX (5.00) // maximum allowable setting +#ifndef MIN_SEGMENT_MS #define MIN_SEGMENT_MS ((float)0.75) // minimum segment milliseconds -#define NOM_SEGMENT_MS ((float)1.5) // nominal segment ms (at LEAST MIN_SEGMENT_MS * 2) -#define MIN_BLOCK_MS ((float)1.5) // minimum block (whole move) milliseconds +#endif +#define NOM_SEGMENT_MS ((float)MIN_SEGMENT_MS*2.0) // nominal segment ms (at LEAST MIN_SEGMENT_MS * 2) +#define MIN_BLOCK_MS ((float)MIN_SEGMENT_MS*2.0) // minimum block (whole move) milliseconds #define BLOCK_TIMEOUT_MS ((float)30.0) // MS before deciding there are no new blocks arriving #define PHAT_CITY_MS ((float)100.0) // if you have at least this much time in the planner From 1905fe1238f774abf744f70e73ebeb0117121132 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Sat, 18 Feb 2017 09:01:37 -0600 Subject: [PATCH 016/193] Remove too-strict tests and extra commented-out code in stepper and exec. --- g2core/plan_exec.cpp | 5 ----- g2core/stepper.cpp | 48 +++++++++++++++++++------------------------- 2 files changed, 21 insertions(+), 32 deletions(-) diff --git a/g2core/plan_exec.cpp b/g2core/plan_exec.cpp index 3aab7b920..db6ca788a 100644 --- a/g2core/plan_exec.cpp +++ b/g2core/plan_exec.cpp @@ -272,11 +272,6 @@ stat_t mp_exec_move() } if (bf->buffer_state == MP_BUFFER_PREPPED) { - if (cm.motion_state == MOTION_RUN) { -#if IN_DEBUGGER == 1 - __asm__("BKPT"); // we are running but don't have a block planned -#endif - } // We need to have it planned. We don't want to do this here, as it // might already be happening in a lower interrupt. st_request_forward_plan(); diff --git a/g2core/stepper.cpp b/g2core/stepper.cpp index 0b1c8f8c6..5c2a6032c 100644 --- a/g2core/stepper.cpp +++ b/g2core/stepper.cpp @@ -76,7 +76,6 @@ extern OutputPin debug_pin3; //extern OutputPin debug_pin4; dda_timer_type dda_timer {kTimerUpToMatch, FREQUENCY_DDA}; // stepper pulse generation -//load_timer_type load_timer; // triggers load of next stepper segment exec_timer_type exec_timer; // triggers calculation of next+1 stepper segment fwd_plan_timer_type fwd_plan_timer; // triggers planning of next block @@ -125,15 +124,12 @@ void stepper_init() // If you need more pulse width you need to drop the DDA clock rate dda_timer.setInterrupts(kInterruptOnOverflow | kInterruptPriorityHighest); - // setup software interrupt load timer -// load_timer.setInterrupts(kInterruptOnSoftwareTrigger | kInterruptPriorityHigh); - // setup software interrupt exec timer & initial condition - exec_timer.setInterrupts(kInterruptOnSoftwareTrigger | kInterruptPriorityMedium); + exec_timer.setInterrupts(kInterruptOnSoftwareTrigger | kInterruptPriorityHigh); st_pre.buffer_state = PREP_BUFFER_OWNED_BY_EXEC; // setup software interrupt forward plan timer & initial condition - fwd_plan_timer.setInterrupts(kInterruptOnSoftwareTrigger | kInterruptPriorityLow); + fwd_plan_timer.setInterrupts(kInterruptOnSoftwareTrigger | kInterruptPriorityMedium); // setup motor power levels and apply power level to stepper drivers for (uint8_t motor=0; motor -// void load_timer_type::interrupt() -// { -// load_timer.getInterruptCause(); // read SR to clear interrupt condition -// stepper_debug("L>"); -// _load_move(); -// stepper_debug("L+\n"); -// } -//} // namespace Motate - /**************************************************************************************** * _load_move() - Dequeue move and load into stepper runtime structure * @@ -454,7 +439,16 @@ static void _load_move() return; // exit if the runtime is busy } if (st_pre.buffer_state != PREP_BUFFER_OWNED_BY_LOADER) { // if there are no moves to load... - + + if (cm.motion_state == MOTION_RUN) { +#if IN_DEBUGGER == 1 +//#warning debbugger REQUIRED for running this firmware! +// __asm__("BKPT"); // attempted to _load_move with PREP_BUFFER_OWNED_BY_EXEC and cm.motion_state == MOTION_RUN +#endif + st_request_exec_move(); + return; + } + // ...start motor power timeouts // for (uint8_t motor = MOTOR_1; motor < MOTORS; motor++) { // Motors[motor]->motionStopped(); @@ -675,8 +669,8 @@ stat_t st_prep_line(float travel_steps[], float following_error[], float segment return (cm_panic(STAT_PREP_LINE_MOVE_TIME_IS_INFINITE, "st_prep_line()")); } else if (isnan(segment_time)) { // never supposed to happen return (cm_panic(STAT_PREP_LINE_MOVE_TIME_IS_NAN, "st_prep_line()")); - } else if (segment_time < EPSILON) { - return (STAT_MINIMUM_TIME_MOVE); +// } else if (segment_time < EPSILON) { +// return (STAT_MINIMUM_TIME_MOVE); } // setup segment parameters // - dda_ticks is the integer number of DDA clock ticks needed to play out the segment @@ -803,7 +797,7 @@ static void _set_hw_microsteps(const uint8_t motor, const uint8_t microsteps) if (motor >= MOTORS) {return;} Motors[motor]->setMicrosteps(microsteps); - } +} /*********************************************************************************** From ca7c48965f5ae5af6a702128c67993db38ff17af Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Sat, 18 Feb 2017 09:02:56 -0600 Subject: [PATCH 017/193] New command: {prbs:true} store the current position as a probe point. MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Should be used when motion has stopped or in a M100, or you’ll get a probe stored for whatever position it’s currently at as it’s moving. --- g2core/canonical_machine.h | 3 +++ g2core/config_app.cpp | 1 + g2core/cycle_probing.cpp | 48 ++++++++++++++++++++++++++++++-------- 3 files changed, 42 insertions(+), 10 deletions(-) diff --git a/g2core/canonical_machine.h b/g2core/canonical_machine.h index e2c165d60..6e55d9b34 100644 --- a/g2core/canonical_machine.h +++ b/g2core/canonical_machine.h @@ -831,6 +831,9 @@ stat_t cm_set_jh(nvObj_t *nv); // set jerk high with 1,000,000 correcti stat_t cm_set_mfo(nvObj_t *nv); // set manual feedrate override factor stat_t cm_set_mto(nvObj_t *nv); // set manual traverse override factor +stat_t cm_set_probe(nvObj_t *nv); // store current position as the latest probe + + stat_t cm_set_tram(nvObj_t *nv); // attempt setting the rotation matrix stat_t cm_get_tram(nvObj_t *nv); // return if the rotation matrix is non-identity diff --git a/g2core/config_app.cpp b/g2core/config_app.cpp index 1014b6501..3b01028be 100644 --- a/g2core/config_app.cpp +++ b/g2core/config_app.cpp @@ -174,6 +174,7 @@ const cfgItem_t cfgArray[] = { { "prb","prba",_f0, 3, tx_print_nul, get_flt, set_ro, (float *)&cm.probe_results[0][AXIS_A], 0 }, { "prb","prbb",_f0, 3, tx_print_nul, get_flt, set_ro, (float *)&cm.probe_results[0][AXIS_B], 0 }, { "prb","prbc",_f0, 3, tx_print_nul, get_flt, set_ro, (float *)&cm.probe_results[0][AXIS_C], 0 }, + { "prb","prbs",_f0, 0, tx_print_nul, get_nul, cm_set_probe, (float *)&cs.null, 0 }, // store probe { "jog","jogx",_f0, 0, tx_print_nul, get_nul, cm_run_jogx, (float *)&cm.jogging_dest, 0}, { "jog","jogy",_f0, 0, tx_print_nul, get_nul, cm_run_jogy, (float *)&cm.jogging_dest, 0}, diff --git a/g2core/cycle_probing.cpp b/g2core/cycle_probing.cpp index 3bb194e85..70509fc40 100644 --- a/g2core/cycle_probing.cpp +++ b/g2core/cycle_probing.cpp @@ -74,6 +74,26 @@ static stat_t _probing_finalize_exit(); static stat_t _probing_error_exit(int8_t axis); static stat_t _probe_axis_move(const float target[], bool exact_position); static void _probe_axis_move_callback(float* vect, bool* flag); +void _prepare_for_probe(); +void _store_probe_position(); + +/**** JSON INTERFACE ******************************************************************* + * cm_set_probe() - a command to tell it to store the current point as a probe point + */ + +stat_t cm_set_probe(nvObj_t *nv) +{ + if (!fp_ZERO(nv->value)) { + nv->valuetype = TYPE_BOOL; + nv->value = true; + + _prepare_for_probe(); + cm.probe_state[0] = PROBE_SUCCEEDED; + _store_probe_position(); + } + return (STAT_OK); +} + /**** HELPERS *************************************************************************** * _set_pb_func() - a convenience for setting the next dispatch vector and exiting @@ -84,6 +104,22 @@ static stat_t _set_pb_func(uint8_t (*func)()) { return (STAT_EAGAIN); } +void _prepare_for_probe() { + // if the previous probe succeeded, roll probes to the next position + if (cm.probe_state[0] == PROBE_SUCCEEDED) { + for (uint8_t n = PROBES_STORED - 1; n > 0; n--) { + cm.probe_state[n] = cm.probe_state[n - 1]; + for (uint8_t axis = 0; axis < AXES; axis++) { cm.probe_results[n][axis] = cm.probe_results[n - 1][axis]; } + } + } +} + +void _store_probe_position() { + for (uint8_t axis = 0; axis < AXES; axis++) { + cm.probe_results[0][axis] = cm_get_absolute_position(ACTIVE_MODEL, axis); + } +} + /*********************************************************************************** **** G38.x Probing Cycle *********************************************************** ***********************************************************************************/ @@ -155,13 +191,7 @@ uint8_t cm_straight_probe(float target[], bool flags[], bool failure_is_fatal, b copy_vector(pb.target, target); // set probe move endpoint copy_vector(pb.flags, flags); // set axes involved on the move - // if the previous probe succeeded, roll probes to the next position - if (cm.probe_state[0] == PROBE_SUCCEEDED) { - for (uint8_t n = PROBES_STORED - 1; n > 0; n--) { - cm.probe_state[n] = cm.probe_state[n - 1]; - for (uint8_t axis = 0; axis < AXES; axis++) { cm.probe_results[n][axis] = cm.probe_results[n - 1][axis]; } - } - } + _prepare_for_probe(); // clear the old probe position clear_vector(cm.probe_results[0]); @@ -349,9 +379,7 @@ static void _probe_axis_move_callback(float* vect, bool* flag) { pb.waiting_for_ */ static stat_t _probing_finish() { - for (uint8_t axis = 0; axis < AXES; axis++) { - cm.probe_results[0][axis] = cm_get_absolute_position(ACTIVE_MODEL, axis); - } + _store_probe_position(); // If probe was successful the 'e' word == 1, otherwise e == 0 to signal an error char buf[32]; From a5466bf9a007adc235a487075ce3631ec492a01f Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Sat, 18 Feb 2017 09:03:09 -0600 Subject: [PATCH 018/193] Tweak AxiDrawv3 settings. --- g2core/settings/settings_axidraw_v3.h | 26 +++++++++++--------------- 1 file changed, 11 insertions(+), 15 deletions(-) diff --git a/g2core/settings/settings_axidraw_v3.h b/g2core/settings/settings_axidraw_v3.h index a27c4b408..3d9acbfca 100755 --- a/g2core/settings/settings_axidraw_v3.h +++ b/g2core/settings/settings_axidraw_v3.h @@ -33,7 +33,7 @@ // ***> NOTE: The init message must be a single line with no CRs or LFs #define INIT_MESSAGE "Initializing configs to WaterColorBot v2 settings" -#define JUNCTION_INTEGRATION_TIME 1.50 // cornering - usually between 0.5 and 2.0 (higher is faster) +#define JUNCTION_INTEGRATION_TIME 2.5 // cornering - usually between 0.5 and 2.0 (higher is faster) #define CHORDAL_TOLERANCE 0.01 // chordal accuracy for arc drawing (in mm) #define SOFT_LIMIT_ENABLE 0 // 0=off, 1=on @@ -92,23 +92,19 @@ #define M1_MOTOR_MAP AXIS_COREXY_A // 1ma #define M1_STEP_ANGLE 1.8 // 1sa -// According to the EiBB settings here: -// https://github.com/evil-mad/axidraw/blob/master/inkscape%20driver/axidraw_conf.py -// At 16x microstepping, it's 2032 steps per INCH, which is ((16/2032)*25.4) = 0.2mm per FULL step -// With a 200 step/revolution (1.8º/step) motor, that's 0.2*200=40mm per revolution #define M1_TRAVEL_PER_REV 40 // 1tr #define M1_MICROSTEPS 32 // 1mi 1,2,4,8 #define M1_POLARITY 0 // 1po 0=normal, 1=reversed #define M1_POWER_MODE MOTOR_POWER_MODE // 1pm standard -#define M1_POWER_LEVEL 0.4 +#define M1_POWER_LEVEL 0.6 #define M2_MOTOR_MAP AXIS_COREXY_B #define M2_STEP_ANGLE 1.8 #define M2_TRAVEL_PER_REV 40 #define M2_MICROSTEPS 32 -#define M2_POLARITY 1 +#define M2_POLARITY 0 #define M2_POWER_MODE MOTOR_POWER_MODE -#define M2_POWER_LEVEL 0.4 +#define M2_POWER_LEVEL 0.6 #define M3_MOTOR_MAP AXIS_Z // This "stepper" is a hobby servo. Note that all hobby @@ -125,11 +121,11 @@ // *** axis settings ********************************************************************************** -#define JERK_MAX 20000 +#define JERK_MAX 2000 #define X_AXIS_MODE AXIS_STANDARD // xam see canonical_machine.h cmAxisMode for valid values -#define X_VELOCITY_MAX 50000 // xvm G0 max velocity in mm/min -#define X_FEEDRATE_MAX X_VELOCITY_MAX // xfr G1 max feed rate in mm/min +#define X_VELOCITY_MAX 10000 // xvm G0 max velocity in mm/min +#define X_FEEDRATE_MAX 10000 // xfr G1 max feed rate in mm/min #define X_TRAVEL_MIN 0 // xtn minimum travel - used by soft limits and homing #define X_TRAVEL_MAX 400 // xtm maximum travel - used by soft limits and homing #define X_JERK_MAX JERK_MAX // xjm @@ -142,8 +138,8 @@ #define X_ZERO_BACKOFF 2 // xzb mm #define Y_AXIS_MODE AXIS_STANDARD -#define Y_VELOCITY_MAX 50000 -#define Y_FEEDRATE_MAX Y_VELOCITY_MAX +#define Y_VELOCITY_MAX 10000 +#define Y_FEEDRATE_MAX 10000 #define Y_TRAVEL_MIN 0 #define Y_TRAVEL_MAX 175 #define Y_JERK_MAX JERK_MAX @@ -156,11 +152,11 @@ #define Y_ZERO_BACKOFF 2 #define Z_AXIS_MODE AXIS_STANDARD -#define Z_VELOCITY_MAX 15000 +#define Z_VELOCITY_MAX 10000 #define Z_FEEDRATE_MAX Z_VELOCITY_MAX #define Z_TRAVEL_MIN 0 #define Z_TRAVEL_MAX 75 -#define Z_JERK_MAX 5000 +#define Z_JERK_MAX 1000 #define Z_JERK_HIGH_SPEED Z_JERK_MAX #define Z_HOMING_INPUT 6 #define Z_HOMING_DIRECTION 1 From e811666631660bdb46ed289c56075f1a133c7581 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Sat, 18 Feb 2017 09:03:25 -0600 Subject: [PATCH 019/193] Update motate reference for minor S70 USB adjustment. --- Motate | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Motate b/Motate index db22af8c3..ef6d51f68 160000 --- a/Motate +++ b/Motate @@ -1 +1 @@ -Subproject commit db22af8c3cd5af5d11cb97c70fece51259dc9f38 +Subproject commit ef6d51f6808940817ad76c51189efd3b5761de54 From 2d3e916c5a0a426e5a6c529246a448cb73a3ec29 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Wed, 22 Feb 2017 10:02:13 -0600 Subject: [PATCH 020/193] Cleanup for DEBUG=0 --- g2core/Makefile | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/g2core/Makefile b/g2core/Makefile index fa453acbf..cf8777f8f 100755 --- a/g2core/Makefile +++ b/g2core/Makefile @@ -52,8 +52,11 @@ NEEDS_PRINTF_FLOAT=1 # Now invoke the Motate compile system include $(MOTATE_PATH)/Motate.mk +ifeq ($(DEBUG),0) + DEVICE_DEFINES += DEBUG=0 IN_DEBUGGER=0 +endif ifeq ($(DEBUG),1) - DEVICE_DEFINES += DEBUG=1 + DEVICE_DEFINES += DEBUG=1 IN_DEBUGGER=0 endif ifeq ($(DEBUG),2) DEVICE_DEFINES += DEBUG=1 IN_DEBUGGER=1 From cb651382c2409ba3e01258044f9768d003a48586 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Wed, 22 Feb 2017 10:30:13 -0600 Subject: [PATCH 021/193] Cleanup gQuintic. Added 6th motor, a hobby servo (motor 6) on OUT_7. --- g2core/board/gquadratic/hardware.h | 2 +- g2core/board/gquintic.mk | 5 +++-- g2core/board/gquintic/board_stepper.cpp | 4 +++- g2core/board/gquintic/board_stepper.h | 2 ++ g2core/board/gquintic/gquintic-b-pinout.h | 6 ++++-- g2core/board/gquintic/hardware.h | 8 +++++--- g2core/board/gquintic/motate_pin_assignments.h | 11 ++++++++--- .../device/step_dir_hobbyservo/step_dir_hobbyservo.h | 6 +++--- 8 files changed, 29 insertions(+), 15 deletions(-) diff --git a/g2core/board/gquadratic/hardware.h b/g2core/board/gquadratic/hardware.h index 166f24298..9c3b27504 100644 --- a/g2core/board/gquadratic/hardware.h +++ b/g2core/board/gquadratic/hardware.h @@ -121,7 +121,7 @@ using Motate::OutputPin; /**** Stepper DDA and dwell timer settings ****/ //#define FREQUENCY_DDA 200000UL // Hz step frequency. Interrupts actually fire at 2x (400 KHz) -#define FREQUENCY_DDA 150000UL // Hz step frequency. Interrupts actually fire at 2x (300 KHz) +#define FREQUENCY_DDA 200000UL // Hz step frequency. Interrupts actually fire at 2x (300 KHz) #define FREQUENCY_DWELL 1000UL #define MIN_SEGMENT_MS ((float)0.125) // S70 can handle much much smaller segements diff --git a/g2core/board/gquintic.mk b/g2core/board/gquintic.mk index ab60f6cb0..7f267ed8a 100755 --- a/g2core/board/gquintic.mk +++ b/g2core/board/gquintic.mk @@ -16,6 +16,7 @@ ifeq ("$(BOARD)","gquintic-b") BASE_BOARD=gquintic DEVICE_DEFINES += MOTATE_BOARD="gquintic-b" DEVICE_DEFINES += SETTINGS_FILE=${SETTINGS_FILE} + DEVICE_DEFINES += SERVO_MOTOR=6 endif @@ -26,7 +27,7 @@ endif ifeq ("$(BASE_BOARD)","gquintic") _BOARD_FOUND = 1 - DEVICE_DEFINES += MOTATE_CONFIG_HAS_USBSERIAL=1 + DEVICE_DEFINES += MOTATE_CONFIG_HAS_USBSERIAL=1 ENABLE_TCM=1 FIRST_LINK_SOURCES += $(sort $(wildcard ${MOTATE_PATH}/Atmel_sam_common/*.cpp)) $(sort $(wildcard ${MOTATE_PATH}/Atmel_sams70/*.cpp)) @@ -35,7 +36,7 @@ ifeq ("$(BASE_BOARD)","gquintic") CHIP_LOWERCASE = sams70n19 BOARD_PATH = ./board/gquintic - SOURCE_DIRS += ${BOARD_PATH} device/trinamic + SOURCE_DIRS += ${BOARD_PATH} device/trinamic device/step_dir_hobbyservo PLATFORM_BASE = ${MOTATE_PATH}/platform/atmel_sam include $(PLATFORM_BASE).mk diff --git a/g2core/board/gquintic/board_stepper.cpp b/g2core/board/gquintic/board_stepper.cpp index 8168f5380..cc58f61dc 100755 --- a/g2core/board/gquintic/board_stepper.cpp +++ b/g2core/board/gquintic/board_stepper.cpp @@ -63,7 +63,9 @@ Trinamic2130 motor_5{spiBus, spiCSPinMux.getCS(0)}; -Stepper* Motors[MOTORS] = {&motor_1, &motor_2, &motor_3, &motor_4, &motor_5}; +StepDirHobbyServo motor_6; + +Stepper* Motors[MOTORS] = {&motor_1, &motor_2, &motor_3, &motor_4, &motor_5, &motor_6}; void board_stepper_init() { spiBus.init(); diff --git a/g2core/board/gquintic/board_stepper.h b/g2core/board/gquintic/board_stepper.h index 23b8c4dbf..c2cf6ebe1 100755 --- a/g2core/board/gquintic/board_stepper.h +++ b/g2core/board/gquintic/board_stepper.h @@ -30,6 +30,7 @@ #include "hardware.h" // for MOTORS #include "tmc2130.h" +#include "step_dir_hobbyservo.h" typedef Motate::SPIBus SPIBus_used_t; @@ -59,6 +60,7 @@ extern Trinamic2130 motor_5; +extern StepDirHobbyServo motor_6; extern Stepper* Motors[MOTORS]; diff --git a/g2core/board/gquintic/gquintic-b-pinout.h b/g2core/board/gquintic/gquintic-b-pinout.h index 75d7c52ec..520f7806b 100755 --- a/g2core/board/gquintic/gquintic-b-pinout.h +++ b/g2core/board/gquintic/gquintic-b-pinout.h @@ -130,7 +130,8 @@ _MAKE_MOTATE_PIN(kI2C1_SDAPinNumber, 'A', 3); // _MAKE_MOTATE_PIN(kI2C1_SCLPinNumber, 'A', 4); // _MAKE_MOTATE_PIN(kOutput11_PinNumber, 'A', 5); // _MAKE_MOTATE_PIN(kExternalClock1_PinNumber, 'A', 6); // CPU_CLK -_MAKE_MOTATE_PIN(kOutput7_PinNumber, 'A', 7); // +//_MAKE_MOTATE_PIN(kOutput7_PinNumber, 'A', 7); // +_MAKE_MOTATE_PIN(kServo1_PinNumber, 'A', 7); // _MAKE_MOTATE_PIN(kSerial_RTSPinNumber, 'A', 8); // _MAKE_MOTATE_PIN(kSerial_RXPinNumber, 'A', 9); // _MAKE_MOTATE_PIN(kSerial_TXPinNumber, 'A', 10); // @@ -146,7 +147,8 @@ _MAKE_MOTATE_PIN(kADC1_PinNumber, 'A', 19); // _MAKE_MOTATE_PIN(kADC0_PinNumber, 'A', 20); // _MAKE_MOTATE_PIN(kSerial_CTSPinNumber, 'A', 21); // _MAKE_MOTATE_PIN(kSocket1_EnablePinNumber, 'A', 22); // -_MAKE_MOTATE_PIN(kOutput10_PinNumber, 'A', 23); // +//_MAKE_MOTATE_PIN(kOutput10_PinNumber, 'A', 23); // +_MAKE_MOTATE_PIN(kServo1_PinNumber, 'A', 23); // _MAKE_MOTATE_PIN(kSocket3_EnablePinNumber, 'A', 24); // _MAKE_MOTATE_PIN(kSocket2_DirPinNumber, 'A', 25); // _MAKE_MOTATE_PIN(kOutput5_PinNumber, 'A', 26); // On Timer 2! diff --git a/g2core/board/gquintic/hardware.h b/g2core/board/gquintic/hardware.h index 42a789eb3..41d3215d3 100644 --- a/g2core/board/gquintic/hardware.h +++ b/g2core/board/gquintic/hardware.h @@ -58,7 +58,7 @@ enum hwPlatform { #define AXES 6 // number of axes supported in this version #define HOMING_AXES 4 // number of axes that can be homed (assumes Zxyabc sequence) -#define MOTORS 5 // number of motors on the board +#define MOTORS 6 // number of motors on the board - 5 Trinamics + 1 servo #define COORDS 6 // number of supported coordinate systems (index starts at 1) #define PWMS 2 // number of supported PWM channels #define TOOLS 32 // number of entries in tool table (index starts at 1) @@ -120,8 +120,10 @@ using Motate::OutputPin; /**** Stepper DDA and dwell timer settings ****/ //#define FREQUENCY_DDA 200000UL // Hz step frequency. Interrupts actually fire at 2x (400 KHz) -#define FREQUENCY_DDA 300000UL // Hz step frequency. Interrupts actually fire at 2x (300 KHz) -#define FREQUENCY_DWELL 1000UL +#define FREQUENCY_DDA 200000UL // Hz step frequency. Interrupts actually fire at 2x (300 KHz) +#define FREQUENCY_DWELL 1000UL + +#define MIN_SEGMENT_MS ((float)0.125) // S70 can handle much much smaller segements /**** Motate Definitions ****/ diff --git a/g2core/board/gquintic/motate_pin_assignments.h b/g2core/board/gquintic/motate_pin_assignments.h index af029d317..2a93633aa 100755 --- a/g2core/board/gquintic/motate_pin_assignments.h +++ b/g2core/board/gquintic/motate_pin_assignments.h @@ -176,6 +176,7 @@ pin_number kGRBL_FeedHoldPinNumber = -1; pin_number kGRBL_CycleStartPinNumber = -1; pin_number kGRBL_CommonEnablePinNumber = -1; + // g2ref extensions // These first 5 may replace the Spindle and Coolant pins, above pin_number kOutput1_PinNumber = 130; // DO_1: Extruder1_PWM @@ -187,8 +188,8 @@ pin_number kOutput5_PinNumber = 134; // DO_5: Fan2A_PWM pin_number kOutput6_PinNumber = 135; // See Spindle Enable pin_number kOutput7_PinNumber = 136; // See Spindle Direction pin_number kOutput8_PinNumber = 137; // See Coolant Enable -pin_number kOutput9_PinNumber = 138; // SAFE signal -pin_number kOutput10_PinNumber = 139; // DO_10: Fan2B_PWM +pin_number kOutput9_PinNumber = 138; // DO_09: May be resued for Servo1 +pin_number kOutput10_PinNumber = 139; // DO_10: May be resued for Servo2 pin_number kOutput11_PinNumber = 140; // DO_11: Heated Bed FET pin_number kOutput12_PinNumber = 141; // DO_12: Indicator_LED @@ -215,8 +216,12 @@ pin_number kADC14_PinNumber = 164; // Not physically pinned out pin_number kExternalClock1_PinNumber = 170; // External pins for exporting a clock signal (for Trinamics) +pin_number kServo1_PinNumber = 171; // +pin_number kServo2_PinNumber = 172; // +pin_number kServo3_PinNumber = 173; // -// start next sequence at 171 + +// start next sequence at 174 // blank spots for unassigned pins - all unassigned pins need a unique number (do not re-use numbers) diff --git a/g2core/device/step_dir_hobbyservo/step_dir_hobbyservo.h b/g2core/device/step_dir_hobbyservo/step_dir_hobbyservo.h index d631b5586..cfef808f4 100644 --- a/g2core/device/step_dir_hobbyservo/step_dir_hobbyservo.h +++ b/g2core/device/step_dir_hobbyservo/step_dir_hobbyservo.h @@ -48,7 +48,7 @@ struct StepDirHobbyServo final : Stepper { int16_t _microsteps_per_step = 1; bool _step_is_forward = false; - int32_t _position = 0; // in steps from 0 - 6400 for a full "rotation" + int32_t _position = 0; // in steps from 0 - 6400 for a full "rotation" int32_t _position_computed = 0; // in steps from 0 - 6400 for a full "rotation" float _min_value; float _max_value; @@ -62,8 +62,8 @@ struct StepDirHobbyServo final : Stepper { _pwm_pin.setFrequency(frequency); // redundant due to a bug uint16_t _top_value = _pwm_pin.getTopValue(); float frequency_inv = 1.0/(float)frequency; - _min_value = (float)_top_value / ((frequency_inv)/(750.0/1000000.0)); - _max_value = (float)_top_value / ((frequency_inv)/(2000.0/1000000.0)); + _min_value = (float)floor(_top_value / ((frequency_inv)/(750.0/1000000.0))); + _max_value = (float)ceil(_top_value / ((frequency_inv)/(2000.0/1000000.0))); _value_range = _max_value - _min_value; _position_computed = _min_value; check_timer.set(1); From fdf663f84f2aabf3b85f4889522694386183f2de Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Wed, 22 Feb 2017 10:30:36 -0600 Subject: [PATCH 022/193] Updated AxiDrawv3 settings to support the gQuintic or gQuadratic. --- g2core/settings/settings_axidraw_v3.h | 46 +++++++++++++++++++++------ 1 file changed, 36 insertions(+), 10 deletions(-) diff --git a/g2core/settings/settings_axidraw_v3.h b/g2core/settings/settings_axidraw_v3.h index 3d9acbfca..0e78157c6 100755 --- a/g2core/settings/settings_axidraw_v3.h +++ b/g2core/settings/settings_axidraw_v3.h @@ -89,23 +89,36 @@ #define KINEMATICS KINE_CORE_XY // X and Y MUST use the same settings! +#if MOTORS == 3 +// gQuadratic +#define A_B_POWER_LEVEL 0.4 +#define A_B_MICROSTEPS 32 +#define JERK_MAX 2000 +#endif +#if MOTORS == 6 +// gQuintic +#define A_B_POWER_LEVEL 0.7 +#define A_B_MICROSTEPS 64 +#define JERK_MAX 3000 +#endif #define M1_MOTOR_MAP AXIS_COREXY_A // 1ma #define M1_STEP_ANGLE 1.8 // 1sa #define M1_TRAVEL_PER_REV 40 // 1tr -#define M1_MICROSTEPS 32 // 1mi 1,2,4,8 +#define M1_MICROSTEPS A_B_MICROSTEPS // 1mi 1,2,4,8 #define M1_POLARITY 0 // 1po 0=normal, 1=reversed #define M1_POWER_MODE MOTOR_POWER_MODE // 1pm standard -#define M1_POWER_LEVEL 0.6 +#define M1_POWER_LEVEL A_B_POWER_LEVEL #define M2_MOTOR_MAP AXIS_COREXY_B #define M2_STEP_ANGLE 1.8 #define M2_TRAVEL_PER_REV 40 -#define M2_MICROSTEPS 32 +#define M2_MICROSTEPS A_B_MICROSTEPS #define M2_POLARITY 0 #define M2_POWER_MODE MOTOR_POWER_MODE -#define M2_POWER_LEVEL 0.6 +#define M2_POWER_LEVEL A_B_POWER_LEVEL +#if MOTORS == 3 #define M3_MOTOR_MAP AXIS_Z // This "stepper" is a hobby servo. Note that all hobby // servo settings are per full servo range, instead of @@ -117,15 +130,28 @@ #define M3_POLARITY 1 #define M3_POWER_MODE MOTOR_ALWAYS_POWERED #define M3_POWER_LEVEL 0.50 // this is ignored - +#endif + +#if MOTORS == 6 +#define M6_MOTOR_MAP AXIS_Z +// This "stepper" is a hobby servo. Note that all hobby +// servo settings are per full servo range, instead of +// per revolution. +#define M6_STEP_ANGLE 1.8 // hobby servos are simulated with 200 "full steps" +#define M6_TRAVEL_PER_REV 26 // this is actually the full travel of the servo, not +// necessarily covering a revolution +#define M6_MICROSTEPS 32 // the max step resolution for a hobby servo is 1/32 +#define M6_POLARITY 1 +#define M6_POWER_MODE MOTOR_ALWAYS_POWERED +#define M6_POWER_LEVEL 0.50 // this is ignored +#endif // *** axis settings ********************************************************************************** -#define JERK_MAX 2000 #define X_AXIS_MODE AXIS_STANDARD // xam see canonical_machine.h cmAxisMode for valid values -#define X_VELOCITY_MAX 10000 // xvm G0 max velocity in mm/min -#define X_FEEDRATE_MAX 10000 // xfr G1 max feed rate in mm/min +#define X_VELOCITY_MAX 15000 // xvm G0 max velocity in mm/min +#define X_FEEDRATE_MAX 15000 // xfr G1 max feed rate in mm/min #define X_TRAVEL_MIN 0 // xtn minimum travel - used by soft limits and homing #define X_TRAVEL_MAX 400 // xtm maximum travel - used by soft limits and homing #define X_JERK_MAX JERK_MAX // xjm @@ -138,8 +164,8 @@ #define X_ZERO_BACKOFF 2 // xzb mm #define Y_AXIS_MODE AXIS_STANDARD -#define Y_VELOCITY_MAX 10000 -#define Y_FEEDRATE_MAX 10000 +#define Y_VELOCITY_MAX 15000 +#define Y_FEEDRATE_MAX 15000 #define Y_TRAVEL_MIN 0 #define Y_TRAVEL_MAX 175 #define Y_JERK_MAX JERK_MAX From a22158f9ddf3de2b607ddc40199ef187eb7451dd Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Wed, 22 Feb 2017 11:13:02 -0600 Subject: [PATCH 023/193] =?UTF-8?q?Removing=20all=20references=20to=20SysT?= =?UTF-8?q?ickTimer=5FgetValue()=20=E2=80=A6=20again.?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Most of these should be moved to Motate::Timouts. Add to the TODO… --- g2core/canonical_machine.cpp | 2 +- g2core/controller.cpp | 4 ++-- g2core/main.cpp | 2 +- g2core/report.cpp | 8 ++++---- g2core/util.cpp | 16 ++++++++-------- 5 files changed, 16 insertions(+), 16 deletions(-) diff --git a/g2core/canonical_machine.cpp b/g2core/canonical_machine.cpp index ad1c132ca..7289a851b 100644 --- a/g2core/canonical_machine.cpp +++ b/g2core/canonical_machine.cpp @@ -738,7 +738,7 @@ void canonical_machine_reset() cm.cycle_state = CYCLE_OFF; cm.motion_state = MOTION_STOP; cm.hold_state = FEEDHOLD_OFF; - cm.esc_boot_timer = SysTickTimer_getValue(); + cm.esc_boot_timer = SysTickTimer.getValue(); cm.gmx.block_delete_switch = true; cm.gm.motion_mode = MOTION_MODE_CANCEL_MOTION_MODE; // never start in a motion mode cm.machine_state = MACHINE_READY; diff --git a/g2core/controller.cpp b/g2core/controller.cpp index 70fb3378d..55174dcf7 100755 --- a/g2core/controller.cpp +++ b/g2core/controller.cpp @@ -359,8 +359,8 @@ static stat_t _led_indicator() cs.led_blink_rate = blink_rate; cs.led_timer = 0; } - if (SysTickTimer_getValue() > cs.led_timer) { - cs.led_timer = SysTickTimer_getValue() + cs.led_blink_rate; + if (SysTickTimer.getValue() > cs.led_timer) { + cs.led_timer = SysTickTimer.getValue() + cs.led_blink_rate; IndicatorLed.toggle(); } return (STAT_OK); diff --git a/g2core/main.cpp b/g2core/main.cpp index 625d38e5c..f4e4af321 100644 --- a/g2core/main.cpp +++ b/g2core/main.cpp @@ -140,7 +140,7 @@ void setup(void) { // application setup application_init_services(); - while (SysTickTimer_getValue() < 400); // delay 400 ms for USB to come up + while (SysTickTimer.getValue() < 400); // delay 400 ms for USB to come up application_init_machine(); application_init_startup(); diff --git a/g2core/report.cpp b/g2core/report.cpp index 829545e66..38c7696ce 100644 --- a/g2core/report.cpp +++ b/g2core/report.cpp @@ -257,7 +257,7 @@ stat_t sr_request_status_report(cmStatusReportRequest request_type) return (STAT_OK); } - sr.status_report_systick = SysTickTimer_getValue(); + sr.status_report_systick = SysTickTimer.getValue(); if (request_type == SR_REQUEST_IMMEDIATE) { sr.status_report_request = SR_FILTERED; // will trigger a filtered or verbose report depending on verbosity setting @@ -283,7 +283,7 @@ stat_t sr_status_report_callback() // called by controller dispatcher // conditions where autogenerated SRs will not be returned if ((sr.status_report_request == SR_OFF) || (sr.status_report_verbosity == SR_OFF) || - (SysTickTimer_getValue() < sr.status_report_systick) ) { + (SysTickTimer.getValue() < sr.status_report_systick) ) { return (STAT_NOOP); } @@ -479,7 +479,7 @@ void qr_init_queue_report() qr.queue_report_requested = false; qr.buffers_added = 0; qr.buffers_removed = 0; - qr.init_tick = SysTickTimer_getValue(); // Uses C mapping of SysTickTimer.getValue(); + qr.init_tick = SysTickTimer.getValue(); // Uses C mapping of SysTickTimer.getValue(); } /* @@ -503,7 +503,7 @@ void qr_request_queue_report(int8_t buffers) // qr.motion_mode = cm_get_motion_mode(ACTIVE_MODEL); qr.motion_mode = cm_get_motion_mode((GCodeState_t *)&cm.gm); if ((qr.motion_mode == MOTION_MODE_CW_ARC) || (qr.motion_mode == MOTION_MODE_CCW_ARC)) { - uint32_t tick = SysTickTimer_getValue(); + uint32_t tick = SysTickTimer.getValue(); if (tick - qr.init_tick < MIN_ARC_QR_INTERVAL) { qr.queue_report_requested = false; return; diff --git a/g2core/util.cpp b/g2core/util.cpp index 53608493c..b75ed64b2 100644 --- a/g2core/util.cpp +++ b/g2core/util.cpp @@ -243,14 +243,14 @@ uint16_t compute_checksum(char const *string, const uint16_t length) return (h % HASHMASK); } -/* - * SysTickTimer_getValue() - this is a hack to get around some compatibility problems - */ - -uint32_t SysTickTimer_getValue() -{ - return (SysTickTimer.getValue()); -} +///* +// * SysTickTimer_getValue() - this is a hack to get around some compatibility problems +// */ +// +//uint32_t SysTickTimer_getValue() +//{ +// return (SysTickTimer.getValue()); +//} /*********************************************** **** Very Fast Number to ASCII Conversions **** From a8a5ab50232b9d636947c237669f7f31fb609fb3 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Wed, 22 Feb 2017 11:13:54 -0600 Subject: [PATCH 024/193] Fix for crash with an FPU: converting a float to a int32, then storing it as a int16. --- g2core/config.h | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/g2core/config.h b/g2core/config.h index 7f65852ae..e303db09f 100644 --- a/g2core/config.h +++ b/g2core/config.h @@ -170,7 +170,8 @@ // Sizing and footprints // chose one based on # of elements in cfgArray //typedef uint8_t index_t; // use this if there are < 256 indexed objects -typedef uint16_t index_t; // use this if there are > 255 indexed objects +//typedef uint16_t index_t; // use this if there are > 255 indexed objects +typedef uint32_t index_t; // use this because set/get_int is expecting an int32_t // defines allocated from stack (not-pre-allocated) #define NV_FORMAT_LEN 128 // print formatting string max length From b810a01af8fa77667652ba3e1b548b40bd9c7f8f Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Wed, 22 Feb 2017 11:14:27 -0600 Subject: [PATCH 025/193] Removed SysTickTimer_getValue() for real this time. --- g2core/util.cpp | 9 --------- 1 file changed, 9 deletions(-) diff --git a/g2core/util.cpp b/g2core/util.cpp index b75ed64b2..fe4b56bd7 100644 --- a/g2core/util.cpp +++ b/g2core/util.cpp @@ -243,15 +243,6 @@ uint16_t compute_checksum(char const *string, const uint16_t length) return (h % HASHMASK); } -///* -// * SysTickTimer_getValue() - this is a hack to get around some compatibility problems -// */ -// -//uint32_t SysTickTimer_getValue() -//{ -// return (SysTickTimer.getValue()); -//} - /*********************************************** **** Very Fast Number to ASCII Conversions **** ***********************************************/ From 0806ab6e138c466b5158949f047cac9bec768982 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Wed, 22 Feb 2017 12:38:32 -0600 Subject: [PATCH 026/193] Update Motate reference to get new SAMS&0 changes and new compiler. Also now supports JLink/ICE interchangeably (OSX/Linux). --- Motate | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Motate b/Motate index ef6d51f68..31af41606 160000 --- a/Motate +++ b/Motate @@ -1 +1 @@ -Subproject commit ef6d51f6808940817ad76c51189efd3b5761de54 +Subproject commit 31af41606478cd0ace341f3ea08bc8f5a5adbc54 From d5c131b87094581944ec0aa09d73ecea471ca888 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Wed, 22 Feb 2017 12:39:24 -0600 Subject: [PATCH 027/193] GDB file changes for ICE/Jlink independence. --- g2core/board/g2_default.gdb | 7 +++++-- g2core/board/gquadratic.gdb | 39 +++++++++++++++++++++++++++++++++---- g2core/board/gquintic.gdb | 39 +++++++++++++++++++++++++++++++++---- 3 files changed, 75 insertions(+), 10 deletions(-) diff --git a/g2core/board/g2_default.gdb b/g2core/board/g2_default.gdb index dc505ef19..f7e7e2282 100644 --- a/g2core/board/g2_default.gdb +++ b/g2core/board/g2_default.gdb @@ -8,11 +8,14 @@ set history expansion on set print pretty on -monitor adapter_khz 5000 +# monitor adapter_khz 5000 define reset boot_from_flash - monitor reset init + # for openocd + # monitor reset init + # for jlink + monitor reset end define flash diff --git a/g2core/board/gquadratic.gdb b/g2core/board/gquadratic.gdb index bd2e88282..2619f7e4a 100644 --- a/g2core/board/gquadratic.gdb +++ b/g2core/board/gquadratic.gdb @@ -1,12 +1,43 @@ # Open and connect to openocd with the ATMEL-ICE -target remote | /usr/local/bin/openocd -c "set CHIPNAME ${CHIP}" -f ${MOTATE_PATH}/openocd.cfg -f ${MOTATE_PATH}/platform/atmel_sam/atmel_sam.cfg -c "gdb_port pipe; log_output openocd.log" +#target remote | /usr/local/bin/openocd -c "set CHIPNAME ${CHIP}" -f ${MOTATE_PATH}/openocd.cfg -f ${MOTATE_PATH}/platform/atmel_sam/atmel_sam.cfg -c "gdb_port pipe; log_output openocd.log" -monitor arm semihosting enable +target extended-remote :2331 -source ./board/g2_default.gdb +# Setup for non-wrapped lines and non-pages prints +set width 0 +set height 0 + +# Turn on history saving +set history save on +set history expansion on + +set print pretty on + +define reset_deep + monitor reset + + # Reset peripheral (RSTC_CR) + set *0x400E1800 = 0xA5000004 + +# # Initializing PC and stack pointer +# mon reg sp = (0x20400000) +# set *0x20400004 = *0x20400004 & 0xFFFFFFFE +# mon reg pc=(0x20400004) + info reg +end + +define flash + make + load + reset +end + +define dump_mb + source ../Resources/debug/mb.gdb +end define boot_from_flash - monitor atsamv gpnvm set 1 + #monitor atsamv gpnvm set 1 end source -s arm.gdb diff --git a/g2core/board/gquintic.gdb b/g2core/board/gquintic.gdb index bd2e88282..2619f7e4a 100644 --- a/g2core/board/gquintic.gdb +++ b/g2core/board/gquintic.gdb @@ -1,12 +1,43 @@ # Open and connect to openocd with the ATMEL-ICE -target remote | /usr/local/bin/openocd -c "set CHIPNAME ${CHIP}" -f ${MOTATE_PATH}/openocd.cfg -f ${MOTATE_PATH}/platform/atmel_sam/atmel_sam.cfg -c "gdb_port pipe; log_output openocd.log" +#target remote | /usr/local/bin/openocd -c "set CHIPNAME ${CHIP}" -f ${MOTATE_PATH}/openocd.cfg -f ${MOTATE_PATH}/platform/atmel_sam/atmel_sam.cfg -c "gdb_port pipe; log_output openocd.log" -monitor arm semihosting enable +target extended-remote :2331 -source ./board/g2_default.gdb +# Setup for non-wrapped lines and non-pages prints +set width 0 +set height 0 + +# Turn on history saving +set history save on +set history expansion on + +set print pretty on + +define reset_deep + monitor reset + + # Reset peripheral (RSTC_CR) + set *0x400E1800 = 0xA5000004 + +# # Initializing PC and stack pointer +# mon reg sp = (0x20400000) +# set *0x20400004 = *0x20400004 & 0xFFFFFFFE +# mon reg pc=(0x20400004) + info reg +end + +define flash + make + load + reset +end + +define dump_mb + source ../Resources/debug/mb.gdb +end define boot_from_flash - monitor atsamv gpnvm set 1 + #monitor atsamv gpnvm set 1 end source -s arm.gdb From dda233f70170e06d9d39e32c7344336c4fd8ac30 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Wed, 22 Feb 2017 12:40:20 -0600 Subject: [PATCH 028/193] gQuintic: Fix redundant Servo1 pin assignment. --- g2core/board/gquintic/gquintic-b-pinout.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/g2core/board/gquintic/gquintic-b-pinout.h b/g2core/board/gquintic/gquintic-b-pinout.h index 520f7806b..f05a8bcf4 100755 --- a/g2core/board/gquintic/gquintic-b-pinout.h +++ b/g2core/board/gquintic/gquintic-b-pinout.h @@ -147,8 +147,8 @@ _MAKE_MOTATE_PIN(kADC1_PinNumber, 'A', 19); // _MAKE_MOTATE_PIN(kADC0_PinNumber, 'A', 20); // _MAKE_MOTATE_PIN(kSerial_CTSPinNumber, 'A', 21); // _MAKE_MOTATE_PIN(kSocket1_EnablePinNumber, 'A', 22); // -//_MAKE_MOTATE_PIN(kOutput10_PinNumber, 'A', 23); // -_MAKE_MOTATE_PIN(kServo1_PinNumber, 'A', 23); // +_MAKE_MOTATE_PIN(kOutput10_PinNumber, 'A', 23); // +//_MAKE_MOTATE_PIN(kServo1_PinNumber, 'A', 23); // _MAKE_MOTATE_PIN(kSocket3_EnablePinNumber, 'A', 24); // _MAKE_MOTATE_PIN(kSocket2_DirPinNumber, 'A', 25); // _MAKE_MOTATE_PIN(kOutput5_PinNumber, 'A', 26); // On Timer 2! From 9136aba90b64d7b6d4c7a3d7ee87869006936f8a Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Wed, 22 Feb 2017 12:41:03 -0600 Subject: [PATCH 029/193] HOT_FUNC and HOT_DATA assignments sprinkled all over. Also removing now-redundant abs definition. --- g2core/plan_zoid.cpp | 5 +++-- g2core/planner.h | 44 ++++++++++++++++++++++---------------------- g2core/stepper.cpp | 11 ++++++++++- g2core/stepper.h | 13 ++++++------- g2core/util.h | 2 +- g2core/xio.cpp | 8 +++++--- 6 files changed, 47 insertions(+), 36 deletions(-) diff --git a/g2core/plan_zoid.cpp b/g2core/plan_zoid.cpp index 12f85d3fa..e3d7ab6ed 100644 --- a/g2core/plan_zoid.cpp +++ b/g2core/plan_zoid.cpp @@ -69,7 +69,7 @@ static float _get_meet_velocity(const float v_0, const float v_2, const float L, mpBuf_t* bf, - mpBlockRuntimeBuf_t* block); + mpBlockRuntimeBuf_t* block) HOT_FUNC; /**************************************************************************************** * mp_calculate_ramps() - calculate trapezoid-like ramp parameters for a block @@ -114,7 +114,8 @@ static float _get_meet_velocity(const float v_0, * */ -void _zoid_exit(mpBuf_t* bf, zoidExitPoint exit_point) +void _zoid_exit(mpBuf_t* bf, zoidExitPoint exit_point) HOT_FUNC; +void _zoid_exit(mpBuf_t* bf, zoidExitPoint exit_point) { //+++++ DIAGNOSTIC // bf->zoid_exit = exit_point; diff --git a/g2core/planner.h b/g2core/planner.h index d7562d922..ef5ebecaa 100644 --- a/g2core/planner.h +++ b/g2core/planner.h @@ -514,9 +514,9 @@ typedef struct mpMotionRuntimeSingleton { // persistent runtime variables } mpMotionRuntimeSingleton_t; // Reference global scope structures -extern mpBufferPool_t mb; // buffer pool management -extern mpMotionPlannerSingleton_t mp; // context for block planning -extern mpMotionRuntimeSingleton_t mr; // context for block runtime +extern mpBufferPool_t mb HOT_DATA; // buffer pool management +extern mpMotionPlannerSingleton_t mp HOT_DATA; // context for block planning +extern mpMotionRuntimeSingleton_t mr HOT_DATA; // context for block runtime /* * Global Scope Functions @@ -566,30 +566,30 @@ void mp_init_buffers(void); #define mp_get_prev_buffer(b) ((mpBuf_t *)(b->pv)) #define mp_get_next_buffer(b) ((mpBuf_t *)(b->nx)) -mpBuf_t * mp_get_write_buffer(void); -void mp_commit_write_buffer(const blockType block_type); -mpBuf_t * mp_get_run_buffer(void); -bool mp_free_run_buffer(void); +mpBuf_t * mp_get_write_buffer(void) HOT_FUNC; +void mp_commit_write_buffer(const blockType block_type) HOT_FUNC; +mpBuf_t * mp_get_run_buffer(void) HOT_FUNC; +bool mp_free_run_buffer(void) HOT_FUNC; // plan_line.c functions -void mp_zero_segment_velocity(void); // getters and setters... -float mp_get_runtime_velocity(void); +void mp_zero_segment_velocity(void) HOT_FUNC; // getters and setters... +float mp_get_runtime_velocity(void) HOT_FUNC; float mp_get_runtime_absolute_position(uint8_t axis); float mp_get_runtime_work_position(uint8_t axis); void mp_set_runtime_work_offset(float offset[]); -bool mp_get_runtime_busy(void); -bool mp_runtime_is_idle(void); +bool mp_get_runtime_busy(void) HOT_FUNC; +bool mp_runtime_is_idle(void) HOT_FUNC; -stat_t mp_aline(GCodeState_t *gm_in); // line planning... -void mp_plan_block_list(void); -void mp_plan_block_forward(mpBuf_t *bf); +stat_t mp_aline(GCodeState_t *gm_in) HOT_FUNC; // line planning... +void mp_plan_block_list(void) HOT_FUNC; +void mp_plan_block_forward(mpBuf_t *bf) HOT_FUNC; // plan_zoid.c functions -void mp_calculate_ramps(mpBlockRuntimeBuf_t *block, mpBuf_t *bf, const float entry_velocity); -float mp_get_target_length(const float v_0, const float v_1, const mpBuf_t *bf); -float mp_get_target_velocity(const float v_0, const float L, const mpBuf_t *bf); // acceleration ONLY -float mp_get_decel_velocity(const float v_0, const float L, const mpBuf_t *bf); // deceleration ONLY -float mp_find_t(const float v_0, const float v_1, const float L, const float totalL, const float initial_t, const float T); +void mp_calculate_ramps(mpBlockRuntimeBuf_t *block, mpBuf_t *bf, const float entry_velocity) HOT_FUNC; +float mp_get_target_length(const float v_0, const float v_1, const mpBuf_t *bf) HOT_FUNC; +float mp_get_target_velocity(const float v_0, const float L, const mpBuf_t *bf) HOT_FUNC; // acceleration ONLY +float mp_get_decel_velocity(const float v_0, const float L, const mpBuf_t *bf) HOT_FUNC; // deceleration ONLY +float mp_find_t(const float v_0, const float v_1, const float L, const float totalL, const float initial_t, const float T) HOT_FUNC; float mp_calc_v(const float t, const float v_0, const float v_1); // compute the velocity along the curve accelerating from v_0 to v_1, at position t=[0,1] float mp_calc_a(const float t, const float v_0, const float v_1, const float T); // compute acceleration over curve accelerating from v_0 to v_1, at position t=[0,1], total time T @@ -597,9 +597,9 @@ float mp_calc_j(const float t, const float v_0, const float v_1, const float T); //float mp_calc_l(const float t, const float v_0, const float v_1, const float T); // compute length over curve accelerating from v_0 to v_1, at position t=[0,1], total time T // plan_exec.c functions -stat_t mp_forward_plan(void); -stat_t mp_exec_move(void); -stat_t mp_exec_aline(mpBuf_t *bf); +stat_t mp_forward_plan(void) HOT_FUNC; +stat_t mp_exec_move(void) HOT_FUNC; +stat_t mp_exec_aline(mpBuf_t *bf) HOT_FUNC; void mp_exit_hold_state(void); void mp_dump_planner(mpBuf_t *bf_start); diff --git a/g2core/stepper.cpp b/g2core/stepper.cpp index 5c2a6032c..b8e17a6ff 100644 --- a/g2core/stepper.cpp +++ b/g2core/stepper.cpp @@ -58,7 +58,7 @@ void stepper_debug(const char (&str)[len]) { ; }; stConfig_t st_cfg; stPrepSingleton_t st_pre; -static stRunSingleton_t st_run; +static stRunSingleton_t st_run HOT_DATA; /**** Static functions ****/ @@ -256,6 +256,9 @@ stat_t st_motor_power_callback() // called by controller */ namespace Motate { // Must define timer interrupts inside the Motate namespace + template<> + void dda_timer_type::interrupt() HOT_FUNC; + template<> void dda_timer_type::interrupt() { @@ -358,6 +361,9 @@ void st_request_exec_move() } namespace Motate { // Define timer inside Motate namespace + template<> + void exec_timer_type::interrupt() HOT_FUNC; + template<> void exec_timer_type::interrupt() { @@ -382,6 +388,9 @@ void st_request_forward_plan() } namespace Motate { // Define timer inside Motate namespace + template<> + void fwd_plan_timer_type::interrupt() HOT_FUNC; + template<> void fwd_plan_timer_type::interrupt() { diff --git a/g2core/stepper.h b/g2core/stepper.h index 5734ef0ee..709305d4d 100644 --- a/g2core/stepper.h +++ b/g2core/stepper.h @@ -423,8 +423,8 @@ typedef struct stPrepSingleton { magic_t magic_end; } stPrepSingleton_t; -extern stConfig_t st_cfg; // config struct is exposed. The rest are private -extern stPrepSingleton_t st_pre; // only used by config_app diagnostics +extern stConfig_t st_cfg HOT_DATA; // config struct is exposed. The rest are private +extern stPrepSingleton_t st_pre HOT_DATA; // only used by config_app diagnostics /**** Stepper (base object) ****/ @@ -569,15 +569,14 @@ stat_t st_clc(nvObj_t *nv); void st_set_motor_power(const uint8_t motor); stat_t st_motor_power_callback(void); -void st_request_forward_plan(void); -void st_request_exec_move(void); -void st_request_load_move(void); +void st_request_forward_plan(void) HOT_FUNC; +void st_request_exec_move(void) HOT_FUNC; +void st_request_load_move(void) HOT_FUNC; void st_prep_null(void); void st_prep_command(void *bf); // use a void pointer since we don't know about mpBuf_t yet) void st_prep_dwell(float microseconds); void st_request_out_of_band_dwell(float microseconds); -//stat_t st_prep_line(float travel_steps[], float following_error[], float segment_time); -stat_t st_prep_line(float travel_steps[], float following_error[], float segment_time); +stat_t st_prep_line(float travel_steps[], float following_error[], float segment_time) HOT_FUNC; stat_t st_set_ma(nvObj_t *nv); stat_t st_set_sa(nvObj_t *nv); diff --git a/g2core/util.h b/g2core/util.h index a662463c8..2d5991bca 100644 --- a/g2core/util.h +++ b/g2core/util.h @@ -113,7 +113,7 @@ using std::max; template inline T square(const T x) { return (x)*(x); } /* UNSAFE */ -inline float abs(const float a) { return fabs(a); } +//inline float abs(const float a) { return fabs(a); } #ifndef avg template diff --git a/g2core/xio.cpp b/g2core/xio.cpp index 6c2c121d0..b443b790c 100755 --- a/g2core/xio.cpp +++ b/g2core/xio.cpp @@ -46,6 +46,8 @@ using Motate::RXBuffer; using Motate::TXBuffer; +#include "MotateUtilities.h" // for HOT_DATA and HOT_FUNC + #ifdef __TEXT_MODE #include "text_parser.h" #endif @@ -1026,12 +1028,12 @@ struct xioDeviceWrapper : xioDeviceWrapperBase { // describes a device for re // ALLOCATIONS // Declare a device wrapper class for SerialUSB and SerialUSB1 #if XIO_HAS_USB == 1 -xioDeviceWrapper serialUSB0Wrapper { +xioDeviceWrapper serialUSB0Wrapper HOT_DATA { &SerialUSB, (DEV_CAN_READ | DEV_CAN_WRITE | DEV_CAN_BE_CTRL | DEV_CAN_BE_DATA) }; #if USB_SERIAL_PORTS_EXPOSED == 2 -xioDeviceWrapper serialUSB1Wrapper { +xioDeviceWrapper serialUSB1Wrapper HOT_DATA { &SerialUSB1, (DEV_CAN_READ | DEV_CAN_WRITE | DEV_CAN_BE_CTRL | DEV_CAN_BE_DATA) }; @@ -1043,7 +1045,7 @@ constexpr devflags_t _serial0ExtraFlags = DEV_IS_ALWAYS_BOTH | DEV_IS_MUTE_SECON #else constexpr devflags_t _serial0ExtraFlags = DEV_IS_ALWAYS_BOTH; #endif -xioDeviceWrapper serial0Wrapper { +xioDeviceWrapper serial0Wrapper HOT_DATA { &Serial, (DEV_CAN_READ | DEV_CAN_WRITE | _serial0ExtraFlags) }; From 48c4d7d75ea5eab6c24faa17a5bc8e96e6c2aee0 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Thu, 23 Feb 2017 20:31:57 -0600 Subject: [PATCH 030/193] Adding gQuadratic and gQuintic on AxiDraw v3 configs to Atmel Studio, and jlink.config. --- g2core.atsln | 11 +++- g2core/g2core.cppproj | 132 ++++++++++++++++++++++++++++++++++++++++++ g2core/jlink.config | 39 +++++++++++++ 3 files changed, 181 insertions(+), 1 deletion(-) create mode 100755 g2core/jlink.config diff --git a/g2core.atsln b/g2core.atsln index 93cd6ae13..c8f6bcae0 100644 --- a/g2core.atsln +++ b/g2core.atsln @@ -1,6 +1,6 @@ Microsoft Visual Studio Solution File, Format Version 12.00 # Atmel Studio Solution File, Format Version 11.00 -VisualStudioVersion = 14.0.23107.0 +VisualStudioVersion = 14.0.25420.1 MinimumVisualStudioVersion = 10.0.40219.1 Project("{E66E83B9-2572-4076-B26E-6BE79FF3018A}") = "g2core", "g2core\g2core.cppproj", "{44EA8FEC-55D7-4149-8A78-A574FC26BF51}" EndProject @@ -9,6 +9,8 @@ EndProject Global GlobalSection(SolutionConfigurationPlatforms) = preSolution G2v9k|ARM = G2v9k|ARM + gQuadratic on AxiDraw v3|ARM = gQuadratic on AxiDraw v3|ARM + gQuintic on AxiDraw v3|ARM = gQuintic on AxiDraw v3|ARM gShield|ARM = gShield|ARM Makeblock-v9|ARM = Makeblock-v9|ARM Othermill|ARM = Othermill|ARM @@ -28,6 +30,11 @@ Global GlobalSection(ProjectConfigurationPlatforms) = postSolution {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.G2v9k|ARM.ActiveCfg = G2v9k|ARM {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.G2v9k|ARM.Build.0 = G2v9k|ARM + {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.G2v9k|ARM.Deploy.0 = G2v9k|ARM + {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.gQuadratic on AxiDraw v3|ARM.ActiveCfg = gQuadratic on AxiDraw v3|ARM + {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.gQuadratic on AxiDraw v3|ARM.Build.0 = gQuadratic on AxiDraw v3|ARM + {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.gQuintic on AxiDraw v3|ARM.ActiveCfg = qQuintic on AxiDraw v3|ARM + {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.gQuintic on AxiDraw v3|ARM.Build.0 = qQuintic on AxiDraw v3|ARM {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.gShield|ARM.ActiveCfg = gShield|ARM {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.gShield|ARM.Build.0 = gShield|ARM {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.Makeblock-v9|ARM.ActiveCfg = Makeblock-v9|ARM @@ -58,6 +65,8 @@ Global {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.Zen7x12|ARM.ActiveCfg = Zen7x12|ARM {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.Zen7x12|ARM.Build.0 = Zen7x12|ARM {D7779B24-5CD6-4A1B-893C-2CAE8CF7A3A0}.G2v9k|ARM.ActiveCfg = Stub|ARM + {D7779B24-5CD6-4A1B-893C-2CAE8CF7A3A0}.gQuadratic on AxiDraw v3|ARM.ActiveCfg = Stub|ARM + {D7779B24-5CD6-4A1B-893C-2CAE8CF7A3A0}.gQuintic on AxiDraw v3|ARM.ActiveCfg = Stub|ARM {D7779B24-5CD6-4A1B-893C-2CAE8CF7A3A0}.gShield|ARM.ActiveCfg = Stub|ARM {D7779B24-5CD6-4A1B-893C-2CAE8CF7A3A0}.Makeblock-v9|ARM.ActiveCfg = Stub|ARM {D7779B24-5CD6-4A1B-893C-2CAE8CF7A3A0}.Othermill|ARM.ActiveCfg = Stub|ARM diff --git a/g2core/g2core.cppproj b/g2core/g2core.cppproj index 591d31b03..cc06d9143 100644 --- a/g2core/g2core.cppproj +++ b/g2core/g2core.cppproj @@ -1520,6 +1520,138 @@ Makefile bin\TestQuadratic\ + + + + True + True + True + True + True + + + C:\Program Files\Atmel\Atmel Studio 6.0\extensions\Atmel\ARMGCC\3.3.1.128\ARMSupportFiles + C:\Program Files\Atmel\Atmel Studio 6.0\extensions\Atmel\ARMGCC\3.3.1.128\ARMSupportFiles\CMSIS\Include + C:\Program Files\Atmel\Atmel Studio 6.0\extensions\Atmel\ARMGCC\3.3.1.128\ARMSupportFiles\Device\ATMEL + C:\Program Files\Atmel\Atmel Studio 6.0\extensions\Atmel\ARMGCC\3.3.1.128\ARMSupportFiles\Device\ATMEL\sam3xa\include + C:\Program Files\Atmel\Atmel Toolchain\ARM GCC\Native\4.7.2.87\arm-gnu-toolchain\bin\..\..\CMSIS_Atmel + C:\Program Files\Atmel\Atmel Toolchain\ARM GCC\Native\4.7.2.87\arm-gnu-toolchain\bin\..\..\CMSIS_Atmel\CMSIS\Include + C:\Program Files\Atmel\Atmel Toolchain\ARM GCC\Native\4.7.2.87\arm-gnu-toolchain\bin\..\..\CMSIS_Atmel\Device\ATMEL + C:\Program Files\Atmel\Atmel Toolchain\ARM GCC\Native\4.7.2.87\arm-gnu-toolchain\bin\..\..\CMSIS_Atmel\Device\ATMEL\sam3xa\include + + + Optimize (-O1) + True + Maximum (-g3) + True + + + C:\Program Files\Atmel\Atmel Studio 6.0\extensions\Atmel\ARMGCC\3.3.1.128\ARMSupportFiles + C:\Program Files\Atmel\Atmel Studio 6.0\extensions\Atmel\ARMGCC\3.3.1.128\ARMSupportFiles\CMSIS\Include + C:\Program Files\Atmel\Atmel Studio 6.0\extensions\Atmel\ARMGCC\3.3.1.128\ARMSupportFiles\Device\ATMEL + C:\Program Files\Atmel\Atmel Studio 6.0\extensions\Atmel\ARMGCC\3.3.1.128\ARMSupportFiles\Device\ATMEL\sam3xa\include + C:\Program Files\Atmel\Atmel Toolchain\ARM GCC\Native\4.7.2.87\arm-gnu-toolchain\bin\..\..\CMSIS_Atmel + C:\Program Files\Atmel\Atmel Toolchain\ARM GCC\Native\4.7.2.87\arm-gnu-toolchain\bin\..\..\CMSIS_Atmel\CMSIS\Include + C:\Program Files\Atmel\Atmel Toolchain\ARM GCC\Native\4.7.2.87\arm-gnu-toolchain\bin\..\..\CMSIS_Atmel\Device\ATMEL + C:\Program Files\Atmel\Atmel Toolchain\ARM GCC\Native\4.7.2.87\arm-gnu-toolchain\bin\..\..\CMSIS_Atmel\Device\ATMEL\sam3xa\include + + + Optimize (-O1) + True + Maximum (-g3) + True + + + libm + + + True + -Tsam3x8c_flash.ld + Default (-g) + + + C:\Program Files\Atmel\Atmel Toolchain\ARM GCC\Native\4.7.2.87\arm-gnu-toolchain\bin\..\..\CMSIS_Atmel + C:\Program Files\Atmel\Atmel Toolchain\ARM GCC\Native\4.7.2.87\arm-gnu-toolchain\bin\..\..\CMSIS_Atmel\CMSIS\Include + C:\Program Files\Atmel\Atmel Toolchain\ARM GCC\Native\4.7.2.87\arm-gnu-toolchain\bin\..\..\CMSIS_Atmel\Device\ATMEL + C:\Program Files\Atmel\Atmel Toolchain\ARM GCC\Native\4.7.2.87\arm-gnu-toolchain\bin\..\..\CMSIS_Atmel\Device\ATMEL\sam3xa\include + + + Default (-Wa,-g) + + + True + + CONFIG=AxiDrawv3 BOARD=gquintic-b COLOR=0 VERBOSE=1 + clean CONFIG=AxiDrawv3 BOARD=gquintic-b + Makefile + bin\qQuintic on AxiDraw v3\ + + + + + True + True + True + True + True + + + C:\Program Files\Atmel\Atmel Studio 6.0\extensions\Atmel\ARMGCC\3.3.1.128\ARMSupportFiles + C:\Program Files\Atmel\Atmel Studio 6.0\extensions\Atmel\ARMGCC\3.3.1.128\ARMSupportFiles\CMSIS\Include + C:\Program Files\Atmel\Atmel Studio 6.0\extensions\Atmel\ARMGCC\3.3.1.128\ARMSupportFiles\Device\ATMEL + C:\Program Files\Atmel\Atmel Studio 6.0\extensions\Atmel\ARMGCC\3.3.1.128\ARMSupportFiles\Device\ATMEL\sam3xa\include + C:\Program Files\Atmel\Atmel Toolchain\ARM GCC\Native\4.7.2.87\arm-gnu-toolchain\bin\..\..\CMSIS_Atmel + C:\Program Files\Atmel\Atmel Toolchain\ARM GCC\Native\4.7.2.87\arm-gnu-toolchain\bin\..\..\CMSIS_Atmel\CMSIS\Include + C:\Program Files\Atmel\Atmel Toolchain\ARM GCC\Native\4.7.2.87\arm-gnu-toolchain\bin\..\..\CMSIS_Atmel\Device\ATMEL + C:\Program Files\Atmel\Atmel Toolchain\ARM GCC\Native\4.7.2.87\arm-gnu-toolchain\bin\..\..\CMSIS_Atmel\Device\ATMEL\sam3xa\include + + + Optimize (-O1) + True + Maximum (-g3) + True + + + C:\Program Files\Atmel\Atmel Studio 6.0\extensions\Atmel\ARMGCC\3.3.1.128\ARMSupportFiles + C:\Program Files\Atmel\Atmel Studio 6.0\extensions\Atmel\ARMGCC\3.3.1.128\ARMSupportFiles\CMSIS\Include + C:\Program Files\Atmel\Atmel Studio 6.0\extensions\Atmel\ARMGCC\3.3.1.128\ARMSupportFiles\Device\ATMEL + C:\Program Files\Atmel\Atmel Studio 6.0\extensions\Atmel\ARMGCC\3.3.1.128\ARMSupportFiles\Device\ATMEL\sam3xa\include + C:\Program Files\Atmel\Atmel Toolchain\ARM GCC\Native\4.7.2.87\arm-gnu-toolchain\bin\..\..\CMSIS_Atmel + C:\Program Files\Atmel\Atmel Toolchain\ARM GCC\Native\4.7.2.87\arm-gnu-toolchain\bin\..\..\CMSIS_Atmel\CMSIS\Include + C:\Program Files\Atmel\Atmel Toolchain\ARM GCC\Native\4.7.2.87\arm-gnu-toolchain\bin\..\..\CMSIS_Atmel\Device\ATMEL + C:\Program Files\Atmel\Atmel Toolchain\ARM GCC\Native\4.7.2.87\arm-gnu-toolchain\bin\..\..\CMSIS_Atmel\Device\ATMEL\sam3xa\include + + + Optimize (-O1) + True + Maximum (-g3) + True + + + libm + + + True + -Tsam3x8c_flash.ld + Default (-g) + + + C:\Program Files\Atmel\Atmel Toolchain\ARM GCC\Native\4.7.2.87\arm-gnu-toolchain\bin\..\..\CMSIS_Atmel + C:\Program Files\Atmel\Atmel Toolchain\ARM GCC\Native\4.7.2.87\arm-gnu-toolchain\bin\..\..\CMSIS_Atmel\CMSIS\Include + C:\Program Files\Atmel\Atmel Toolchain\ARM GCC\Native\4.7.2.87\arm-gnu-toolchain\bin\..\..\CMSIS_Atmel\Device\ATMEL + C:\Program Files\Atmel\Atmel Toolchain\ARM GCC\Native\4.7.2.87\arm-gnu-toolchain\bin\..\..\CMSIS_Atmel\Device\ATMEL\sam3xa\include + + + Default (-Wa,-g) + + + True + + CONFIG=AxiDrawv3 BOARD=gquadratic-b COLOR=0 VERBOSE=1 + clean CONFIG=AxiDrawv3 BOARD=gquadratic-b + Makefile + bin\gQuadratic on AxiDraw v3\ + compile diff --git a/g2core/jlink.config b/g2core/jlink.config new file mode 100755 index 000000000..292d9a028 --- /dev/null +++ b/g2core/jlink.config @@ -0,0 +1,39 @@ +[BREAKPOINTS] +ForceImpTypeAny = 0 +ShowInfoWin = 1 +EnableFlashBP = 2 +BPDuringExecution = 0 +[CFI] +CFISize = 0x00 +CFIAddr = 0x00 +[CPU] +MonModeVTableAddr = 0xFFFFFFFF +MonModeDebug = 0 +MaxNumAPs = 0 +LowPowerHandlingMode = 0 +OverrideMemMap = 0 +AllowSimulation = 1 +ScriptFile="" +[FLASH] +CacheExcludeSize = 0x00 +CacheExcludeAddr = 0x00 +MinNumBytesFlashDL = 0 +SkipProgOnCRCMatch = 1 +VerifyDownload = 1 +AllowCaching = 1 +EnableFlashDL = 2 +Override = 0 +Device="ARM7" +[GENERAL] +WorkRAMSize = 0x00 +WorkRAMAddr = 0x00 +RAMUsageLimit = 0x00 +[SWO] +SWOLogFile="" +[MEM] +RdOverrideOrMask = 0x00 +RdOverrideAndMask = 0xFFFFFFFF +RdOverrideAddr = 0xFFFFFFFF +WrOverrideOrMask = 0x00 +WrOverrideAndMask = 0xFFFFFFFF +WrOverrideAddr = 0xFFFFFFFF From c20684fb459e659abd8b5194ebb4593c3046ea7c Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Thu, 23 Feb 2017 20:32:38 -0600 Subject: [PATCH 031/193] Updated reference to Motate for make clean and tools won load files on Windows. --- Motate | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Motate b/Motate index 31af41606..6d43c1fb7 160000 --- a/Motate +++ b/Motate @@ -1 +1 @@ -Subproject commit 31af41606478cd0ace341f3ea08bc8f5a5adbc54 +Subproject commit 6d43c1fb7ac2b6fff6eff164816d51f26220a8dd From c031daa51291189645b2e8091aa83e6fff09a5f7 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Thu, 23 Feb 2017 22:33:11 -0600 Subject: [PATCH 032/193] Fix for broken Motor_3! --- g2core/board/gquintic/gquintic-b-pinout.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/g2core/board/gquintic/gquintic-b-pinout.h b/g2core/board/gquintic/gquintic-b-pinout.h index f05a8bcf4..ad3425c3c 100755 --- a/g2core/board/gquintic/gquintic-b-pinout.h +++ b/g2core/board/gquintic/gquintic-b-pinout.h @@ -152,7 +152,7 @@ _MAKE_MOTATE_PIN(kOutput10_PinNumber, 'A', 23); // _MAKE_MOTATE_PIN(kSocket3_EnablePinNumber, 'A', 24); // _MAKE_MOTATE_PIN(kSocket2_DirPinNumber, 'A', 25); // _MAKE_MOTATE_PIN(kOutput5_PinNumber, 'A', 26); // On Timer 2! -_MAKE_MOTATE_PIN(kSocket3_StepPinNumber, 'A', 27); // On Timer 2! +_MAKE_MOTATE_PIN(kSocket3_DirPinNumber, 'A', 27); // On Timer 2! _MAKE_MOTATE_PIN(kUnassigned1, 'A', 28); // DIAG1 _MAKE_MOTATE_PIN(kUnassigned2, 'A', 29); // _MAKE_MOTATE_PIN(kInput1_PinNumber, 'A', 30); // @@ -193,7 +193,7 @@ _MAKE_MOTATE_PIN(kSocket5_EnablePinNumber, 'D', 14); // _MAKE_MOTATE_PIN(kUnassigned5, 'D', 15); // _MAKE_MOTATE_PIN(kSocket4_StepPinNumber, 'D', 16); // _MAKE_MOTATE_PIN(kSocket4_DirPinNumber, 'D', 17); // -_MAKE_MOTATE_PIN(kSocket3_DirPinNumber, 'D', 18); // +_MAKE_MOTATE_PIN(kSocket3_StepPinNumber, 'D', 18); // _MAKE_MOTATE_PIN(kUnassigned6, 'D', 19); // _MAKE_MOTATE_PIN(kSPI0_MISOPinNumber, 'D', 20); // _MAKE_MOTATE_PIN(kSPI0_MOSIPinNumber, 'D', 21); // From c2f5bfdb9963d45f2460318555ae78fe1fa8dd0d Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Thu, 23 Feb 2017 22:33:44 -0600 Subject: [PATCH 033/193] Adjust TMC2130 callbacks, lower processor usage noticeably --- g2core/device/trinamic/tmc2130.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/g2core/device/trinamic/tmc2130.h b/g2core/device/trinamic/tmc2130.h index 96f3083bd..d522c7dcc 100644 --- a/g2core/device/trinamic/tmc2130.h +++ b/g2core/device/trinamic/tmc2130.h @@ -539,7 +539,7 @@ struct Trinamic2130 final : Stepper { _reading_only = false; _transmitting = false; - //_startNextReadWrite(); + _startNextReadWrite(); }; void init() override @@ -634,7 +634,7 @@ struct Trinamic2130 final : Stepper { IOIN_needs_read = true; CHOPCONF_needs_read = true; DRV_STATUS_needs_read = true; + _startNextReadWrite(); } - _startNextReadWrite(); }; }; From b97fb544d525c18533956ee6e147409d9195fd75 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Thu, 23 Feb 2017 23:09:14 -0600 Subject: [PATCH 034/193] =?UTF-8?q?Fix=20issue=20where=20power=20levels=20?= =?UTF-8?q?are=20getting=20scaled=20before=20the=20per-driver=20stepper=20?= =?UTF-8?q?object.=20They=E2=80=99re=20now=20scaled=20(or=20not)=20inside?= =?UTF-8?q?=20the=20stepper=20objects.?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- g2core/device/step_dir_driver/step_dir_driver.h | 7 ++++++- g2core/stepper.cpp | 10 +++++----- g2core/stepper.h | 8 -------- 3 files changed, 11 insertions(+), 14 deletions(-) diff --git a/g2core/device/step_dir_driver/step_dir_driver.h b/g2core/device/step_dir_driver/step_dir_driver.h index da3cfc1e7..d64ddded6 100644 --- a/g2core/device/step_dir_driver/step_dir_driver.h +++ b/g2core/device/step_dir_driver/step_dir_driver.h @@ -40,6 +40,11 @@ using Motate::kStartHigh; using Motate::kNormal; using Motate::Timeout; +// Stepper power management settings +// These should be more flexible, but for now this will do +#define Vcc 3.3 // volts +#define MaxVref 2.25 // max vref for driver circuit. Our ckt is 2.25 volts +#define POWER_LEVEL_SCALE_FACTOR ((MaxVref/Vcc)) // scale power level setting for voltage range // Motor structures template setPowerLevel(st_cfg.mot[motor].power_level_scaled); - st_run.mot[motor].power_level_dynamic = st_cfg.mot[motor].power_level_scaled; + Motors[motor]->setPowerLevel(st_cfg.mot[motor].power_level); + st_run.mot[motor].power_level_dynamic = st_cfg.mot[motor].power_level; } board_stepper_init(); stepper_reset(); // reset steppers to known state @@ -1000,9 +1000,9 @@ stat_t st_set_pl(nvObj_t *nv) // motor power level set_flt(nv); // set power_setting value in the motor config struct (st) uint8_t motor = _get_motor(nv->index); - st_cfg.mot[motor].power_level_scaled = (nv->value * POWER_LEVEL_SCALE_FACTOR); - st_run.mot[motor].power_level_dynamic = (st_cfg.mot[motor].power_level_scaled); - Motors[motor]->setPowerLevel(st_cfg.mot[motor].power_level_scaled); + st_cfg.mot[motor].power_level = nv->value; + st_run.mot[motor].power_level_dynamic = (st_cfg.mot[motor].power_level); + Motors[motor]->setPowerLevel(st_cfg.mot[motor].power_level); return(STAT_OK); } diff --git a/g2core/stepper.h b/g2core/stepper.h index 709305d4d..4b2f7824e 100644 --- a/g2core/stepper.h +++ b/g2core/stepper.h @@ -282,11 +282,6 @@ typedef enum { MOTOR_POWER_MODE_MAX_VALUE // for input range checking } stPowerMode; -// Stepper power management settings -#define Vcc 3.3 // volts -#define MaxVref 2.25 // max vref for driver circuit. Our ckt is 2.25 volts -#define POWER_LEVEL_SCALE_FACTOR ((MaxVref/Vcc)) // scale power level setting for voltage range - // Min/Max timeouts allowed for motor disable. Allow for inertial stop; must be non-zero #define MOTOR_TIMEOUT_SECONDS_MIN (float)0.1 // seconds !!! SHOULD NEVER BE ZERO !!! #define MOTOR_TIMEOUT_SECONDS_MAX (float)4294967 // (4294967295/1000) -- for conversion to uint32_t @@ -359,9 +354,6 @@ typedef struct cfgMotor { // per-motor configs float travel_rev; // mm or deg of travel per motor revolution float steps_per_unit; // microsteps per mm (or degree) of travel float units_per_step; // mm or degrees of travel per microstep - - // private - float power_level_scaled; // scaled to internal range - must be between 0 and 1 } cfgMotor_t; typedef struct stConfig { // stepper configs From 73a772b13851cdd5a96eed404cee6b2f81ea5bb2 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Fri, 24 Feb 2017 10:58:05 -0600 Subject: [PATCH 035/193] Update Makefile and Motate to get TOOLS_VERSION matching. --- Motate | 2 +- g2core/Makefile | 14 ++++++++------ 2 files changed, 9 insertions(+), 7 deletions(-) diff --git a/Motate b/Motate index 6d43c1fb7..bf4f2fb3d 160000 --- a/Motate +++ b/Motate @@ -1 +1 @@ -Subproject commit 6d43c1fb7ac2b6fff6eff164816d51f26220a8dd +Subproject commit bf4f2fb3dcd710abfd8aa2c2cdcc56128dd7ddb1 diff --git a/g2core/Makefile b/g2core/Makefile index cf8777f8f..494fd4e0c 100755 --- a/g2core/Makefile +++ b/g2core/Makefile @@ -49,17 +49,19 @@ SETTINGS_FILE ?= settings_default.h NEEDS_PRINTF_FLOAT=1 -# Now invoke the Motate compile system -include $(MOTATE_PATH)/Motate.mk - ifeq ($(DEBUG),0) - DEVICE_DEFINES += DEBUG=0 IN_DEBUGGER=0 +DEVICE_DEFINES += DEBUG=0 IN_DEBUGGER=0 endif ifeq ($(DEBUG),1) - DEVICE_DEFINES += DEBUG=1 IN_DEBUGGER=0 +DEVICE_DEFINES += DEBUG=1 IN_DEBUGGER=0 endif ifeq ($(DEBUG),2) - DEVICE_DEFINES += DEBUG=1 IN_DEBUGGER=1 +DEVICE_DEFINES += DEBUG=1 IN_DEBUGGER=1 endif +TOOLS_VERSION = 6.2 + +# Now invoke the Motate compile system +include $(MOTATE_PATH)/Motate.mk + # *** EOF *** From aace4ad6e02ed976556467cf6a36d7799194f686 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Fri, 24 Feb 2017 13:18:56 -0600 Subject: [PATCH 036/193] Speedup for gQuintic: DDA freq of 300K, and marked USB object as HOT_DATA. --- g2core/board/gquintic/board_xio.h | 2 +- g2core/board/gquintic/hardware.h | 2 +- .../G2 gQuadratic Test copy.xcscheme | 80 ------------------- 3 files changed, 2 insertions(+), 82 deletions(-) delete mode 100644 g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 gQuadratic Test copy.xcscheme diff --git a/g2core/board/gquintic/board_xio.h b/g2core/board/gquintic/board_xio.h index 09f20fef8..df866818a 100755 --- a/g2core/board/gquintic/board_xio.h +++ b/g2core/board/gquintic/board_xio.h @@ -43,7 +43,7 @@ typedef Motate::USBDevice< Motate::USBCDC > XIOUSBDevice_t; typedef Motate::USBDevice XIOUSBDevice_t; #endif -extern XIOUSBDevice_t usb; +extern XIOUSBDevice_t usb HOT_DATA; extern decltype(usb.mixin<0>::Serial)& SerialUSB; #if USB_SERIAL_PORTS_EXPOSED == 2 extern decltype(usb.mixin<1>::Serial)& SerialUSB1; diff --git a/g2core/board/gquintic/hardware.h b/g2core/board/gquintic/hardware.h index 41d3215d3..d82ce5034 100644 --- a/g2core/board/gquintic/hardware.h +++ b/g2core/board/gquintic/hardware.h @@ -120,7 +120,7 @@ using Motate::OutputPin; /**** Stepper DDA and dwell timer settings ****/ //#define FREQUENCY_DDA 200000UL // Hz step frequency. Interrupts actually fire at 2x (400 KHz) -#define FREQUENCY_DDA 200000UL // Hz step frequency. Interrupts actually fire at 2x (300 KHz) +#define FREQUENCY_DDA 300000UL // Hz step frequency. Interrupts actually fire at 2x (300 KHz) #define FREQUENCY_DWELL 1000UL #define MIN_SEGMENT_MS ((float)0.125) // S70 can handle much much smaller segements diff --git a/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 gQuadratic Test copy.xcscheme b/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 gQuadratic Test copy.xcscheme deleted file mode 100644 index e21407543..000000000 --- a/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 gQuadratic Test copy.xcscheme +++ /dev/null @@ -1,80 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - From 87967e78e616233a57ff4c6dadffa0c471cbd02a Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Wed, 8 Mar 2017 22:23:45 -0600 Subject: [PATCH 037/193] Update Motate for initial ADC code (broken) --- Motate | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Motate b/Motate index bf4f2fb3d..c1c87e085 160000 --- a/Motate +++ b/Motate @@ -1 +1 @@ -Subproject commit bf4f2fb3dcd710abfd8aa2c2cdcc56128dd7ddb1 +Subproject commit c1c87e085182e8abedd3d7815f88e9507b5a7c38 From ec80cbf5877b7da998a730fc4978c85ebd49e4df Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Wed, 8 Mar 2017 22:24:05 -0600 Subject: [PATCH 038/193] Updates for new ADC API (cleaner). --- g2core/board/gquintic/gquintic-b-pinout.h | 8 +-- g2core/temperature.cpp | 62 ++++++++++++----------- 2 files changed, 36 insertions(+), 34 deletions(-) diff --git a/g2core/board/gquintic/gquintic-b-pinout.h b/g2core/board/gquintic/gquintic-b-pinout.h index ad3425c3c..66c9c1cbc 100755 --- a/g2core/board/gquintic/gquintic-b-pinout.h +++ b/g2core/board/gquintic/gquintic-b-pinout.h @@ -84,9 +84,9 @@ #define INPUT13_AVAILABLE 0 -#define ADC0_AVAILABLE 0 -#define ADC1_AVAILABLE 0 -#define ADC2_AVAILABLE 0 +#define ADC0_AVAILABLE 1 +#define ADC1_AVAILABLE 1 +#define ADC2_AVAILABLE 1 #define ADC3_AVAILABLE 0 #define XIO_HAS_USB 1 @@ -94,7 +94,7 @@ #define XIO_HAS_SPI 0 #define XIO_HAS_I2C 0 -#define TEMPERATURE_OUTPUT_ON 0 // NO ADC yet +#define TEMPERATURE_OUTPUT_ON 1 // NO ADC yet // Some pins, if the PWM capability is turned on, it will cause timer conflicts. // So we have to explicitly enable them as PWM pins. diff --git a/g2core/temperature.cpp b/g2core/temperature.cpp index a3666df7b..221b7e035 100755 --- a/g2core/temperature.cpp +++ b/g2core/temperature.cpp @@ -109,7 +109,7 @@ struct Thermistor { float c1, c2, c3, pullup_resistance, inline_resistance; // We'll pull adc top value from the adc_pin.getTop() - ADCPin adc_pin; + ADCPin adc_pin {kNormal, [&]{this->adc_has_new_value();} }; uint16_t raw_adc_value = 0; typedef Thermistor type; @@ -205,42 +205,42 @@ Thermistor thermistor1 { /*R1:*/ 140000.0, /*R2:*/ 593.0, /*R3:*/ 189.0, /*pullup_resistance:*/ 4700, /*inline_resistance:*/ 4700 }; -#if ADC1_AVAILABLE == 1 -namespace Motate { -template<> -void ADCPin::interrupt() { - thermistor1.adc_has_new_value(); -}; -} -#endif +//#if ADC1_AVAILABLE == 1 +//namespace Motate { +//template<> +//void ADCPin::interrupt() { +// thermistor1.adc_has_new_value(); +//}; +//} +//#endif // Extruder 2 Thermistor thermistor2 { /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, /*R1:*/ 140000.0, /*R2:*/ 490.0, /*R3:*/ 109.0, /*pullup_resistance:*/ 4700, /*inline_resistance:*/ 4700 }; -#if ADC2_AVAILABLE == 1 -namespace Motate { -template<> -void ADCPin::interrupt() { - thermistor2.adc_has_new_value(); -}; -} -#endif +//#if ADC2_AVAILABLE == 1 +//namespace Motate { +//template<> +//void ADCPin::interrupt() { +// thermistor2.adc_has_new_value(); +//}; +//} +//#endif // Heated bed Thermistor thermistor3 { /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, /*R1:*/ 140000.0, /*R2:*/ 490.0, /*R3:*/ 109.0, /*pullup_resistance:*/ 4700, /*inline_resistance:*/ 4700 }; -#if ADC0_AVAILABLE == 1 -namespace Motate { -template<> -void ADCPin::interrupt() { - thermistor3.adc_has_new_value(); -}; -} -#endif +//#if ADC0_AVAILABLE == 1 +//namespace Motate { +//template<> +//void ADCPin::interrupt() { +// thermistor3.adc_has_new_value(); +//}; +//} +//#endif float last_reported_temp1 = 0; // keep track of what we've reported for SR generation float last_reported_temp2 = 0; @@ -300,12 +300,14 @@ PWMOutputPin<-1> fet_pin3;// {kPWMPinInverted}; #if TEMPERATURE_OUTPUT_ON == 1 // We're going to register a SysTick event -const int16_t fet_pin1_sample_freq = 10; // every fet_pin1_sample_freq interrupts, sample -int16_t fet_pin1_sample_counter = fet_pin1_sample_freq; +const int16_t temperature_sample_freq = 10; // every fet_pin1_sample_freq interrupts, sample +int16_t temperature_sample_counter = temperature_sample_freq; SysTickEvent adc_tick_event {[&] { - if (!--fet_pin1_sample_counter) { - ADC_Module::startSampling(); - fet_pin1_sample_counter = fet_pin1_sample_freq; + if (!--temperature_sample_counter) { + thermistor1.adc_pin.startSampling(); + thermistor2.adc_pin.startSampling(); + thermistor3.adc_pin.startSampling(); + temperature_sample_counter = temperature_sample_freq; } }, nullptr}; From 9d9ed0e98ecc04c646527b4d450bf32ce4f57967 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Wed, 8 Mar 2017 22:24:17 -0600 Subject: [PATCH 039/193] Fix a sprint with the wrong tag --- g2core/config.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/g2core/config.cpp b/g2core/config.cpp index b9f65526b..45a9c68fc 100644 --- a/g2core/config.cpp +++ b/g2core/config.cpp @@ -738,7 +738,7 @@ void nv_print_list(stat_t status, uint8_t text_flags, uint8_t json_flags) void nv_dump_nv(nvObj_t *nv) { - sprintf (cs.out_buf, "i:%d, d:%d, t:%d, p:%d, v:%f, g:%s, t:%s, s:%s\n", + sprintf (cs.out_buf, "i:%ld, d:%d, t:%d, p:%d, v:%f, g:%s, t:%s, s:%s\n", nv->index, nv->depth, nv->valuetype, From 264f11df4e9ed26823cd5d41e506d8991dba1782 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Tue, 14 Mar 2017 20:49:06 -0500 Subject: [PATCH 040/193] Update Motate reference for new ADC updates --- Motate | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Motate b/Motate index c1c87e085..25a835471 160000 --- a/Motate +++ b/Motate @@ -1 +1 @@ -Subproject commit c1c87e085182e8abedd3d7815f88e9507b5a7c38 +Subproject commit 25a835471c912c0969122aaed15e7e0cd3d086f0 From 1c3915c1a433469367681b4cdce42d6625ebcef0 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Tue, 14 Mar 2017 20:51:00 -0500 Subject: [PATCH 041/193] =?UTF-8?q?Added=20=E2=80=9CheNtv=E2=80=9D=20to=20?= =?UTF-8?q?display=20the=20sensor=E2=80=99s=20voltage=20reading.=20Added?= =?UTF-8?q?=20PT100=20sensor=20and=20settings=20to=20choose=20Thermistor?= =?UTF-8?q?=20or=20PT100.?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- g2core/config_app.cpp | 3 + g2core/settings/settings_Printrbot_Play.h | 44 ++++ g2core/settings/settings_Printrbot_Plus.h | 44 ++++ .../settings/settings_Printrbot_Simple_1403.h | 44 ++++ .../settings/settings_Printrbot_Simple_1608.h | 44 ++++ g2core/temperature.cpp | 223 ++++++++++++------ g2core/temperature.h | 1 + 7 files changed, 325 insertions(+), 78 deletions(-) diff --git a/g2core/config_app.cpp b/g2core/config_app.cpp index 3b01028be..34cc29ed9 100644 --- a/g2core/config_app.cpp +++ b/g2core/config_app.cpp @@ -497,6 +497,7 @@ const cfgItem_t cfgArray[] = { { "he1","he1t", _f0, 1, tx_print_nul, cm_get_temperature, set_ro, (float *)&cs.null, 0 }, { "he1","he1op",_f0, 3, tx_print_nul, cm_get_heater_output, set_ro, (float *)&cs.null, 0 }, { "he1","he1tr",_f0, 3, tx_print_nul, cm_get_thermistor_resistance, set_ro, (float *)&cs.null, 0 }, + { "he1","he1tv",_f0, 6, tx_print_nul, cm_get_thermistor_voltage, set_ro, (float *)&cs.null, 0 }, { "he1","he1at",_f0, 0, tx_print_nul, cm_get_at_temperature, set_ro, (float *)&cs.null, 0 }, { "he1","he1an",_f0, 0, tx_print_nul, cm_get_heater_adc, set_ro, (float *)&cs.null, 0 }, { "he1","he1fp",_f0, 1, tx_print_nul, cm_get_fan_power, cm_set_fan_power, (float *)&cs.null, 0 }, @@ -512,6 +513,7 @@ const cfgItem_t cfgArray[] = { { "he2","he2t", _f0, 1, tx_print_nul, cm_get_temperature, set_ro, (float *)&cs.null, 0 }, { "he2","he2op",_f0, 3, tx_print_nul, cm_get_heater_output, set_ro, (float *)&cs.null, 0 }, { "he2","he2tr",_f0, 3, tx_print_nul, cm_get_thermistor_resistance, set_ro, (float *)&cs.null, 0 }, + { "he2","he2tv",_f0, 6, tx_print_nul, cm_get_thermistor_voltage, set_ro, (float *)&cs.null, 0 }, { "he2","he2at",_f0, 0, tx_print_nul, cm_get_at_temperature, set_ro, (float *)&cs.null, 0 }, { "he2","he2an",_f0, 0, tx_print_nul, cm_get_heater_adc, set_ro, (float *)&cs.null, 0 }, { "he2","he2fp",_f0, 1, tx_print_nul, cm_get_fan_power, cm_set_fan_power, (float *)&cs.null, 0 }, @@ -527,6 +529,7 @@ const cfgItem_t cfgArray[] = { { "he3","he3t", _f0, 1, tx_print_nul, cm_get_temperature, set_ro, (float *)&cs.null, 0 }, { "he3","he3op",_f0, 3, tx_print_nul, cm_get_heater_output, set_ro, (float *)&cs.null, 0 }, { "he3","he3tr",_f0, 3, tx_print_nul, cm_get_thermistor_resistance, set_ro, (float *)&cs.null, 0 }, + { "he3","he3tv",_f0, 6, tx_print_nul, cm_get_thermistor_voltage, set_ro, (float *)&cs.null, 0 }, { "he3","he3at",_f0, 0, tx_print_nul, cm_get_at_temperature, set_ro, (float *)&cs.null, 0 }, { "he3","he3an",_f0, 0, tx_print_nul, cm_get_heater_adc, set_ro, (float *)&cs.null, 0 }, { "he3","he3fp",_f0, 1, tx_print_nul, cm_get_fan_power, cm_set_fan_power, (float *)&cs.null, 0 }, diff --git a/g2core/settings/settings_Printrbot_Play.h b/g2core/settings/settings_Printrbot_Play.h index 09d996ef0..19695b5ad 100644 --- a/g2core/settings/settings_Printrbot_Play.h +++ b/g2core/settings/settings_Printrbot_Play.h @@ -236,6 +236,50 @@ //*** Input / output settings *** + +//** Temperature Sensors ** + +#define HAS_TEMPERATURE_SENSOR_1 true +#if HAS_TEMPERATURE_SENSOR_1 +// Must choose Thermistor or PT100 + +#define TEMPERATURE_SENSOR_1_TYPE Thermistor +#define TEMPERATURE_SENSOR_1_INIT { \ +/*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ +/*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ +} + +//#define TEMPERATURE_SENSOR_1_TYPE PT100 +//#define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} +#endif + +#define HAS_TEMPERATURE_SENSOR_2 true +#if HAS_TEMPERATURE_SENSOR_2 +#define TEMPERATURE_SENSOR_2_TYPE Thermistor +#define TEMPERATURE_SENSOR_2_INIT { \ +/*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ +/*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ +} + +//#define TEMPERATURE_SENSOR_2_TYPE PT100 +//#define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} +#endif + +#define HAS_TEMPERATURE_SENSOR_3 true +#if HAS_TEMPERATURE_SENSOR_3 +#define TEMPERATURE_SENSOR_3_TYPE Thermistor +#define TEMPERATURE_SENSOR_3_INIT { \ +/*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ +/*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ +} + +//#define TEMPERATURE_SENSOR_3_TYPE PT100 +//#define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} +#endif + + +//** Digital Inputs ** + /* IO_MODE_DISABLED IO_ACTIVE_LOW aka NORMALLY_OPEN diff --git a/g2core/settings/settings_Printrbot_Plus.h b/g2core/settings/settings_Printrbot_Plus.h index 4ca7db276..3a8d577c9 100644 --- a/g2core/settings/settings_Printrbot_Plus.h +++ b/g2core/settings/settings_Printrbot_Plus.h @@ -245,6 +245,50 @@ #define A_JERK_HIGH_SPEED A_JERK_MAX //*** Input / output settings *** + +//** Temperature Sensors ** + +#define HAS_TEMPERATURE_SENSOR_1 true +#if HAS_TEMPERATURE_SENSOR_1 +// Must choose Thermistor or PT100 + +#define TEMPERATURE_SENSOR_1_TYPE Thermistor +#define TEMPERATURE_SENSOR_1_INIT { \ +/*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ +/*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ +} + +//#define TEMPERATURE_SENSOR_1_TYPE PT100 +//#define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} +#endif + +#define HAS_TEMPERATURE_SENSOR_2 true +#if HAS_TEMPERATURE_SENSOR_2 +#define TEMPERATURE_SENSOR_2_TYPE Thermistor +#define TEMPERATURE_SENSOR_2_INIT { \ +/*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ +/*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ +} + +//#define TEMPERATURE_SENSOR_2_TYPE PT100 +//#define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} +#endif + +#define HAS_TEMPERATURE_SENSOR_3 true +#if HAS_TEMPERATURE_SENSOR_3 +#define TEMPERATURE_SENSOR_3_TYPE Thermistor +#define TEMPERATURE_SENSOR_3_INIT { \ +/*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ +/*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ +} + +//#define TEMPERATURE_SENSOR_3_TYPE PT100 +//#define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} +#endif + + +//** Digital Inputs ** + /* IO_MODE_DISABLED IO_ACTIVE_LOW aka NORMALLY_OPEN diff --git a/g2core/settings/settings_Printrbot_Simple_1403.h b/g2core/settings/settings_Printrbot_Simple_1403.h index c32c4739c..8ee77df25 100644 --- a/g2core/settings/settings_Printrbot_Simple_1403.h +++ b/g2core/settings/settings_Printrbot_Simple_1403.h @@ -233,6 +233,50 @@ //*** Input / output settings *** + +//** Temperature Sensors ** + +#define HAS_TEMPERATURE_SENSOR_1 true +#if HAS_TEMPERATURE_SENSOR_1 +// Must choose Thermistor or PT100 + +#define TEMPERATURE_SENSOR_1_TYPE Thermistor +#define TEMPERATURE_SENSOR_1_INIT { \ +/*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ +/*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ +} + +//#define TEMPERATURE_SENSOR_1_TYPE PT100 +//#define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} +#endif + +#define HAS_TEMPERATURE_SENSOR_2 true +#if HAS_TEMPERATURE_SENSOR_2 +#define TEMPERATURE_SENSOR_2_TYPE Thermistor +#define TEMPERATURE_SENSOR_2_INIT { \ +/*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ +/*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ +} + +//#define TEMPERATURE_SENSOR_2_TYPE PT100 +//#define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} +#endif + +#define HAS_TEMPERATURE_SENSOR_3 true +#if HAS_TEMPERATURE_SENSOR_3 +#define TEMPERATURE_SENSOR_3_TYPE Thermistor +#define TEMPERATURE_SENSOR_3_INIT { \ +/*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ +/*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ +} + +//#define TEMPERATURE_SENSOR_3_TYPE PT100 +//#define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} +#endif + + +//** Digital Inputs ** + /* IO_MODE_DISABLED IO_ACTIVE_LOW aka NORMALLY_OPEN diff --git a/g2core/settings/settings_Printrbot_Simple_1608.h b/g2core/settings/settings_Printrbot_Simple_1608.h index a24510b6d..0a568aa87 100644 --- a/g2core/settings/settings_Printrbot_Simple_1608.h +++ b/g2core/settings/settings_Printrbot_Simple_1608.h @@ -241,6 +241,50 @@ //*** Input / output settings *** + +//** Temperature Sensors ** + +#define HAS_TEMPERATURE_SENSOR_1 true +#if HAS_TEMPERATURE_SENSOR_1 +// Must choose Thermistor or PT100 + +#define TEMPERATURE_SENSOR_1_TYPE Thermistor +#define TEMPERATURE_SENSOR_1_INIT { \ + /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ + /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ +} + +//#define TEMPERATURE_SENSOR_1_TYPE PT100 +//#define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} +#endif + +#define HAS_TEMPERATURE_SENSOR_2 true +#if HAS_TEMPERATURE_SENSOR_2 +#define TEMPERATURE_SENSOR_2_TYPE Thermistor +#define TEMPERATURE_SENSOR_2_INIT { \ + /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ + /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ +} + +//#define TEMPERATURE_SENSOR_2_TYPE PT100 +//#define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} +#endif + +#define HAS_TEMPERATURE_SENSOR_3 true +#if HAS_TEMPERATURE_SENSOR_3 +#define TEMPERATURE_SENSOR_3_TYPE Thermistor +#define TEMPERATURE_SENSOR_3_INIT { \ + /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ + /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ +} + +//#define TEMPERATURE_SENSOR_3_TYPE PT100 +//#define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} +#endif + + +//** Digital Inputs ** + /* IO_MODE_DISABLED IO_ACTIVE_LOW aka NORMALLY_OPEN diff --git a/g2core/temperature.cpp b/g2core/temperature.cpp index 221b7e035..d820e774a 100755 --- a/g2core/temperature.cpp +++ b/g2core/temperature.cpp @@ -42,6 +42,15 @@ /**** Local safety/limit settings ****/ +#ifndef HAS_TEMPERATURE_SENSOR_1 +#define HAS_TEMPERATURE_SENSOR_1 false +#endif +#ifndef HAS_TEMPERATURE_SENSOR_2 +#define HAS_TEMPERATURE_SENSOR_2 false +#endif +#ifndef HAS_TEMPERATURE_SENSOR_3 +#define HAS_TEMPERATURE_SENSOR_3 false +#endif // These could be moved to settings // If the temperature stays at set_point +- TEMP_SETPOINT_HYSTERESIS for more @@ -103,23 +112,40 @@ using namespace Motate; // Luckily, we only use boards that are 3.3V logic at the moment. const float kSystemVoltage = 3.3; +// This may be used as a base class in the future, but for now it's just a dummy sensor +struct TemperatureSensor { + TemperatureSensor() {} + + float temperature_exact() { + return -1; // invalid temperature + }; + + float get_resistance() { + return -1; // invalid temperature from a thermistor + }; + + float get_voltage() { + return -1; + } +}; -template +template struct Thermistor { - float c1, c2, c3, pullup_resistance, inline_resistance; + float c1, c2, c3, pullup_resistance; // We'll pull adc top value from the adc_pin.getTop() ADCPin adc_pin {kNormal, [&]{this->adc_has_new_value();} }; uint16_t raw_adc_value = 0; + float raw_adc_voltage = 0.0; - typedef Thermistor type; + typedef Thermistor type; // References for thermistor formulas: // http://assets.newport.com/webDocuments-EN/images/AN04_Thermistor_Calibration_IX.PDF // http://hydraraptor.blogspot.com/2012/11/more-accurate-thermistor-tables.html - Thermistor(const float temp_low, const float temp_med, const float temp_high, const float res_low, const float res_med, const float res_high, const float pullup_resistance_, const float inline_resistance_ = 0) - : pullup_resistance{ pullup_resistance_ }, inline_resistance { inline_resistance_ } { + Thermistor(const float temp_low, const float temp_med, const float temp_high, const float res_low, const float res_med, const float res_high, const float pullup_resistance_) + : pullup_resistance{ pullup_resistance_ } { setup(temp_low, temp_med, temp_high, res_low, res_med, res_high); adc_pin.setInterrupts(kPinInterruptOnChange|kInterruptPriorityLow); } @@ -146,31 +172,16 @@ struct Thermistor { c3 = (x-z*w/y)/(v-z*u/y); c2 = (x-c3*v)/z; c1 = 1/temp_low_fixed-c3*pow(a1,3)-c2*a1; - - // int16_t temp = min_temp; - // for (int i=0; temp < max_temp && i < table_size; i++) { - // lookup_table[i][0] = adc_value(temp); - // lookup_table[i][0] = temp; - // - // temp += (min_temp-max_temp)/(table_size-1); - // } }; -// uint16_t adc_value_(int16_t temp) { -// float y = (c1 - (1/(temp+273.15))) / (2*c3); -// float x = sqrt(pow(c2 / (3*c3),3) + pow(y,2)); -// float r = exp((x-y) - (x+y)); // resistance of thermistor -// return (r / (pullup_resistance + r)) * (adc_pin.getTop()); -// }; - float temperature_exact() { // Sanity check: if (raw_adc_value < 1) { return -1; // invalid temperature from a thermistor } - float v = (float)raw_adc_value * kSystemVoltage / (adc_pin.getTop()); // convert the 10 bit ADC value to a voltage - float r = ((pullup_resistance * v) / (kSystemVoltage - v)) - inline_resistance; // resistance of thermistor + float v = raw_adc_voltage; // convert the ADC value to a voltage + float r = ((pullup_resistance * v) / (kSystemVoltage - v)); // resistance of thermistor if ((r < 0) || (r > TEMP_MIN_DISCONNECTED_RESISTANCE)) { return -1; @@ -186,61 +197,98 @@ struct Thermistor { return -1; // invalid temperature from a thermistor } - float v = (float)raw_adc_value * kSystemVoltage / (adc_pin.getTop()); // convert the 10 bit ADC value to a voltage - return ((pullup_resistance * v) / (kSystemVoltage - v)) - inline_resistance; // resistance of thermistor + float v = raw_adc_voltage; // convert the ADC value to a voltage + return ((pullup_resistance * v) / (kSystemVoltage - v)); // resistance of thermistor + }; + + float get_voltage() { + return raw_adc_voltage; } // Call back function from the ADC to tell it that the ADC has a new sample... void adc_has_new_value() { + raw_adc_voltage = (raw_adc_voltage * 2.0 + adc_pin.getVoltage())/3.0; raw_adc_value = (adc_pin.getRaw() + (9 * raw_adc_value))/10; }; }; + +template +struct PT100 { + float pullup_resistance; + float inline_resistance; + + ADCPin adc_pin {kNormal, [&]{this->adc_has_new_value();} }; + float raw_adc_voltage = 0.0; + int32_t raw_adc_value = 0; + + typedef PT100 type; + + PT100(const float pullup_resistance_, const float inline_resistance_) + : pullup_resistance{ pullup_resistance_ }, inline_resistance{ inline_resistance_ } { + adc_pin.setInterrupts(kPinInterruptOnChange|kInterruptPriorityLow); + adc_pin.setVoltageRange(kSystemVoltage, 0.0687, 0.165, 6400.0); + } + + float temperature_exact() { + // Sanity check: + if (raw_adc_voltage < 0.06) { + return -1; // invalid temperature from a thermistor + } + + float v = raw_adc_voltage; + float r = ((pullup_resistance * v) / (kSystemVoltage - v)) - inline_resistance; // resistance of thermistor + + // from https://www.maximintegrated.com/en/app-notes/index.mvp/id/3450 + // run through wolfram as: + // solve R = 100(1 + A*T + B*T^2); A = 3.9083*10^-3; B = -5.775*10^-7 for T + return 3383.81 - (0.287154*sqrt(159861899.0 - 210000.0*r)); + }; + + float get_resistance() { + if (raw_adc_voltage < 0.001) { + return -1; // invalid temperature from a thermistor + } + + float v = raw_adc_voltage; + return ((pullup_resistance * v) / (kSystemVoltage - v)) - inline_resistance; // resistance of thermistor + }; + + float get_voltage() { + return raw_adc_voltage; + } + + // Call back function from the ADC to tell it that the ADC has a new sample... + void adc_has_new_value() { + raw_adc_voltage = (raw_adc_voltage * 2.0 + adc_pin.getVoltage())/3.0; + raw_adc_value = adc_pin.getRaw(); + }; +}; + // Temperature debug string: {sr:{"he1t":t,"he1st":t,"he1at":t, "he1tr":t, "he1op":t}} // PID debug string: {sr:{"he1t":t,"he1st":t,"pid1p":t, "pid1i":t, "pid1d":t, "he1op":t, "line":t, "stat":t}} +#if HAS_TEMPERATURE_SENSOR_1 // Extruder 1 -Thermistor thermistor1 { - /*T1:*/ 20.0, /*T2:*/ 195.0, /*T3:*/ 255.0, - /*R1:*/ 140000.0, /*R2:*/ 593.0, /*R3:*/ 189.0, /*pullup_resistance:*/ 4700, /*inline_resistance:*/ 4700 - }; - -//#if ADC1_AVAILABLE == 1 -//namespace Motate { -//template<> -//void ADCPin::interrupt() { -// thermistor1.adc_has_new_value(); -//}; -//} -//#endif +TEMPERATURE_SENSOR_1_TYPE temperature_sensor_1 TEMPERATURE_SENSOR_1_INIT; +#else +TemperatureSensor temperature_sensor_1; +#endif // Extruder 2 -Thermistor thermistor2 { - /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, - /*R1:*/ 140000.0, /*R2:*/ 490.0, /*R3:*/ 109.0, /*pullup_resistance:*/ 4700, /*inline_resistance:*/ 4700 - }; -//#if ADC2_AVAILABLE == 1 -//namespace Motate { -//template<> -//void ADCPin::interrupt() { -// thermistor2.adc_has_new_value(); -//}; -//} -//#endif +#if HAS_TEMPERATURE_SENSOR_2 +// Extruder 2 +TEMPERATURE_SENSOR_2_TYPE temperature_sensor_2 TEMPERATURE_SENSOR_2_INIT; +#else +TemperatureSensor temperature_sensor_2; +#endif +#if HAS_TEMPERATURE_SENSOR_3 // Heated bed -Thermistor thermistor3 { - /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, - /*R1:*/ 140000.0, /*R2:*/ 490.0, /*R3:*/ 109.0, /*pullup_resistance:*/ 4700, /*inline_resistance:*/ 4700 - }; -//#if ADC0_AVAILABLE == 1 -//namespace Motate { -//template<> -//void ADCPin::interrupt() { -// thermistor3.adc_has_new_value(); -//}; -//} -//#endif +TEMPERATURE_SENSOR_3_TYPE temperature_sensor_3 TEMPERATURE_SENSOR_3_INIT; +#else +TemperatureSensor temperature_sensor_3; +#endif float last_reported_temp1 = 0; // keep track of what we've reported for SR generation float last_reported_temp2 = 0; @@ -251,7 +299,7 @@ float last_reported_temp3 = 0; // DO_1: Extruder1_PWM const int16_t fet_pin1_freq = 100; #if TEMPERATURE_OUTPUT_ON == 1 -PWMOutputPin fet_pin1;// {kPWMPinInverted}; +PWMOutputPin fet_pin1;// {kPWMPinInverted}; #else PWMOutputPin<-1> fet_pin1;// {kPWMPinInverted}; #endif @@ -259,7 +307,7 @@ PWMOutputPin<-1> fet_pin1;// {kPWMPinInverted}; // DO_2: Extruder2_PWM const int16_t fet_pin2_freq = 100; #if TEMPERATURE_OUTPUT_ON == 1 -PWMOutputPin fet_pin2;// {kPWMPinInverted}; +PWMOutputPin fet_pin2;// {kPWMPinInverted}; #else PWMOutputPin<-1> fet_pin2;// {kPWMPinInverted}; #endif @@ -304,9 +352,9 @@ const int16_t temperature_sample_freq = 10; // every fet_pin1_sample_freq interr int16_t temperature_sample_counter = temperature_sample_freq; SysTickEvent adc_tick_event {[&] { if (!--temperature_sample_counter) { - thermistor1.adc_pin.startSampling(); - thermistor2.adc_pin.startSampling(); - thermistor3.adc_pin.startSampling(); + temperature_sensor_1.adc_pin.startSampling(); + temperature_sensor_2.adc_pin.startSampling(); + temperature_sensor_3.adc_pin.startSampling(); temperature_sample_counter = temperature_sample_freq; } }, nullptr}; @@ -546,7 +594,7 @@ stat_t temperature_callback() bool sr_requested = false; if (pid1._enable) { - temp = thermistor1.temperature_exact(); + temp = temperature_sensor_1.temperature_exact(); fet_pin1 = pid1.getNewOutput(temp); if (fabs(temp - last_reported_temp1) > kTempDiffSRTrigger) { @@ -558,7 +606,7 @@ stat_t temperature_callback() heater_fan1.newTemp(temp); if (pid2._enable) { - temp = thermistor2.temperature_exact(); + temp = temperature_sensor_2.temperature_exact(); fet_pin2 = pid2.getNewOutput(temp); if (fabs(temp - last_reported_temp2) > kTempDiffSRTrigger) { @@ -568,7 +616,7 @@ stat_t temperature_callback() } if (pid3._enable) { - temp = thermistor3.temperature_exact(); + temp = temperature_sensor_3.temperature_exact(); fet_pin3 = pid3.getNewOutput(temp); if (fabs(temp - last_reported_temp3) > kTempDiffSRTrigger) { @@ -948,9 +996,9 @@ stat_t cm_get_heater_output(nvObj_t *nv) stat_t cm_get_heater_adc(nvObj_t *nv) { switch(_get_heater_number(nv)) { - case '1': { nv->value = (float)thermistor1.raw_adc_value; break; } - case '2': { nv->value = (float)thermistor2.raw_adc_value; break; } - case '3': { nv->value = (float)thermistor3.raw_adc_value; break; } + case '1': { nv->value = (float)temperature_sensor_1.raw_adc_value; break; } + case '2': { nv->value = (float)temperature_sensor_2.raw_adc_value; break; } + case '3': { nv->value = (float)temperature_sensor_3.raw_adc_value; break; } // Failsafe. We can only get here if we set it up in config_app, but not here. default: { nv->value = 0.0; break; } @@ -967,9 +1015,9 @@ stat_t cm_get_heater_adc(nvObj_t *nv) stat_t cm_get_temperature(nvObj_t *nv) { switch(_get_heater_number(nv)) { - case '1': { nv->value = last_reported_temp1 = thermistor1.temperature_exact(); break; } - case '2': { nv->value = last_reported_temp2 = thermistor2.temperature_exact(); break; } - case '3': { nv->value = last_reported_temp3 = thermistor3.temperature_exact(); break; } + case '1': { nv->value = last_reported_temp1 = temperature_sensor_1.temperature_exact(); break; } + case '2': { nv->value = last_reported_temp2 = temperature_sensor_2.temperature_exact(); break; } + case '3': { nv->value = last_reported_temp3 = temperature_sensor_3.temperature_exact(); break; } // Failsafe. We can only get here if we set it up in config_app, but not here. default: { nv->value = 0.0; break; } @@ -987,9 +1035,28 @@ stat_t cm_get_temperature(nvObj_t *nv) stat_t cm_get_thermistor_resistance(nvObj_t *nv) { switch(_get_heater_number(nv)) { - case '1': { nv->value = thermistor1.get_resistance(); break; } - case '2': { nv->value = thermistor2.get_resistance(); break; } - case '3': { nv->value = thermistor3.get_resistance(); break; } + case '1': { nv->value = temperature_sensor_1.get_resistance(); break; } + case '2': { nv->value = temperature_sensor_2.get_resistance(); break; } + case '3': { nv->value = temperature_sensor_3.get_resistance(); break; } + + // Failsafe. We can only get here if we set it up in config_app, but not here. + default: { nv->value = 0.0; break; } + } + nv->precision = GET_TABLE_WORD(precision); + nv->valuetype = TYPE_FLOAT; + + return (STAT_OK); +} + +/* + * cm_get_thermistor_resistance() - get the current temperature + */ +stat_t cm_get_thermistor_voltage(nvObj_t* nv) +{ + switch(_get_heater_number(nv)) { + case '1': { nv->value = temperature_sensor_1.get_voltage(); break; } + case '2': { nv->value = temperature_sensor_2.get_voltage(); break; } + case '3': { nv->value = temperature_sensor_3.get_voltage(); break; } // Failsafe. We can only get here if we set it up in config_app, but not here. default: { nv->value = 0.0; break; } diff --git a/g2core/temperature.h b/g2core/temperature.h index 0163ce116..670659df3 100755 --- a/g2core/temperature.h +++ b/g2core/temperature.h @@ -64,6 +64,7 @@ stat_t cm_get_heater_output(nvObj_t* nv); stat_t cm_get_heater_adc(nvObj_t* nv); stat_t cm_get_temperature(nvObj_t* nv); stat_t cm_get_thermistor_resistance(nvObj_t* nv); +stat_t cm_get_thermistor_voltage(nvObj_t* nv); /*--- text_mode support functions ---*/ From 54f30619795723fd3fad90eb41b16af3cd95380c Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Tue, 14 Mar 2017 20:51:38 -0500 Subject: [PATCH 042/193] Fix INPUTn_AVAILABLE settings for gquintic-b --- g2core/board/gquintic/gquintic-b-pinout.h | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/g2core/board/gquintic/gquintic-b-pinout.h b/g2core/board/gquintic/gquintic-b-pinout.h index 66c9c1cbc..f20137114 100755 --- a/g2core/board/gquintic/gquintic-b-pinout.h +++ b/g2core/board/gquintic/gquintic-b-pinout.h @@ -70,17 +70,17 @@ // We don't have all of the inputs, so we have to indicate as much: #define INPUT1_AVAILABLE 1 -#define INPUT2_AVAILABLE 0 -#define INPUT3_AVAILABLE 0 +#define INPUT2_AVAILABLE 1 +#define INPUT3_AVAILABLE 1 #define INPUT4_AVAILABLE 1 #define INPUT5_AVAILABLE 1 -#define INPUT6_AVAILABLE 0 -#define INPUT7_AVAILABLE 0 +#define INPUT6_AVAILABLE 1 +#define INPUT7_AVAILABLE 1 #define INPUT8_AVAILABLE 1 -#define INPUT9_AVAILABLE 0 -#define INPUT10_AVAILABLE 0 -#define INPUT11_AVAILABLE 0 -#define INPUT12_AVAILABLE 0 +#define INPUT9_AVAILABLE 1 +#define INPUT10_AVAILABLE 1 +#define INPUT11_AVAILABLE 1 +#define INPUT12_AVAILABLE 1 #define INPUT13_AVAILABLE 0 From c96849c76eb7b115ec9ccc12bf4497d68e1b2ed0 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Tue, 14 Mar 2017 20:52:16 -0500 Subject: [PATCH 043/193] Added CONFIG=Ultimaker2Plus and settings_Ultimaker_2_Plus.h --- g2core/boards.mk | 6 +- g2core/settings/settings_Ultimaker_2_Plus.h | 413 ++++++++++++++++++++ 2 files changed, 416 insertions(+), 3 deletions(-) create mode 100644 g2core/settings/settings_Ultimaker_2_Plus.h diff --git a/g2core/boards.mk b/g2core/boards.mk index 222ddf679..5b2b7c66a 100644 --- a/g2core/boards.mk +++ b/g2core/boards.mk @@ -130,11 +130,11 @@ endif ########## # Ultimaker configs: -ifeq ("$(CONFIG)","Ultimakerv9k") +ifeq ("$(CONFIG)","Ultimaker2Plus") ifeq ("$(BOARD)","NONE") - BOARD=g2v9k + BOARD=gquintic-b endif - SETTINGS_FILE="settings_ultimaker.h" + SETTINGS_FILE="settings_Ultimaker_2_Plus.h" endif ########## diff --git a/g2core/settings/settings_Ultimaker_2_Plus.h b/g2core/settings/settings_Ultimaker_2_Plus.h new file mode 100644 index 000000000..59f295848 --- /dev/null +++ b/g2core/settings/settings_Ultimaker_2_Plus.h @@ -0,0 +1,413 @@ +/* + * settings_printrbot_simple_1608.h - New Simple, 2016 version + * This file is part of the the g2core project + * + * Copyright (c) 2010 - 2016 Alden S. Hart, Jr. + * Copyright (c) 2010 - 2016 Robert Giseburt + * + * This file ("the software") is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License, version 2 as published by the + * Free Software Foundation. You should have received a copy of the GNU General Public + * License, version 2 along with the software. If not, see . + * + * As a special exception, you may use this file as part of a software library without + * restriction. Specifically, if other files instantiate templates or use macros or + * inline functions from this file, or you compile this file and link it with other + * files to produce an executable, this file does not by itself cause the resulting + * executable to be covered by the GNU General Public License. This exception does not + * however invalidate any other reasons why the executable file might be covered by the + * GNU General Public License. + * + * THE SOFTWARE IS DISTRIBUTED IN THE HOPE THAT IT WILL BE USEFUL, BUT WITHOUT ANY + * WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES + * OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT + * SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF + * OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + */ + +/***********************************************************************/ +/**** Printrbot Simple profile *******************************************/ +/***********************************************************************/ + +// ***> NOTE: The init message must be a single line with no CRs or LFs +#define INIT_MESSAGE "Initializing configs to Ultimaker 2+ profile" + +#ifndef PI +#define PI 3.14159628 +#endif + +//**** GLOBAL / GENERAL SETTINGS ****************************************************** + +#define JUNCTION_INTEGRATION_TIME 1.15 // cornering - between 0.10 and 2.00 (higher is faster) +#define CHORDAL_TOLERANCE 0.01 // chordal accuracy for arc drawing (in mm) + +#define SOFT_LIMIT_ENABLE 0 // 0=off, 1=on +#define HARD_LIMIT_ENABLE 1 // 0=off, 1=on +#define SAFETY_INTERLOCK_ENABLE 1 // 0=off, 1=on + +#define SPINDLE_ENABLE_POLARITY 1 // 0=active low, 1=active high +#define SPINDLE_DIR_POLARITY 0 // 0=clockwise is low, 1=clockwise is high +#define SPINDLE_PAUSE_ON_HOLD true +#define SPINDLE_DWELL_TIME 1.0 + +#define COOLANT_MIST_POLARITY 1 // 0=active low, 1=active high +#define COOLANT_FLOOD_POLARITY 1 // 0=active low, 1=active high +#define COOLANT_PAUSE_ON_HOLD false + +// Communications and reporting settings + +#define COMM_MODE JSON_MODE // one of: TEXT_MODE, JSON_MODE +#define XIO_ENABLE_FLOW_CONTROL FLOW_CONTROL_RTS // FLOW_CONTROL_OFF, FLOW_CONTROL_RTS +#define XIO_UART_MUTES_WHEN_USB_CONNECTED 1 // Mute the UART when USB connects + +#define TEXT_VERBOSITY TV_VERBOSE // one of: TV_SILENT, TV_VERBOSE +#define JSON_VERBOSITY JV_LINENUM // one of: JV_SILENT, JV_FOOTER, JV_CONFIGS, JV_MESSAGES, JV_LINENUM, JV_VERBOSE +#define QUEUE_REPORT_VERBOSITY QR_OFF // one of: QR_OFF, QR_SINGLE, QR_TRIPLE + +#define STATUS_REPORT_VERBOSITY SR_FILTERED // one of: SR_OFF, SR_FILTERED, SR_VERBOSE +#define STATUS_REPORT_MIN_MS 100 // milliseconds - enforces a viable minimum +#define STATUS_REPORT_INTERVAL_MS 250 // milliseconds - set $SV=0 to disable + +// Defaults for 3DP +//#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","vel","he1t","he1st","he1at","feed","unit","path","stat" +// There are no heater two or three, but these would show those: ,"he2t","he2st","he2at","he3t","he3st","he3at" + +// Defaults for motion debugging +//#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","he1t","he1st","he1at","he2t","he2st","he2at","he3t","he3st","he3at","_fe5","_fe4","feed","vel","unit","path","stat" + +// Defaults for PID tuning +//#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","he1t","he1st","he1at","he1op","pid1p","pid1i","pid1d","feed","vel","unit","path","stat" + +// Defaults for thermistor tuning +#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","he1t","he1st","he1at","he1tr","he1tv","he1op","he2t","he2st","he2at","he2tr","he2tv","he1op","he3t","he3st","he3at","he3tr","he3tv","he1op","feed","vel","unit","path","stat" + +// Gcode startup defaults +#define GCODE_DEFAULT_UNITS MILLIMETERS // MILLIMETERS or INCHES +#define GCODE_DEFAULT_PLANE CANON_PLANE_XY // CANON_PLANE_XY, CANON_PLANE_XZ, or CANON_PLANE_YZ +#define GCODE_DEFAULT_COORD_SYSTEM G54 // G54, G55, G56, G57, G58 or G59 +#define GCODE_DEFAULT_PATH_CONTROL PATH_CONTINUOUS +#define GCODE_DEFAULT_DISTANCE_MODE ABSOLUTE_DISTANCE_MODE + + +// *** motor settings ************************************************************************************ + +#define MOTOR_POWER_TIMEOUT 30 // don't disable motors (without an explicit {md:0}) for 30 seconds + +#define MOTOR_POWER_MODE MOTOR_POWERED_IN_CYCLE // default motor power mode (see cmMotorPowerMode in stepper.h) +// 80 steps/mm at 1/16 microstepping = 40 mm/rev +#define M1_MOTOR_MAP AXIS_X // 1ma +#define M1_STEP_ANGLE 1.8 // 1sa +// Marlin says 80 steps/unit, and 16 microsteps, with a 200-step/rev motor +#define M1_TRAVEL_PER_REV 40 // 1tr +#define M1_MICROSTEPS 32 // 1mi 1,2,4,8,16,32 +#define M1_POLARITY 0 // 1po 0=normal, 1=reversed +#define M1_POWER_MODE MOTOR_POWER_MODE // 1pm standard +#define M1_POWER_LEVEL 0.9 // 1mp + +// 80 steps/mm at 1/16 microstepping = 40 mm/rev +#define M2_MOTOR_MAP AXIS_Y +#define M2_STEP_ANGLE 1.8 +// Marlin says 80 steps/unit, and 16 microsteps, with a 200-step/rev motor +#define M2_TRAVEL_PER_REV 40 +#define M2_MICROSTEPS 32 +#define M2_POLARITY 0 +#define M2_POWER_MODE MOTOR_POWER_MODE +#define M2_POWER_LEVEL 0.9 + +#define M3_MOTOR_MAP AXIS_Z +#define M3_STEP_ANGLE 1.8 +// Marlin says 200 steps/unit, and 8 microsteps, with a 200-step/rev motor +#define M3_TRAVEL_PER_REV 8 +#define M3_MICROSTEPS 32 +#define M3_POLARITY 0 +#define M3_POWER_MODE MOTOR_POWER_MODE +#define M3_POWER_LEVEL 0.9 + +#define M4_MOTOR_MAP AXIS_A +#define M4_STEP_ANGLE 1.8 +#define M4_TRAVEL_PER_REV 360 // degrees moved per motor rev +#define M4_MICROSTEPS 32 +#define M4_POLARITY 1 +#define M4_POWER_MODE MOTOR_POWER_MODE +#define M4_POWER_LEVEL 0.9 + +// 96 steps/mm at 1/16 microstepping = 33.3333 mm/rev +#define M5_MOTOR_MAP AXIS_B +#define M5_STEP_ANGLE 1.8 +#define M5_TRAVEL_PER_REV 360 // degrees moved per motor rev +#define M5_MICROSTEPS 32 +#define M5_POLARITY 0 +#define M5_POWER_MODE MOTOR_POWER_MODE +#define M5_POWER_LEVEL 0.3 + +// *** axis settings ********************************************************************************** + +#define X_AXIS_MODE AXIS_STANDARD // xam see canonical_machine.h cmAxisMode for valid values +#define X_VELOCITY_MAX 15000 // xvm G0 max velocity in mm/min +#define X_FEEDRATE_MAX X_VELOCITY_MAX // xfr G1 max feed rate in mm/min +#define X_TRAVEL_MIN 0 // xtn minimum travel - used by soft limits and homing +#define X_TRAVEL_MAX 230 // xtm travel between switches or crashes +#define X_JERK_MAX 6000 // xjm yes, that's "100 billion" mm/(min^3) +#define X_JERK_HIGH_SPEED 6000 // xjh +#define X_HOMING_INPUT 1 // xhi input used for homing or 0 to disable +#define X_HOMING_DIRECTION 0 // xhd 0=search moves negative, 1= search moves positive +#define X_SEARCH_VELOCITY 2500 // xsv move in negative direction +#define X_LATCH_VELOCITY 200 // xlv mm/min +#define X_LATCH_BACKOFF 5 // xlb mm +#define X_ZERO_BACKOFF 0.5 // xzb mm + +#define Y_AXIS_MODE AXIS_STANDARD +#define Y_VELOCITY_MAX 15000 +#define Y_FEEDRATE_MAX Y_VELOCITY_MAX +#define Y_TRAVEL_MIN 0 +#define Y_TRAVEL_MAX 224.5 +#define Y_JERK_MAX 6000 +#define Y_JERK_HIGH_SPEED 6000 +#define Y_HOMING_INPUT 3 +#define Y_HOMING_DIRECTION 0 +#define Y_SEARCH_VELOCITY 3000 +#define Y_LATCH_VELOCITY 200 +#define Y_LATCH_BACKOFF 5 +#define Y_ZERO_BACKOFF 0.5 + +#define Z_AXIS_MODE AXIS_STANDARD +#define Z_VELOCITY_MAX 2000 +#define Z_FEEDRATE_MAX Z_VELOCITY_MAX +#define Z_TRAVEL_MIN 0 +#define Z_TRAVEL_MAX 230 +#define Z_JERK_MAX 1500 +#define Z_JERK_HIGH_SPEED 3000 +#define Z_HOMING_INPUT 6 +#define Z_HOMING_DIRECTION 1 +#define Z_SEARCH_VELOCITY 300 +#define Z_LATCH_VELOCITY 100 +#define Z_LATCH_BACKOFF 2 +#define Z_ZERO_BACKOFF 0 + +// Rotary values are chosen to make the motor react the same as X for testing +/*************************************************************************************** + * To calculate the speeds here, in Wolfram Alpha-speak: + * + * c=2*pi*r, r=0.609, d=c/360, s=((S*60)/d), S=40 for s + * c=2*pi*r, r=4.28394, d=c/360, s=((S*60)/d), S=40 for s + * + * Change r to A_RADIUS, and S to the desired speed, in mm/s or mm/s/s/s. + * + * It will return s= as the value you want to enter. + * + * If the value is over 1 million, the code will divide it by 1 million, + * so you have to pre-multiply it by 1000000.0. (The value is in millions, btw.) + * + * Note that you need these to be floating point values, so always have a .0 at the end! + * + ***************************************************************************************/ + +#define A_AXIS_MODE AXIS_RADIUS +// Marlin says 282 steps/unit, and 8 microsteps, with a 200-step/rev motor = 5.6737588652 mm/rev circumference +// Which yields a radius of 0.9030067693 +#define A_RADIUS 0.9030067693 +//#define A_VELOCITY_MAX 25920.0 // ~40 mm/s, 2,400 mm/min +//#define A_FEEDRATE_MAX 25920.0/2.0 // ~20 mm/s, 1,200 mm/min +#define A_VELOCITY_MAX 77760.0 // G0 rate ~120 mm/s, 2,400 mm/min +#define A_FEEDRATE_MAX 16050 // ~10 mm/s +//#define A_FEEDRATE_MAX 9720.0 // 9720.0 = G1 rate ~15 mm/s, 900 mm/min +#define A_TRAVEL_MIN 0 +#define A_TRAVEL_MAX 10 +//#define A_JERK_MAX 81000 // 250 million mm/min^3 = 324000 +#define A_JERK_MAX 162000 // 250 million mm/min^3 = 324000 +//#define A_JERK_MAX 324000 // 500 million mm/min^3 = 324000 +//#define A_JERK_MAX 648000 // 1,000 million mm/min^3 = 648000 +// * a million IF it's over a million +// c=2*pi*r, r=5.30516476972984, d=c/360, s=((1000*60)/d) +#define A_HOMING_INPUT 0 +#define A_HOMING_DIRECTION 0 +#define A_SEARCH_VELOCITY 2000 +#define A_LATCH_VELOCITY 2000 +#define A_LATCH_BACKOFF 5 +#define A_ZERO_BACKOFF 2 +#define A_JERK_HIGH_SPEED A_JERK_MAX + +#define B_AXIS_MODE AXIS_DISABLED +#define B_RADIUS 0.9030067693 +//#define B_VELOCITY_MAX 25920.0 // ~40 mm/s, 2,400 mm/min +//#define B_FEEDRATE_MAX 25920.0/2.0 // ~20 mm/s, 1,200 mm/min +#define B_VELOCITY_MAX 77760.0 // G0 rate ~120 mm/s, 2,400 mm/min +#define B_FEEDRATE_MAX 16050 // ~10 mm/s +//#define B_FEEDRATE_MAX 9720.0 // 9720.0 = G1 rate ~15 mm/s, 900 mm/min +#define B_TRAVEL_MIN 0 +#define B_TRAVEL_MAX 10 +//#define B_JERK_MAX 81000 // 250 million mm/min^3 = 324000 +#define B_JERK_MAX 162000 // 250 million mm/min^3 = 324000 +//#define B_JERK_MAX 324000 // 500 million mm/min^3 = 324000 +//#define B_JERK_MAX 648000 // 1,000 million mm/min^3 = 648000 +// * a million IF it's over a million +// c=2*pi*r, r=5.30516476972984, d=c/360, s=((1000*60)/d) +#define B_HOMING_INPUT 0 +#define B_HOMING_DIRECTION 0 +#define B_SEARCH_VELOCITY 2000 +#define B_LATCH_VELOCITY 2000 +#define B_LATCH_BACKOFF 5 +#define B_ZERO_BACKOFF 2 +#define B_JERK_HIGH_SPEED B_JERK_MAX + + +//*** Input / output settings *** + +//** Temperature Sensors ** + +#define HAS_TEMPERATURE_SENSOR_1 true +#if HAS_TEMPERATURE_SENSOR_1 +// Must choose Thermistor or PT100 + +//#define TEMPERATURE_SENSOR_1_TYPE Thermistor +//#define TEMPERATURE_SENSOR_1_INIT { \ +// /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ +// /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ +//} + +#define TEMPERATURE_SENSOR_1_TYPE PT100 +#define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} +#endif + +#define HAS_TEMPERATURE_SENSOR_2 true +#if HAS_TEMPERATURE_SENSOR_2 +#define TEMPERATURE_SENSOR_2_TYPE Thermistor +#define TEMPERATURE_SENSOR_2_INIT { \ +/*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ +/*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ +} + +//#define TEMPERATURE_SENSOR_2_TYPE PT100 +//#define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} +#endif + +#define HAS_TEMPERATURE_SENSOR_3 true +#if HAS_TEMPERATURE_SENSOR_3 +#define TEMPERATURE_SENSOR_3_TYPE Thermistor +#define TEMPERATURE_SENSOR_3_INIT { \ +/*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ +/*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ +} + +//#define TEMPERATURE_SENSOR_3_TYPE PT100 +//#define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} +#endif + + +//** Digital Inputs ** +/* + IO_MODE_DISABLED + IO_ACTIVE_LOW aka NORMALLY_OPEN + IO_ACTIVE_HIGH aka NORMALLY_CLOSED + + INPUT_ACTION_NONE + INPUT_ACTION_STOP + INPUT_ACTION_FAST_STOP + INPUT_ACTION_HALT + INPUT_ACTION_RESET + + INPUT_FUNCTION_NONE + INPUT_FUNCTION_LIMIT + INPUT_FUNCTION_INTERLOCK + INPUT_FUNCTION_SHUTDOWN + INPUT_FUNCTION_PANIC + */ +// Inputs are defined for the g2ref(a) board +// Xmn (board label) +#define DI1_MODE IO_ACTIVE_LOW +#define DI1_ACTION INPUT_ACTION_NONE +#define DI1_FUNCTION INPUT_FUNCTION_NONE + +// Xmax +#define DI2_MODE IO_MODE_DISABLED +#define DI2_ACTION INPUT_ACTION_NONE +#define DI2_FUNCTION INPUT_FUNCTION_NONE + +// Ymin +#define DI3_MODE IO_ACTIVE_LOW +#define DI3_ACTION INPUT_ACTION_NONE +#define DI3_FUNCTION INPUT_FUNCTION_NONE + +// Ymax +#define DI4_MODE IO_MODE_DISABLED +#define DI4_ACTION INPUT_ACTION_NONE +#define DI4_FUNCTION INPUT_FUNCTION_NONE + +// Zmin +#define DI5_MODE IO_MODE_DISABLED +#define DI5_ACTION INPUT_ACTION_NONE +#define DI5_FUNCTION INPUT_FUNCTION_NONE + +// Zmax +#define DI6_MODE IO_ACTIVE_LOW +#define DI6_ACTION INPUT_ACTION_NONE +#define DI6_FUNCTION INPUT_FUNCTION_NONE + +// Shutdown (Amin on v9 board) +#define DI7_MODE IO_MODE_DISABLED +#define DI7_ACTION INPUT_ACTION_NONE +#define DI7_FUNCTION INPUT_FUNCTION_NONE + +// High Voltage Z Probe In (Amax on v9 board) +#define DI8_MODE IO_ACTIVE_LOW +#define DI8_ACTION INPUT_ACTION_NONE +#define DI8_FUNCTION INPUT_FUNCTION_NONE + +// Hardware interlock input +#define DI9_MODE IO_MODE_DISABLED +#define DI9_ACTION INPUT_ACTION_NONE +#define DI9_FUNCTION INPUT_FUNCTION_NONE + +//Extruder1_PWM +#define DO1_MODE IO_ACTIVE_HIGH + +//Extruder2_PWM +#define DO2_MODE IO_ACTIVE_HIGH + +//Fan1A_PWM +#define DO3_MODE IO_ACTIVE_HIGH + +//Fan1B_PWM +#define DO4_MODE IO_ACTIVE_HIGH + +#define DO5_MODE IO_ACTIVE_HIGH +#define DO6_MODE IO_ACTIVE_HIGH +#define DO7_MODE IO_ACTIVE_HIGH +#define DO8_MODE IO_ACTIVE_HIGH + +//SAFEin (Output) signal +#define DO9_MODE IO_ACTIVE_HIGH + +#define DO10_MODE IO_ACTIVE_HIGH + +//Header Bed FET +#define DO11_MODE IO_ACTIVE_HIGH + +//Indicator_LED +#define DO12_MODE IO_ACTIVE_HIGH + +#define DO13_MODE IO_ACTIVE_HIGH + + +/*** Extruders / Heaters ***/ + +#define MIX_FAN_VALUE 0.4 // (he1fm) at MIN_FAN_TEMP the fan comes on at this spped (0.0-1.0) +#define MAX_FAN_VALUE 0.75 // (he1fp) at MAX_FAN_TEMP the fan is at this spped (0.0-1.0) +#define MIN_FAN_TEMP 50.0 // (he1fl) at this temp the fan starts to ramp up linearly +#define MAX_FAN_TEMP 100.0 // (he1fh) at this temperature the fan is at "full speed" (MAX_FAN_VALUE) + +#define H1_DEFAULT_ENABLE true +#define H1_DEFAULT_P 7.0 +#define H1_DEFAULT_I 0.05 +#define H1_DEFAULT_D 150.0 + +#define H2_DEFAULT_ENABLE false +#define H2_DEFAULT_P 7.0 +#define H2_DEFAULT_I 0.05 +#define H2_DEFAULT_D 150.0 + +#define H3_DEFAULT_ENABLE false +#define H3_DEFAULT_P 9.0 +#define H3_DEFAULT_I 0.12 +#define H3_DEFAULT_D 400.0 From d2c6effb01e3ce1c3edadb5b1b6bdf57fba9c17e Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Tue, 14 Mar 2017 21:18:18 -0500 Subject: [PATCH 044/193] Cleanup configuration of temperature sensors in settings files. --- g2core/settings/settings_Printrbot_Play.h | 61 ++++++++++--------- g2core/settings/settings_Printrbot_Plus.h | 61 ++++++++++--------- .../settings/settings_Printrbot_Simple_1403.h | 61 ++++++++++--------- .../settings/settings_Printrbot_Simple_1608.h | 53 ++++++++-------- g2core/settings/settings_Ultimaker_2_Plus.h | 61 ++++++++++--------- 5 files changed, 161 insertions(+), 136 deletions(-) diff --git a/g2core/settings/settings_Printrbot_Play.h b/g2core/settings/settings_Printrbot_Play.h index 505e8d6cf..0095531ed 100644 --- a/g2core/settings/settings_Printrbot_Play.h +++ b/g2core/settings/settings_Printrbot_Play.h @@ -244,40 +244,45 @@ #define HAS_TEMPERATURE_SENSOR_1 true #if HAS_TEMPERATURE_SENSOR_1 // Must choose Thermistor or PT100 - -#define TEMPERATURE_SENSOR_1_TYPE Thermistor -#define TEMPERATURE_SENSOR_1_INIT { \ -/*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ -/*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ -} - -//#define TEMPERATURE_SENSOR_1_TYPE PT100 -//#define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} -#endif +#if 1 // 1 if a Thermistor, 0 if a PT100 + #define TEMPERATURE_SENSOR_1_TYPE Thermistor + #define TEMPERATURE_SENSOR_1_INIT { \ + /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ + /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ + } +#else + #define TEMPERATURE_SENSOR_1_TYPE PT100 + #define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} +#endif // 0 or 1 +#endif // HAS_TEMPERATURE_SENSOR_1 #define HAS_TEMPERATURE_SENSOR_2 true #if HAS_TEMPERATURE_SENSOR_2 -#define TEMPERATURE_SENSOR_2_TYPE Thermistor -#define TEMPERATURE_SENSOR_2_INIT { \ -/*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ -/*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ -} - -//#define TEMPERATURE_SENSOR_2_TYPE PT100 -//#define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} -#endif +#if 1 // 1 if a Thermistor, 0 if a PT100 + #define TEMPERATURE_SENSOR_2_TYPE Thermistor + #define TEMPERATURE_SENSOR_2_INIT { \ + /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ + /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ + } +#else + #define TEMPERATURE_SENSOR_2_TYPE PT100 + #define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} +#endif // 0 or 1 +#endif // HAS_TEMPERATURE_SENSOR_2 #define HAS_TEMPERATURE_SENSOR_3 true #if HAS_TEMPERATURE_SENSOR_3 -#define TEMPERATURE_SENSOR_3_TYPE Thermistor -#define TEMPERATURE_SENSOR_3_INIT { \ -/*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ -/*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ -} - -//#define TEMPERATURE_SENSOR_3_TYPE PT100 -//#define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} -#endif +#if 1 // 1 if a Thermistor, 0 if a PT100 + #define TEMPERATURE_SENSOR_3_TYPE Thermistor + #define TEMPERATURE_SENSOR_3_INIT { \ + /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ + /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ + } +#else + #define TEMPERATURE_SENSOR_3_TYPE PT100 + #define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} +#endif // 0 or 1 +#endif // HAS_TEMPERATURE_SENSOR_3 //** Digital Inputs ** diff --git a/g2core/settings/settings_Printrbot_Plus.h b/g2core/settings/settings_Printrbot_Plus.h index 2e2641429..aebb8f0ea 100644 --- a/g2core/settings/settings_Printrbot_Plus.h +++ b/g2core/settings/settings_Printrbot_Plus.h @@ -253,40 +253,45 @@ #define HAS_TEMPERATURE_SENSOR_1 true #if HAS_TEMPERATURE_SENSOR_1 // Must choose Thermistor or PT100 - -#define TEMPERATURE_SENSOR_1_TYPE Thermistor -#define TEMPERATURE_SENSOR_1_INIT { \ -/*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ -/*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ -} - -//#define TEMPERATURE_SENSOR_1_TYPE PT100 -//#define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} -#endif +#if 1 // 1 if a Thermistor, 0 if a PT100 + #define TEMPERATURE_SENSOR_1_TYPE Thermistor + #define TEMPERATURE_SENSOR_1_INIT { \ + /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ + /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ + } +#else + #define TEMPERATURE_SENSOR_1_TYPE PT100 + #define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} +#endif // 0 or 1 +#endif // HAS_TEMPERATURE_SENSOR_1 #define HAS_TEMPERATURE_SENSOR_2 true #if HAS_TEMPERATURE_SENSOR_2 -#define TEMPERATURE_SENSOR_2_TYPE Thermistor -#define TEMPERATURE_SENSOR_2_INIT { \ -/*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ -/*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ -} - -//#define TEMPERATURE_SENSOR_2_TYPE PT100 -//#define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} -#endif +#if 1 // 1 if a Thermistor, 0 if a PT100 + #define TEMPERATURE_SENSOR_2_TYPE Thermistor + #define TEMPERATURE_SENSOR_2_INIT { \ + /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ + /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ + } +#else + #define TEMPERATURE_SENSOR_2_TYPE PT100 + #define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} +#endif // 0 or 1 +#endif // HAS_TEMPERATURE_SENSOR_2 #define HAS_TEMPERATURE_SENSOR_3 true #if HAS_TEMPERATURE_SENSOR_3 -#define TEMPERATURE_SENSOR_3_TYPE Thermistor -#define TEMPERATURE_SENSOR_3_INIT { \ -/*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ -/*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ -} - -//#define TEMPERATURE_SENSOR_3_TYPE PT100 -//#define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} -#endif +#if 1 // 1 if a Thermistor, 0 if a PT100 + #define TEMPERATURE_SENSOR_3_TYPE Thermistor + #define TEMPERATURE_SENSOR_3_INIT { \ + /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ + /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ + } +#else + #define TEMPERATURE_SENSOR_3_TYPE PT100 + #define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} +#endif // 0 or 1 +#endif // HAS_TEMPERATURE_SENSOR_3 //** Digital Inputs ** diff --git a/g2core/settings/settings_Printrbot_Simple_1403.h b/g2core/settings/settings_Printrbot_Simple_1403.h index 29cd0afa6..7fb3af61a 100644 --- a/g2core/settings/settings_Printrbot_Simple_1403.h +++ b/g2core/settings/settings_Printrbot_Simple_1403.h @@ -241,40 +241,45 @@ #define HAS_TEMPERATURE_SENSOR_1 true #if HAS_TEMPERATURE_SENSOR_1 // Must choose Thermistor or PT100 - -#define TEMPERATURE_SENSOR_1_TYPE Thermistor -#define TEMPERATURE_SENSOR_1_INIT { \ -/*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ -/*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ -} - -//#define TEMPERATURE_SENSOR_1_TYPE PT100 -//#define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} -#endif +#if 1 // 1 if a Thermistor, 0 if a PT100 + #define TEMPERATURE_SENSOR_1_TYPE Thermistor + #define TEMPERATURE_SENSOR_1_INIT { \ + /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ + /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ + } +#else + #define TEMPERATURE_SENSOR_1_TYPE PT100 + #define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} +#endif // 0 or 1 +#endif // HAS_TEMPERATURE_SENSOR_1 #define HAS_TEMPERATURE_SENSOR_2 true #if HAS_TEMPERATURE_SENSOR_2 -#define TEMPERATURE_SENSOR_2_TYPE Thermistor -#define TEMPERATURE_SENSOR_2_INIT { \ -/*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ -/*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ -} - -//#define TEMPERATURE_SENSOR_2_TYPE PT100 -//#define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} -#endif +#if 1 // 1 if a Thermistor, 0 if a PT100 + #define TEMPERATURE_SENSOR_2_TYPE Thermistor + #define TEMPERATURE_SENSOR_2_INIT { \ + /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ + /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ + } +#else + #define TEMPERATURE_SENSOR_2_TYPE PT100 + #define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} +#endif // 0 or 1 +#endif // HAS_TEMPERATURE_SENSOR_2 #define HAS_TEMPERATURE_SENSOR_3 true #if HAS_TEMPERATURE_SENSOR_3 -#define TEMPERATURE_SENSOR_3_TYPE Thermistor -#define TEMPERATURE_SENSOR_3_INIT { \ -/*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ -/*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ -} - -//#define TEMPERATURE_SENSOR_3_TYPE PT100 -//#define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} -#endif +#if 1 // 1 if a Thermistor, 0 if a PT100 + #define TEMPERATURE_SENSOR_3_TYPE Thermistor + #define TEMPERATURE_SENSOR_3_INIT { \ + /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ + /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ + } +#else + #define TEMPERATURE_SENSOR_3_TYPE PT100 + #define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} +#endif // 0 or 1 +#endif // HAS_TEMPERATURE_SENSOR_3 //** Digital Inputs ** diff --git a/g2core/settings/settings_Printrbot_Simple_1608.h b/g2core/settings/settings_Printrbot_Simple_1608.h index 15c670cff..01695e304 100644 --- a/g2core/settings/settings_Printrbot_Simple_1608.h +++ b/g2core/settings/settings_Printrbot_Simple_1608.h @@ -265,40 +265,45 @@ #define HAS_TEMPERATURE_SENSOR_1 true #if HAS_TEMPERATURE_SENSOR_1 // Must choose Thermistor or PT100 - -#define TEMPERATURE_SENSOR_1_TYPE Thermistor -#define TEMPERATURE_SENSOR_1_INIT { \ - /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ - /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ -} - -//#define TEMPERATURE_SENSOR_1_TYPE PT100 -//#define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} -#endif +#if 1 // 1 if a Thermistor, 0 if a PT100 + #define TEMPERATURE_SENSOR_1_TYPE Thermistor + #define TEMPERATURE_SENSOR_1_INIT { \ + /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ + /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ + } +#else + #define TEMPERATURE_SENSOR_1_TYPE PT100 + #define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} +#endif // 0 or 1 +#endif // HAS_TEMPERATURE_SENSOR_1 #define HAS_TEMPERATURE_SENSOR_2 true #if HAS_TEMPERATURE_SENSOR_2 -#define TEMPERATURE_SENSOR_2_TYPE Thermistor -#define TEMPERATURE_SENSOR_2_INIT { \ +#if 1 // 1 if a Thermistor, 0 if a PT100 + #define TEMPERATURE_SENSOR_2_TYPE Thermistor + #define TEMPERATURE_SENSOR_2_INIT { \ /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ -} - -//#define TEMPERATURE_SENSOR_2_TYPE PT100 -//#define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} -#endif + } +#else + #define TEMPERATURE_SENSOR_2_TYPE PT100 + #define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} +#endif // 0 or 1 +#endif // HAS_TEMPERATURE_SENSOR_2 #define HAS_TEMPERATURE_SENSOR_3 true #if HAS_TEMPERATURE_SENSOR_3 -#define TEMPERATURE_SENSOR_3_TYPE Thermistor -#define TEMPERATURE_SENSOR_3_INIT { \ +#if 1 // 1 if a Thermistor, 0 if a PT100 + #define TEMPERATURE_SENSOR_3_TYPE Thermistor + #define TEMPERATURE_SENSOR_3_INIT { \ /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ -} - -//#define TEMPERATURE_SENSOR_3_TYPE PT100 -//#define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} -#endif + } +#else + #define TEMPERATURE_SENSOR_3_TYPE PT100 + #define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} +#endif // 0 or 1 +#endif // HAS_TEMPERATURE_SENSOR_3 //** Digital Inputs ** diff --git a/g2core/settings/settings_Ultimaker_2_Plus.h b/g2core/settings/settings_Ultimaker_2_Plus.h index 59f295848..0499152ae 100644 --- a/g2core/settings/settings_Ultimaker_2_Plus.h +++ b/g2core/settings/settings_Ultimaker_2_Plus.h @@ -259,40 +259,45 @@ #define HAS_TEMPERATURE_SENSOR_1 true #if HAS_TEMPERATURE_SENSOR_1 // Must choose Thermistor or PT100 - -//#define TEMPERATURE_SENSOR_1_TYPE Thermistor -//#define TEMPERATURE_SENSOR_1_INIT { \ -// /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ -// /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ -//} - -#define TEMPERATURE_SENSOR_1_TYPE PT100 -#define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} -#endif +#if 0 // 1 if a Thermistor, 0 if a PT100 + #define TEMPERATURE_SENSOR_1_TYPE Thermistor + #define TEMPERATURE_SENSOR_1_INIT { \ + /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ + /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ + } +#else + #define TEMPERATURE_SENSOR_1_TYPE PT100 + #define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} +#endif // 0 or 1 +#endif // HAS_TEMPERATURE_SENSOR_1 #define HAS_TEMPERATURE_SENSOR_2 true #if HAS_TEMPERATURE_SENSOR_2 -#define TEMPERATURE_SENSOR_2_TYPE Thermistor -#define TEMPERATURE_SENSOR_2_INIT { \ -/*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ -/*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ -} - -//#define TEMPERATURE_SENSOR_2_TYPE PT100 -//#define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} -#endif +#if 0 // 1 if a Thermistor, 0 if a PT100 + #define TEMPERATURE_SENSOR_2_TYPE Thermistor + #define TEMPERATURE_SENSOR_2_INIT { \ + /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ + /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ + } +#else + #define TEMPERATURE_SENSOR_2_TYPE PT100 + #define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} +#endif // 0 or 1 +#endif // HAS_TEMPERATURE_SENSOR_2 #define HAS_TEMPERATURE_SENSOR_3 true #if HAS_TEMPERATURE_SENSOR_3 -#define TEMPERATURE_SENSOR_3_TYPE Thermistor -#define TEMPERATURE_SENSOR_3_INIT { \ -/*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ -/*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ -} - -//#define TEMPERATURE_SENSOR_3_TYPE PT100 -//#define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} -#endif +#if 0 // 1 if a Thermistor, 0 if a PT100 + #define TEMPERATURE_SENSOR_3_TYPE Thermistor + #define TEMPERATURE_SENSOR_3_INIT { \ + /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ + /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ + } +#else + #define TEMPERATURE_SENSOR_3_TYPE PT100 + #define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} +#endif // 0 or 1 +#endif // HAS_TEMPERATURE_SENSOR_3 //** Digital Inputs ** From d3e980d42f42da8662b86981aaddda286fc5ada8 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Tue, 14 Mar 2017 21:47:04 -0500 Subject: [PATCH 045/193] Restore cm_set_probe and {"prbs":true} that was broken in the merge. --- g2core/cycle_probing.cpp | 62 +++++++++++++++++++++++++++++++--------- 1 file changed, 48 insertions(+), 14 deletions(-) diff --git a/g2core/cycle_probing.cpp b/g2core/cycle_probing.cpp index 5438f8d31..1e49f6af1 100644 --- a/g2core/cycle_probing.cpp +++ b/g2core/cycle_probing.cpp @@ -73,6 +73,50 @@ static stat_t _probing_exception_exit(stat_t status); static stat_t _probe_move(const float target[], const bool flags[]); static void _send_probe_report(void); +void _prepare_for_probe(); +void _store_probe_position(); + +/**** JSON INTERFACE ******************************************************************* + * cm_set_probe() - a command to tell it to store the current point as a probe point + */ + +stat_t cm_set_probe(nvObj_t *nv) +{ + if (!fp_ZERO(nv->value)) { + nv->valuetype = TYPE_BOOL; + nv->value = true; + + _prepare_for_probe(); + cm.probe_state[0] = PROBE_SUCCEEDED; + _store_probe_position(); + } + return (STAT_OK); +} + + +/**** HELPERS *************************************************************************** + * _prepare_for_probe() - rotate the stored probes in preperation for storing a new probe + * _store_probe_position() - store the position as a finalized probe + */ + +void _prepare_for_probe() { + // if the previous probe succeeded, roll probes to the next position + if (cm.probe_state[0] == PROBE_SUCCEEDED) { + for (uint8_t n = PROBES_STORED - 1; n > 0; n--) { + cm.probe_state[n] = cm.probe_state[n - 1]; + for (uint8_t axis = 0; axis < AXES; axis++) { + cm.probe_results[n][axis] = cm.probe_results[n - 1][axis]; + } + } + } +} + +void _store_probe_position() { + for (uint8_t axis = 0; axis < AXES; axis++) { + cm.probe_results[0][axis] = cm_get_absolute_position(ACTIVE_MODEL, axis); + } +} + // helper static void _motion_end_callback(float* vect, bool* flag) { @@ -159,15 +203,8 @@ uint8_t cm_straight_probe(float target[], bool flags[], bool trip_sense, bool al copy_vector(pb.target, cm.gm.target); // cm_set_model_target() sets target in gm, move it to pb copy_vector(pb.flags, flags); // set axes involved in the move - // if the previous probe succeeded, roll probes to the next position - if (cm.probe_state[0] == PROBE_SUCCEEDED) { - for (uint8_t n = PROBES_STORED - 1; n > 0; n--) { - cm.probe_state[n] = cm.probe_state[n - 1]; - for (uint8_t axis = 0; axis < AXES; axis++) { - cm.probe_results[n][axis] = cm.probe_results[n - 1][axis]; - } - } - } + _prepare_for_probe(); + // clear the old probe results clear_vector(cm.probe_results[0]); // NOTE: relying on cm.probe_results will not detect a probe to 0,0,0. @@ -321,11 +358,8 @@ static stat_t _probing_finish() { _probe_restore_settings(); // cleanup first - // set absolute position in probe results vector - for (uint8_t axis = 0; axis < AXES; axis++) { - cm.probe_results[0][axis] = cm_get_absolute_position(ACTIVE_MODEL, axis); - } - + _store_probe_position(); + // handle failed probes - successful probes already set the flag if (cm.probe_state[0] == PROBE_FAILED) { if (pb.alarm_flag) { From 56f29baabcc26744d9d93914f0e796ee1a0b5234 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Thu, 16 Mar 2017 12:05:17 -0500 Subject: [PATCH 046/193] Rearranged kADCn pin number to start with 1 (except Due). Made extruder and fan pins set in settings file. Updated current settings. --- g2core/board/Archim/Archim-pinout.h | 33 ++++---- g2core/board/ArduinoDue/gShield-pinout.h | 5 -- .../board/ArduinoDue/shopbotShield-pinout.h | 5 -- g2core/board/G2v9/G2v9k-pinout.h | 9 +-- g2core/board/G2v9/motate_pin_assignments.h | 30 ++++---- g2core/board/gquadratic/gquadratic-b-pinout.h | 6 -- .../board/gquadratic/motate_pin_assignments.h | 30 ++++---- g2core/board/gquintic/gquintic-b-pinout.h | 14 +--- .../board/gquintic/motate_pin_assignments.h | 32 ++++---- .../printrboardg2/motate_pin_assignments.h | 30 ++++---- .../printrboardg2/printrboardG2v3-pinout.h | 8 +- g2core/board/sbv300/motate_pin_assignments.h | 66 ++++++++-------- g2core/board/sbv300/sbv300-pinout.h | 5 -- g2core/gpio.h | 4 +- g2core/settings/settings_Printrbot_Play.h | 11 ++- g2core/settings/settings_Printrbot_Plus.h | 10 ++- .../settings/settings_Printrbot_Simple_1403.h | 11 ++- .../settings/settings_Printrbot_Simple_1608.h | 10 ++- g2core/settings/settings_Ultimaker_2_Plus.h | 22 ++++-- g2core/temperature.cpp | 76 ++++++++++++++----- 20 files changed, 222 insertions(+), 195 deletions(-) diff --git a/g2core/board/Archim/Archim-pinout.h b/g2core/board/Archim/Archim-pinout.h index 1d49ac1af..77f61c234 100755 --- a/g2core/board/Archim/Archim-pinout.h +++ b/g2core/board/Archim/Archim-pinout.h @@ -49,11 +49,6 @@ #define INPUT12_AVAILABLE 1 #define INPUT13_AVAILABLE 0 -#define ADC0_AVAILABLE 0 -#define ADC1_AVAILABLE 0 -#define ADC2_AVAILABLE 0 -#define ADC3_AVAILABLE 0 - #define XIO_HAS_USB 1 #define XIO_HAS_UART 1 #define XIO_HAS_SPI 0 @@ -223,21 +218,21 @@ pin_number kOutput14_PinNumber = -1; // 143; pin_number kOutput15_PinNumber = -1; // 144; pin_number kOutput16_PinNumber = -1; // 145; -pin_number kADC0_PinNumber = 11; // Heated bed thermistor ADC -pin_number kADC1_PinNumber = 10; // Extruder1_ADC -pin_number kADC2_PinNumber = 8; // Extruder2_ADC -pin_number kADC3_PinNumber = -1; // 153; -pin_number kADC4_PinNumber = -1; // 154; -pin_number kADC5_PinNumber = -1; // 155; -pin_number kADC6_PinNumber = -1; // 156; -pin_number kADC7_PinNumber = -1; // 157; -pin_number kADC8_PinNumber = -1; // 158; -pin_number kADC9_PinNumber = -1; // 159; -pin_number kADC10_PinNumber = -1; // 160; -pin_number kADC11_PinNumber = -1; // 161; -pin_number kADC12_PinNumber = -1; // 162; -pin_number kADC13_PinNumber = -1; // Not physially pinned out +pin_number kADC1_PinNumber = 11; // Heated bed thermistor ADC +pin_number kADC2_PinNumber = 10; // Extruder1_ADC +pin_number kADC3_PinNumber = 8; // Extruder2_ADC +pin_number kADC4_PinNumber = -1; // 153; +pin_number kADC5_PinNumber = -1; // 154; +pin_number kADC6_PinNumber = -1; // 155; +pin_number kADC7_PinNumber = -1; // 156; +pin_number kADC8_PinNumber = -1; // 157; +pin_number kADC9_PinNumber = -1; // 158; +pin_number kADC10_PinNumber = -1; // 159; +pin_number kADC11_PinNumber = -1; // 160; +pin_number kADC12_PinNumber = -1; // 161; +pin_number kADC13_PinNumber = -1; // 162; pin_number kADC14_PinNumber = -1; // Not physially pinned out +pin_number kADC15_PinNumber = -1; // Not physially pinned out // GRBL / gShield compatibility pins -- Due board ONLY diff --git a/g2core/board/ArduinoDue/gShield-pinout.h b/g2core/board/ArduinoDue/gShield-pinout.h index 314ef41ed..2fd15b5d9 100755 --- a/g2core/board/ArduinoDue/gShield-pinout.h +++ b/g2core/board/ArduinoDue/gShield-pinout.h @@ -54,11 +54,6 @@ #define INPUT12_AVAILABLE 1 #define INPUT13_AVAILABLE 0 -#define ADC0_AVAILABLE 0 -#define ADC1_AVAILABLE 0 -#define ADC2_AVAILABLE 0 -#define ADC3_AVAILABLE 0 - #define XIO_HAS_USB 1 #define XIO_HAS_UART 0 #define XIO_HAS_SPI 0 diff --git a/g2core/board/ArduinoDue/shopbotShield-pinout.h b/g2core/board/ArduinoDue/shopbotShield-pinout.h index b9ba361ea..9b07c9bd3 100755 --- a/g2core/board/ArduinoDue/shopbotShield-pinout.h +++ b/g2core/board/ArduinoDue/shopbotShield-pinout.h @@ -47,11 +47,6 @@ #define INPUT12_AVAILABLE 0 #define INPUT13_AVAILABLE 0 -#define ADC0_AVAILABLE 0 -#define ADC1_AVAILABLE 0 -#define ADC2_AVAILABLE 0 -#define ADC3_AVAILABLE 0 - #define XIO_HAS_USB 1 #define XIO_HAS_UART 0 #define XIO_HAS_SPI 0 diff --git a/g2core/board/G2v9/G2v9k-pinout.h b/g2core/board/G2v9/G2v9k-pinout.h index 71256d3f8..8c89cc8f9 100644 --- a/g2core/board/G2v9/G2v9k-pinout.h +++ b/g2core/board/G2v9/G2v9k-pinout.h @@ -81,11 +81,6 @@ #define INPUT12_AVAILABLE 0 #define INPUT13_AVAILABLE 0 -#define ADC0_AVAILABLE 1 -#define ADC1_AVAILABLE 1 -#define ADC2_AVAILABLE 0 -#define ADC3_AVAILABLE 0 - #define XIO_HAS_USB 1 #define XIO_HAS_UART 0 #define XIO_HAS_SPI 0 @@ -165,8 +160,8 @@ _MAKE_MOTATE_PIN(kSocket1_Microstep_2PinNumber, 'B', 16); // Socket1_Microst _MAKE_MOTATE_PIN(kSocket1_VrefPinNumber, 'B', 17); // Socket1_VrefPinNumber _MAKE_MOTATE_PIN(kSocket2_VrefPinNumber, 'B', 18); // Socket2_VrefPinNumber _MAKE_MOTATE_PIN(kSocket3_VrefPinNumber, 'B', 19); // Socket3_VrefPinNumber -_MAKE_MOTATE_PIN(kADC0_PinNumber, 'B', 20); // Socket2_SPISlaveSelectPinNumber -_MAKE_MOTATE_PIN(kADC1_PinNumber, 'B', 21); // Socket3_SPISlaveSelectPinNumber +_MAKE_MOTATE_PIN(kADC1_PinNumber, 'B', 20); // Socket2_SPISlaveSelectPinNumber +_MAKE_MOTATE_PIN(kADC2_PinNumber, 'B', 21); // Socket3_SPISlaveSelectPinNumber _MAKE_MOTATE_PIN(kSocket4_EnablePinNumber, 'B', 22); // Socket4_EnablePinNumber _MAKE_MOTATE_PIN(kSocket4_SPISlaveSelectPinNumber, 'B', 23); // Socket4_SPISlaveSelectPinNumber _MAKE_MOTATE_PIN(kSocket4_DirPinNumber, 'B', 24); // Socket4_DirPinNumber diff --git a/g2core/board/G2v9/motate_pin_assignments.h b/g2core/board/G2v9/motate_pin_assignments.h index ff1adcd45..2b3450ce2 100644 --- a/g2core/board/G2v9/motate_pin_assignments.h +++ b/g2core/board/G2v9/motate_pin_assignments.h @@ -190,21 +190,21 @@ pin_number kOutput14_PinNumber = -1; // 143; pin_number kOutput15_PinNumber = -1; // 144; pin_number kOutput16_PinNumber = -1; // 145; -pin_number kADC0_PinNumber = 150; // Heated bed thermistor ADC -pin_number kADC1_PinNumber = 151; // Extruder1_ADC -pin_number kADC2_PinNumber = 152; // Extruder2_ADC -pin_number kADC3_PinNumber = -1; // 153; -pin_number kADC4_PinNumber = -1; // 154; -pin_number kADC5_PinNumber = -1; // 155; -pin_number kADC6_PinNumber = -1; // 156; -pin_number kADC7_PinNumber = -1; // 157; -pin_number kADC8_PinNumber = -1; // 158; -pin_number kADC9_PinNumber = -1; // 159; -pin_number kADC10_PinNumber = -1; // 160; -pin_number kADC11_PinNumber = -1; // 161; -pin_number kADC12_PinNumber = -1; // 162; -pin_number kADC13_PinNumber = 163; // Not physially pinned out -pin_number kADC14_PinNumber = 164; // Not physially pinned out +pin_number kADC1_PinNumber = 150; // Heated bed thermistor ADC +pin_number kADC2_PinNumber = 151; // Extruder1_ADC +pin_number kADC3_PinNumber = 152; // Extruder2_ADC +pin_number kADC4_PinNumber = -1; // 153; +pin_number kADC5_PinNumber = -1; // 154; +pin_number kADC6_PinNumber = -1; // 155; +pin_number kADC7_PinNumber = -1; // 156; +pin_number kADC8_PinNumber = -1; // 157; +pin_number kADC9_PinNumber = -1; // 158; +pin_number kADC10_PinNumber = -1; // 159; +pin_number kADC11_PinNumber = -1; // 160; +pin_number kADC12_PinNumber = -1; // 161; +pin_number kADC13_PinNumber = -1; // 162; +pin_number kADC14_PinNumber = 163; // Not physially pinned out +pin_number kADC15_PinNumber = 164; // Not physially pinned out // start next sequence at 170 diff --git a/g2core/board/gquadratic/gquadratic-b-pinout.h b/g2core/board/gquadratic/gquadratic-b-pinout.h index 0eaa3c5d2..6eab01841 100755 --- a/g2core/board/gquadratic/gquadratic-b-pinout.h +++ b/g2core/board/gquadratic/gquadratic-b-pinout.h @@ -83,12 +83,6 @@ #define INPUT12_AVAILABLE 0 #define INPUT13_AVAILABLE 0 - -#define ADC0_AVAILABLE 0 -#define ADC1_AVAILABLE 0 -#define ADC2_AVAILABLE 0 -#define ADC3_AVAILABLE 0 - #define XIO_HAS_USB 1 #define XIO_HAS_UART 1 #define XIO_HAS_SPI 0 diff --git a/g2core/board/gquadratic/motate_pin_assignments.h b/g2core/board/gquadratic/motate_pin_assignments.h index 9cc268e7a..957b7c8d3 100755 --- a/g2core/board/gquadratic/motate_pin_assignments.h +++ b/g2core/board/gquadratic/motate_pin_assignments.h @@ -195,21 +195,21 @@ pin_number kOutput14_PinNumber = -1; // 143; pin_number kOutput15_PinNumber = -1; // 144; pin_number kOutput16_PinNumber = -1; // 145; -pin_number kADC0_PinNumber = 150; // Heated bed thermistor ADC -pin_number kADC1_PinNumber = 151; // Extruder1_ADC -pin_number kADC2_PinNumber = 152; // Extruder2_ADC -pin_number kADC3_PinNumber = 153; // Aux ADC -pin_number kADC4_PinNumber = 154; // Not physically pinned out -pin_number kADC5_PinNumber = 155; // Not physically pinned out -pin_number kADC6_PinNumber = 156; // Not physically pinned out -pin_number kADC7_PinNumber = 157; // Not physically pinned out -pin_number kADC8_PinNumber = 158; // Not physically pinned out -pin_number kADC9_PinNumber = 159; // Not physically pinned out -pin_number kADC10_PinNumber = 160; // Not physically pinned out -pin_number kADC11_PinNumber = 161; // Not physically pinned out -pin_number kADC12_PinNumber = 162; // Not physically pinned out -pin_number kADC13_PinNumber = 163; // Not physically pinned out -pin_number kADC14_PinNumber = 164; // Not physically pinned out +pin_number kADC1_PinNumber = 150; // Heated bed thermistor ADC +pin_number kADC2_PinNumber = 151; // Extruder1_ADC +pin_number kADC3_PinNumber = 152; // Extruder2_ADC +pin_number kADC4_PinNumber = 153; // Aux ADC +pin_number kADC5_PinNumber = 154; // Not physically pinned out +pin_number kADC6_PinNumber = 155; // Not physically pinned out +pin_number kADC7_PinNumber = 156; // Not physically pinned out +pin_number kADC8_PinNumber = 157; // Not physically pinned out +pin_number kADC9_PinNumber = 158; // Not physically pinned out +pin_number kADC10_PinNumber = 159; // Not physically pinned out +pin_number kADC11_PinNumber = 160; // Not physically pinned out +pin_number kADC12_PinNumber = 161; // Not physically pinned out +pin_number kADC13_PinNumber = 162; // Not physically pinned out +pin_number kADC14_PinNumber = 163; // Not physically pinned out +pin_number kADC15_PinNumber = 164; // Not physically pinned out pin_number kExternalClock1_PinNumber = 170; // External pins for exporting a clock signal (for Trinamics) diff --git a/g2core/board/gquintic/gquintic-b-pinout.h b/g2core/board/gquintic/gquintic-b-pinout.h index f20137114..195fd3513 100755 --- a/g2core/board/gquintic/gquintic-b-pinout.h +++ b/g2core/board/gquintic/gquintic-b-pinout.h @@ -83,12 +83,6 @@ #define INPUT12_AVAILABLE 1 #define INPUT13_AVAILABLE 0 - -#define ADC0_AVAILABLE 1 -#define ADC1_AVAILABLE 1 -#define ADC2_AVAILABLE 1 -#define ADC3_AVAILABLE 0 - #define XIO_HAS_USB 1 #define XIO_HAS_UART 1 #define XIO_HAS_SPI 0 @@ -141,10 +135,10 @@ _MAKE_MOTATE_PIN(kOutput8_PinNumber, 'A', 13); // _MAKE_MOTATE_PIN(kSocket1_StepPinNumber, 'A', 14); // _MAKE_MOTATE_PIN(kOutput3_PinNumber, 'A', 15); // _MAKE_MOTATE_PIN(kOutput4_PinNumber, 'A', 16); // -_MAKE_MOTATE_PIN(kADC3_PinNumber, 'A', 17); // -_MAKE_MOTATE_PIN(kADC2_PinNumber, 'A', 18); // -_MAKE_MOTATE_PIN(kADC1_PinNumber, 'A', 19); // -_MAKE_MOTATE_PIN(kADC0_PinNumber, 'A', 20); // +_MAKE_MOTATE_PIN(kADC4_PinNumber, 'A', 17); // +_MAKE_MOTATE_PIN(kADC3_PinNumber, 'A', 18); // +_MAKE_MOTATE_PIN(kADC2_PinNumber, 'A', 19); // +_MAKE_MOTATE_PIN(kADC1_PinNumber, 'A', 20); // _MAKE_MOTATE_PIN(kSerial_CTSPinNumber, 'A', 21); // _MAKE_MOTATE_PIN(kSocket1_EnablePinNumber, 'A', 22); // _MAKE_MOTATE_PIN(kOutput10_PinNumber, 'A', 23); // diff --git a/g2core/board/gquintic/motate_pin_assignments.h b/g2core/board/gquintic/motate_pin_assignments.h index 2a93633aa..30505ad7e 100755 --- a/g2core/board/gquintic/motate_pin_assignments.h +++ b/g2core/board/gquintic/motate_pin_assignments.h @@ -176,7 +176,7 @@ pin_number kGRBL_FeedHoldPinNumber = -1; pin_number kGRBL_CycleStartPinNumber = -1; pin_number kGRBL_CommonEnablePinNumber = -1; - + // g2ref extensions // These first 5 may replace the Spindle and Coolant pins, above pin_number kOutput1_PinNumber = 130; // DO_1: Extruder1_PWM @@ -198,21 +198,21 @@ pin_number kOutput14_PinNumber = -1; // 143; pin_number kOutput15_PinNumber = -1; // 144; pin_number kOutput16_PinNumber = -1; // 145; -pin_number kADC0_PinNumber = 150; // Heated bed thermistor ADC -pin_number kADC1_PinNumber = 151; // Extruder1_ADC -pin_number kADC2_PinNumber = 152; // Extruder2_ADC -pin_number kADC3_PinNumber = 153; // Aux ADC -pin_number kADC4_PinNumber = 154; // Not physically pinned out -pin_number kADC5_PinNumber = 155; // Not physically pinned out -pin_number kADC6_PinNumber = 156; // Not physically pinned out -pin_number kADC7_PinNumber = 157; // Not physically pinned out -pin_number kADC8_PinNumber = 158; // Not physically pinned out -pin_number kADC9_PinNumber = 159; // Not physically pinned out -pin_number kADC10_PinNumber = 160; // Not physically pinned out -pin_number kADC11_PinNumber = 161; // Not physically pinned out -pin_number kADC12_PinNumber = 162; // Not physically pinned out -pin_number kADC13_PinNumber = 163; // Not physically pinned out -pin_number kADC14_PinNumber = 164; // Not physically pinned out +pin_number kADC1_PinNumber = 150; // Heated bed thermistor ADC +pin_number kADC2_PinNumber = 151; // Extruder1_ADC +pin_number kADC3_PinNumber = 152; // Extruder2_ADC +pin_number kADC4_PinNumber = 153; // Aux ADC +pin_number kADC5_PinNumber = 154; // Not physically pinned out +pin_number kADC6_PinNumber = 155; // Not physically pinned out +pin_number kADC7_PinNumber = 156; // Not physically pinned out +pin_number kADC8_PinNumber = 157; // Not physically pinned out +pin_number kADC9_PinNumber = 158; // Not physically pinned out +pin_number kADC10_PinNumber = 159; // Not physically pinned out +pin_number kADC11_PinNumber = 160; // Not physically pinned out +pin_number kADC12_PinNumber = 161; // Not physically pinned out +pin_number kADC13_PinNumber = 162; // Not physically pinned out +pin_number kADC14_PinNumber = 163; // Not physically pinned out +pin_number kADC15_PinNumber = 164; // Not physically pinned out pin_number kExternalClock1_PinNumber = 170; // External pins for exporting a clock signal (for Trinamics) diff --git a/g2core/board/printrboardg2/motate_pin_assignments.h b/g2core/board/printrboardg2/motate_pin_assignments.h index d82bcb268..e90c5e119 100755 --- a/g2core/board/printrboardg2/motate_pin_assignments.h +++ b/g2core/board/printrboardg2/motate_pin_assignments.h @@ -197,21 +197,21 @@ pin_number kOutput14_PinNumber = -1; // 143; pin_number kOutput15_PinNumber = -1; // 144; pin_number kOutput16_PinNumber = -1; // 145; -pin_number kADC0_PinNumber = 150; // Heated bed thermistor ADC -pin_number kADC1_PinNumber = 151; // Extruder1_ADC -pin_number kADC2_PinNumber = 152; // Extruder2_ADC -pin_number kADC3_PinNumber = 153; // Aux ADC -pin_number kADC4_PinNumber = 154; // Not physically pinned out -pin_number kADC5_PinNumber = 155; // Not physically pinned out -pin_number kADC6_PinNumber = 156; // Not physically pinned out -pin_number kADC7_PinNumber = 157; // Not physically pinned out -pin_number kADC8_PinNumber = 158; // Not physically pinned out -pin_number kADC9_PinNumber = 159; // Not physically pinned out -pin_number kADC10_PinNumber = 160; // Not physically pinned out -pin_number kADC11_PinNumber = 161; // Not physically pinned out -pin_number kADC12_PinNumber = 162; // Not physically pinned out -pin_number kADC13_PinNumber = 163; // Not physically pinned out -pin_number kADC14_PinNumber = 164; // Not physically pinned out +pin_number kADC1_PinNumber = 150; // Heated bed thermistor ADC +pin_number kADC2_PinNumber = 151; // Extruder1_ADC +pin_number kADC3_PinNumber = 152; // Extruder2_ADC +pin_number kADC4_PinNumber = 153; // Aux ADC +pin_number kADC5_PinNumber = 154; // Not physically pinned out +pin_number kADC6_PinNumber = 155; // Not physically pinned out +pin_number kADC7_PinNumber = 156; // Not physically pinned out +pin_number kADC8_PinNumber = 157; // Not physically pinned out +pin_number kADC9_PinNumber = 158; // Not physically pinned out +pin_number kADC10_PinNumber = 159; // Not physically pinned out +pin_number kADC11_PinNumber = 160; // Not physically pinned out +pin_number kADC12_PinNumber = 161; // Not physically pinned out +pin_number kADC13_PinNumber = 162; // Not physically pinned out +pin_number kADC14_PinNumber = 163; // Not physically pinned out +pin_number kADC15_PinNumber = 164; // Not physically pinned out // start next sequence at 170 diff --git a/g2core/board/printrboardg2/printrboardG2v3-pinout.h b/g2core/board/printrboardg2/printrboardG2v3-pinout.h index 85df15dbe..386524a8d 100755 --- a/g2core/board/printrboardg2/printrboardG2v3-pinout.h +++ b/g2core/board/printrboardg2/printrboardG2v3-pinout.h @@ -89,12 +89,6 @@ #define INPUT12_AVAILABLE 0 #define INPUT13_AVAILABLE 0 -// BE AWARE: All ADCs set to 1 MUST have a corresponding kADC statement -#define ADC0_AVAILABLE 1 -#define ADC1_AVAILABLE 1 -#define ADC2_AVAILABLE 0 -#define ADC3_AVAILABLE 0 - #define XIO_HAS_USB 1 #define XIO_HAS_UART 1 #define XIO_HAS_SPI 0 @@ -126,7 +120,7 @@ _MAKE_MOTATE_PIN(kUnassigned1, 'A', 0); // nc _MAKE_MOTATE_PIN(kUnassigned2, 'A', 1); // nc _MAKE_MOTATE_PIN(kSocket4_VrefPinNumber, 'A', 2); // M4_Vref _MAKE_MOTATE_PIN(kUnassigned3, 'A', 3); // nc -_MAKE_MOTATE_PIN(kADC0_PinNumber, 'A', 4); // BED_ADC +_MAKE_MOTATE_PIN(kADC3_PinNumber, 'A', 4); // BED_ADC _MAKE_MOTATE_PIN(kOutput1_PinNumber, 'A', 5); // DO_1 (Extruder1_PWM) _MAKE_MOTATE_PIN(kOutput3_PinNumber, 'A', 6); // DO_3 (Fan1B_PWM) _MAKE_MOTATE_PIN(kOutputSAFE_PinNumber, 'A', 7); // DO_9 (SAFE_PULSES - output from MCU) diff --git a/g2core/board/sbv300/motate_pin_assignments.h b/g2core/board/sbv300/motate_pin_assignments.h index de1a5dc7d..a77176a48 100755 --- a/g2core/board/sbv300/motate_pin_assignments.h +++ b/g2core/board/sbv300/motate_pin_assignments.h @@ -174,40 +174,40 @@ pin_number kGRBL_CommonEnablePinNumber = -1; // g2ref extensions // These first 5 may replace the Spindle and Coolant pins, above -pin_number kOutput1_PinNumber = 124; -pin_number kOutput2_PinNumber = 125; -pin_number kOutput3_PinNumber = 126; -pin_number kOutput4_PinNumber = 127; -pin_number kOutput5_PinNumber = 128; - -pin_number kOutput6_PinNumber = 129; -pin_number kOutput7_PinNumber = 130; -pin_number kOutput8_PinNumber = 131; -pin_number kOutput9_PinNumber = 132; -pin_number kOutput10_PinNumber = 133; - -pin_number kOutput11_PinNumber = 134; -pin_number kOutput12_PinNumber = 135; -pin_number kOutput13_PinNumber = -1; -pin_number kOutput14_PinNumber = -1; -pin_number kOutput15_PinNumber = -1; -pin_number kOutput16_PinNumber = -1; - -pin_number kADC0_PinNumber = -1; // Heated bed thermistor ADC -pin_number kADC1_PinNumber = -1; // Extruder1_ADC -pin_number kADC2_PinNumber = -1; // Extruder2_ADC -pin_number kADC3_PinNumber = -1; // 153; -pin_number kADC4_PinNumber = -1; // 154; -pin_number kADC5_PinNumber = -1; // 155; -pin_number kADC6_PinNumber = -1; // 156; -pin_number kADC7_PinNumber = -1; // 157; -pin_number kADC8_PinNumber = -1; // 158; -pin_number kADC9_PinNumber = -1; // 159; -pin_number kADC10_PinNumber = -1; // 160; -pin_number kADC11_PinNumber = -1; // 161; -pin_number kADC12_PinNumber = -1; // 162; -pin_number kADC13_PinNumber = -1; // Not physially pinned out +pin_number kOutput1_PinNumber = 124; +pin_number kOutput2_PinNumber = 125; +pin_number kOutput3_PinNumber = 126; +pin_number kOutput4_PinNumber = 127; +pin_number kOutput5_PinNumber = 128; + +pin_number kOutput6_PinNumber = 129; +pin_number kOutput7_PinNumber = 130; +pin_number kOutput8_PinNumber = 131; +pin_number kOutput9_PinNumber = 132; +pin_number kOutput10_PinNumber = 133; + +pin_number kOutput11_PinNumber = 134; +pin_number kOutput12_PinNumber = 135; +pin_number kOutput13_PinNumber = -1; +pin_number kOutput14_PinNumber = -1; +pin_number kOutput15_PinNumber = -1; +pin_number kOutput16_PinNumber = -1; + +pin_number kADC1_PinNumber = -1; // Heated bed thermistor ADC +pin_number kADC2_PinNumber = -1; // Extruder1_ADC +pin_number kADC3_PinNumber = -1; // Extruder2_ADC +pin_number kADC4_PinNumber = -1; // 153; +pin_number kADC5_PinNumber = -1; // 154; +pin_number kADC6_PinNumber = -1; // 155; +pin_number kADC7_PinNumber = -1; // 156; +pin_number kADC8_PinNumber = -1; // 157; +pin_number kADC9_PinNumber = -1; // 158; +pin_number kADC10_PinNumber = -1; // 159; +pin_number kADC11_PinNumber = -1; // 160; +pin_number kADC12_PinNumber = -1; // 161; +pin_number kADC13_PinNumber = -1; // 162; pin_number kADC14_PinNumber = -1; // Not physially pinned out +pin_number kADC15_PinNumber = -1; // Not physially pinned out // blank spots for unassigned pins - all unassigned pins need a unique number (do not re-use numbers) diff --git a/g2core/board/sbv300/sbv300-pinout.h b/g2core/board/sbv300/sbv300-pinout.h index d46b9cf47..f2667ec5e 100755 --- a/g2core/board/sbv300/sbv300-pinout.h +++ b/g2core/board/sbv300/sbv300-pinout.h @@ -47,11 +47,6 @@ #define INPUT12_AVAILABLE 1 #define INPUT13_AVAILABLE 1 -#define ADC0_AVAILABLE 0 -#define ADC1_AVAILABLE 0 -#define ADC2_AVAILABLE 0 -#define ADC3_AVAILABLE 0 - #define XIO_HAS_USB 1 #define XIO_HAS_UART 0 #define XIO_HAS_SPI 0 diff --git a/g2core/gpio.h b/g2core/gpio.h index c54d7479b..9a44623a8 100644 --- a/g2core/gpio.h +++ b/g2core/gpio.h @@ -34,8 +34,8 @@ //--- change as required for board and switch hardware ---// #define D_IN_CHANNELS 9 // v9 // number of digital inputs supported -//#define D_OUT_CHANNELS 13 // number of digital outputs supported -#define D_OUT_CHANNELS 9 // number of digital outputs supported +#define D_OUT_CHANNELS 13 // number of digital outputs supported +//#define D_OUT_CHANNELS 9 // number of digital outputs supported #define A_IN_CHANNELS 0 // number of analog inputs supported #define A_OUT_CHANNELS 0 // number of analog outputs supported diff --git a/g2core/settings/settings_Printrbot_Play.h b/g2core/settings/settings_Printrbot_Play.h index 0095531ed..6342af679 100644 --- a/g2core/settings/settings_Printrbot_Play.h +++ b/g2core/settings/settings_Printrbot_Play.h @@ -256,6 +256,9 @@ #endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_1 +#define EXTRUDER_1_OUTPUT_PIN kOutput1_PinNumber +#define EXTRUDER_1_FAN_PIN kOutput3_PinNumber + #define HAS_TEMPERATURE_SENSOR_2 true #if HAS_TEMPERATURE_SENSOR_2 #if 1 // 1 if a Thermistor, 0 if a PT100 @@ -270,20 +273,24 @@ #endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_2 +#define EXTRUDER_2_OUTPUT_PIN kOutput2_PinNumber + #define HAS_TEMPERATURE_SENSOR_3 true #if HAS_TEMPERATURE_SENSOR_3 #if 1 // 1 if a Thermistor, 0 if a PT100 - #define TEMPERATURE_SENSOR_3_TYPE Thermistor + #define TEMPERATURE_SENSOR_3_TYPE Thermistor #define TEMPERATURE_SENSOR_3_INIT { \ /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ } #else - #define TEMPERATURE_SENSOR_3_TYPE PT100 + #define TEMPERATURE_SENSOR_3_TYPE PT100 #define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} #endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_3 +#define BED_OUTPUT_PIN kOutput11_PinNumber + //** Digital Inputs ** diff --git a/g2core/settings/settings_Printrbot_Plus.h b/g2core/settings/settings_Printrbot_Plus.h index aebb8f0ea..19eb2d6cb 100644 --- a/g2core/settings/settings_Printrbot_Plus.h +++ b/g2core/settings/settings_Printrbot_Plus.h @@ -265,6 +265,9 @@ #endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_1 +#define EXTRUDER_1_OUTPUT_PIN kOutput1_PinNumber +#define EXTRUDER_1_FAN_PIN kOutput3_PinNumber + #define HAS_TEMPERATURE_SENSOR_2 true #if HAS_TEMPERATURE_SENSOR_2 #if 1 // 1 if a Thermistor, 0 if a PT100 @@ -279,20 +282,23 @@ #endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_2 +#define EXTRUDER_2_OUTPUT_PIN kOutput2_PinNumber + #define HAS_TEMPERATURE_SENSOR_3 true #if HAS_TEMPERATURE_SENSOR_3 #if 1 // 1 if a Thermistor, 0 if a PT100 - #define TEMPERATURE_SENSOR_3_TYPE Thermistor + #define TEMPERATURE_SENSOR_3_TYPE Thermistor #define TEMPERATURE_SENSOR_3_INIT { \ /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ } #else - #define TEMPERATURE_SENSOR_3_TYPE PT100 + #define TEMPERATURE_SENSOR_3_TYPE PT100 #define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} #endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_3 +#define BED_OUTPUT_PIN kOutput11_PinNumber //** Digital Inputs ** diff --git a/g2core/settings/settings_Printrbot_Simple_1403.h b/g2core/settings/settings_Printrbot_Simple_1403.h index 7fb3af61a..829859292 100644 --- a/g2core/settings/settings_Printrbot_Simple_1403.h +++ b/g2core/settings/settings_Printrbot_Simple_1403.h @@ -253,6 +253,9 @@ #endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_1 +#define EXTRUDER_1_OUTPUT_PIN kOutput1_PinNumber +#define EXTRUDER_1_FAN_PIN kOutput3_PinNumber + #define HAS_TEMPERATURE_SENSOR_2 true #if HAS_TEMPERATURE_SENSOR_2 #if 1 // 1 if a Thermistor, 0 if a PT100 @@ -267,22 +270,24 @@ #endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_2 +#define EXTRUDER_2_OUTPUT_PIN kOutput2_PinNumber + #define HAS_TEMPERATURE_SENSOR_3 true #if HAS_TEMPERATURE_SENSOR_3 #if 1 // 1 if a Thermistor, 0 if a PT100 - #define TEMPERATURE_SENSOR_3_TYPE Thermistor + #define TEMPERATURE_SENSOR_3_TYPE Thermistor #define TEMPERATURE_SENSOR_3_INIT { \ /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ } #else - #define TEMPERATURE_SENSOR_3_TYPE PT100 + #define TEMPERATURE_SENSOR_3_TYPE PT100 #define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} #endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_3 +#define BED_OUTPUT_PIN kOutput11_PinNumber -//** Digital Inputs ** /* IO_MODE_DISABLED diff --git a/g2core/settings/settings_Printrbot_Simple_1608.h b/g2core/settings/settings_Printrbot_Simple_1608.h index 01695e304..c4965a76e 100644 --- a/g2core/settings/settings_Printrbot_Simple_1608.h +++ b/g2core/settings/settings_Printrbot_Simple_1608.h @@ -277,6 +277,9 @@ #endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_1 +#define EXTRUDER_1_OUTPUT_PIN kOutput1_PinNumber +#define EXTRUDER_1_FAN_PIN kOutput3_PinNumber + #define HAS_TEMPERATURE_SENSOR_2 true #if HAS_TEMPERATURE_SENSOR_2 #if 1 // 1 if a Thermistor, 0 if a PT100 @@ -291,20 +294,23 @@ #endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_2 +#define EXTRUDER_2_OUTPUT_PIN kOutput2_PinNumber + #define HAS_TEMPERATURE_SENSOR_3 true #if HAS_TEMPERATURE_SENSOR_3 #if 1 // 1 if a Thermistor, 0 if a PT100 - #define TEMPERATURE_SENSOR_3_TYPE Thermistor + #define TEMPERATURE_SENSOR_3_TYPE Thermistor #define TEMPERATURE_SENSOR_3_INIT { \ /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ } #else - #define TEMPERATURE_SENSOR_3_TYPE PT100 + #define TEMPERATURE_SENSOR_3_TYPE PT100 #define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} #endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_3 +#define BED_OUTPUT_PIN kOutput11_PinNumber //** Digital Inputs ** diff --git a/g2core/settings/settings_Ultimaker_2_Plus.h b/g2core/settings/settings_Ultimaker_2_Plus.h index 0499152ae..c42263538 100644 --- a/g2core/settings/settings_Ultimaker_2_Plus.h +++ b/g2core/settings/settings_Ultimaker_2_Plus.h @@ -271,34 +271,40 @@ #endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_1 +#define EXTRUDER_1_OUTPUT_PIN kOutput2_PinNumber +#define EXTRUDER_1_FAN_PIN kOutput3_PinNumber + #define HAS_TEMPERATURE_SENSOR_2 true #if HAS_TEMPERATURE_SENSOR_2 #if 0 // 1 if a Thermistor, 0 if a PT100 - #define TEMPERATURE_SENSOR_2_TYPE Thermistor + #define TEMPERATURE_SENSOR_2_TYPE Thermistor #define TEMPERATURE_SENSOR_2_INIT { \ /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ } #else - #define TEMPERATURE_SENSOR_2_TYPE PT100 - #define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} + #define TEMPERATURE_SENSOR_2_TYPE PT100 + #define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 4700, /*inline_resistance*/0.75} #endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_2 +#define EXTRUDER_2_OUTPUT_PIN kOutput1_PinNumber + #define HAS_TEMPERATURE_SENSOR_3 true #if HAS_TEMPERATURE_SENSOR_3 #if 0 // 1 if a Thermistor, 0 if a PT100 - #define TEMPERATURE_SENSOR_3_TYPE Thermistor + #define TEMPERATURE_SENSOR_3_TYPE Thermistor #define TEMPERATURE_SENSOR_3_INIT { \ /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ } #else - #define TEMPERATURE_SENSOR_3_TYPE PT100 + #define TEMPERATURE_SENSOR_3_TYPE PT100 #define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} #endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_3 +#define BED_OUTPUT_PIN kOutput11_PinNumber //** Digital Inputs ** /* @@ -379,7 +385,7 @@ #define DO5_MODE IO_ACTIVE_HIGH #define DO6_MODE IO_ACTIVE_HIGH #define DO7_MODE IO_ACTIVE_HIGH -#define DO8_MODE IO_ACTIVE_HIGH +#define DO8_MODE IO_ACTIVE_LOW // 5V Fan //SAFEin (Output) signal #define DO9_MODE IO_ACTIVE_HIGH @@ -387,7 +393,7 @@ #define DO10_MODE IO_ACTIVE_HIGH //Header Bed FET -#define DO11_MODE IO_ACTIVE_HIGH +#define DO11_MODE IO_ACTIVE_LOW //Indicator_LED #define DO12_MODE IO_ACTIVE_HIGH @@ -412,7 +418,7 @@ #define H2_DEFAULT_I 0.05 #define H2_DEFAULT_D 150.0 -#define H3_DEFAULT_ENABLE false +#define H3_DEFAULT_ENABLE true #define H3_DEFAULT_P 9.0 #define H3_DEFAULT_I 0.12 #define H3_DEFAULT_D 400.0 diff --git a/g2core/temperature.cpp b/g2core/temperature.cpp index 4ccbb05e0..f1b812c73 100755 --- a/g2core/temperature.cpp +++ b/g2core/temperature.cpp @@ -51,6 +51,22 @@ #ifndef HAS_TEMPERATURE_SENSOR_3 #define HAS_TEMPERATURE_SENSOR_3 false #endif +#ifndef EXTRUDER_1_OUTPUT_PIN +#define EXTRUDER_1_OUTPUT_PIN kOutput1_PinNumber +#endif +#ifndef EXTRUDER_1_FAN_PIN +#define EXTRUDER_1_FAN_PIN kOutput3_PinNumber +#endif +#ifndef EXTRUDER_2_OUTPUT_PIN +#define EXTRUDER_2_OUTPUT_PIN kOutput2_PinNumber +#endif +#ifndef BED_OUTPUT_PIN +#define BED_OUTPUT_PIN kOutput11_PinNumber +#endif +#ifndef BED_OUTPUT_INIT +#define BED_OUTPUT_INIT +//#define BED_OUTPUT_INIT {kPWMPinInverted, fet_pin3_freq} +#endif // These could be moved to settings // If the temperature stays at set_point +- TEMP_SETPOINT_HYSTERESIS for more @@ -124,9 +140,16 @@ struct TemperatureSensor { return -1; // invalid temperature from a thermistor }; + uint16_t get_raw_value() { + return 0; + }; + float get_voltage() { return -1; - } + }; + + void start_sampling() { + }; }; template @@ -201,9 +224,17 @@ struct Thermistor { return ((pullup_resistance * v) / (kSystemVoltage - v)); // resistance of thermistor }; + uint16_t get_raw_value() { + return raw_adc_value; + }; + float get_voltage() { return raw_adc_voltage; - } + }; + + void start_sampling() { + adc_pin.startSampling(); + }; // Call back function from the ADC to tell it that the ADC has a new sample... void adc_has_new_value() { @@ -252,11 +283,19 @@ struct PT100 { float v = raw_adc_voltage; return ((pullup_resistance * v) / (kSystemVoltage - v)) - inline_resistance; // resistance of thermistor -}; + }; + + uint16_t get_raw_value() { + return raw_adc_value; + }; float get_voltage() { return raw_adc_voltage; -} + }; + + void start_sampling() { + adc_pin.startSampling(); + }; // Call back function from the ADC to tell it that the ADC has a new sample... void adc_has_new_value() { @@ -299,7 +338,7 @@ float last_reported_temp3 = 0; // DO_1: Extruder1_PWM const int16_t fet_pin1_freq = 100; #if TEMPERATURE_OUTPUT_ON == 1 -PWMOutputPin fet_pin1;// {kPWMPinInverted}; +PWMOutputPin fet_pin1;// {kPWMPinInverted}; #else PWMOutputPin<-1> fet_pin1;// {kPWMPinInverted}; #endif @@ -307,7 +346,7 @@ PWMOutputPin<-1> fet_pin1;// {kPWMPinInverted}; // DO_2: Extruder2_PWM const int16_t fet_pin2_freq = 100; #if TEMPERATURE_OUTPUT_ON == 1 -PWMOutputPin fet_pin2;// {kPWMPinInverted}; +PWMOutputPin fet_pin2;// {kPWMPinInverted}; #else PWMOutputPin<-1> fet_pin2;// {kPWMPinInverted}; #endif @@ -316,7 +355,7 @@ PWMOutputPin<-1> fet_pin2;// {kPWMPinInverted}; // Warning, HeatBED is likely NOT a PWM pin, so it'll be binary output (duty cucle >= 50%). const int16_t fet_pin3_freq = 100; #if TEMPERATURE_OUTPUT_ON == 1 -PWMOutputPin fet_pin3;// {kPWMPinInverted}; +PWMOutputPin fet_pin3 BED_OUTPUT_INIT; #else PWMOutputPin<-1> fet_pin3;// {kPWMPinInverted}; #endif @@ -352,9 +391,9 @@ const int16_t temperature_sample_freq = 10; // every fet_pin1_sample_freq interr int16_t temperature_sample_counter = temperature_sample_freq; SysTickEvent adc_tick_event {[&] { if (!--temperature_sample_counter) { - temperature_sensor_1.adc_pin.startSampling(); - temperature_sensor_2.adc_pin.startSampling(); - temperature_sensor_3.adc_pin.startSampling(); + temperature_sensor_1.start_sampling(); + temperature_sensor_2.start_sampling(); + temperature_sensor_3.start_sampling(); temperature_sample_counter = temperature_sample_freq; } }, nullptr}; @@ -523,7 +562,7 @@ struct HeaterFan { } }; -HeaterFan heater_fan1; +HeaterFan heater_fan1; /**** Static functions ****/ @@ -536,8 +575,6 @@ void temperature_init() { // setup heater PWM fet_pin1.setFrequency(fet_pin1_freq); - fet_pin1.setInterrupts(kInterruptOnOverflow|kInterruptPriorityLowest); - fet_pin2.setFrequency(fet_pin2_freq); fet_pin3.setFrequency(fet_pin3_freq); @@ -594,6 +631,7 @@ stat_t temperature_callback() pid_timeout.set(100); float temp = 0.0; + float fan_temp = 0.0; bool sr_requested = false; if (pid1._enable) { @@ -605,8 +643,7 @@ stat_t temperature_callback() sr_requested = true; } } - - heater_fan1.newTemp(temp); + fan_temp = temp; if (pid2._enable) { temp = temperature_sensor_2.temperature_exact(); @@ -617,6 +654,9 @@ stat_t temperature_callback() sr_requested = true; } } + fan_temp = max(fan_temp, temp); + + heater_fan1.newTemp(fan_temp); if (pid3._enable) { temp = temperature_sensor_3.temperature_exact(); @@ -1010,9 +1050,9 @@ stat_t cm_get_heater_output(nvObj_t *nv) stat_t cm_get_heater_adc(nvObj_t *nv) { switch(_get_heater_number(nv)) { - case '1': { nv->value = (float)temperature_sensor_1.raw_adc_value; break; } - case '2': { nv->value = (float)temperature_sensor_2.raw_adc_value; break; } - case '3': { nv->value = (float)temperature_sensor_3.raw_adc_value; break; } + case '1': { nv->value = (float)temperature_sensor_1.get_raw_value(); break; } + case '2': { nv->value = (float)temperature_sensor_2.get_raw_value(); break; } + case '3': { nv->value = (float)temperature_sensor_3.get_raw_value(); break; } default: { nv->value = 0.0; break; } } From f1b8d1ffdc8337c747dc49c3c5de782cd64da4a0 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Thu, 16 Mar 2017 18:10:56 -0500 Subject: [PATCH 047/193] Adjustments for quintic pinout and Ultimaker2+ settings --- g2core/board/gquintic/gquintic-b-pinout.h | 156 ++++++++++---------- g2core/settings/settings_Ultimaker_2_Plus.h | 10 +- 2 files changed, 83 insertions(+), 83 deletions(-) diff --git a/g2core/board/gquintic/gquintic-b-pinout.h b/g2core/board/gquintic/gquintic-b-pinout.h index 195fd3513..c0bcf0e38 100755 --- a/g2core/board/gquintic/gquintic-b-pinout.h +++ b/g2core/board/gquintic/gquintic-b-pinout.h @@ -94,17 +94,17 @@ // So we have to explicitly enable them as PWM pins. // Generated with: // perl -e 'for($i=1;$i<14;$i++) { print "#define OUTPUT${i}_PWM 0\n";}' -#define OUTPUT1_PWM 1 // TC0,1 - Fet 1 -#define OUTPUT2_PWM 1 // PWM1 - Fet 2 -#define OUTPUT3_PWM 1 // TC1,0 - Fan 1 -#define OUTPUT4_PWM 1 // TC1,1 - Fan 2 -#define OUTPUT5_PWM 1 // TC2,0 - Fan 3 -#define OUTPUT6_PWM 1 // PWM8+0 -#define OUTPUT7_PWM 1 // PWM3 -#define OUTPUT8_PWM 1 // PWM2 -#define OUTPUT9_PWM 0 // PWM2 -#define OUTPUT10_PWM 1 // PWM8+2 -#define OUTPUT11_PWM 1 // PWM8+3 - Fet 3 +#define OUTPUT1_PWM 1 // TC 0,1 - Fet 1 +#define OUTPUT2_PWM 1 // PWM 1 - Fet 2 +#define OUTPUT3_PWM 1 // TC 1,0 - Fan 1 +#define OUTPUT4_PWM 1 // TC 1,1 - Fan 2 +#define OUTPUT5_PWM 1 // TC 2,0 - Fan 3 +#define OUTPUT6_PWM 1 // PWM 8+0 +#define OUTPUT7_PWM 1 // PWM 3 +#define OUTPUT8_PWM 1 // PWM 2 +#define OUTPUT9_PWM 0 // PWM 2 +#define OUTPUT10_PWM 1 // PWM 8+2 +#define OUTPUT11_PWM 1 // PWM 8+3 - Fet 3 #define OUTPUT12_PWM 0 // Unused #define OUTPUT13_PWM 0 // Unused @@ -117,45 +117,45 @@ namespace Motate { // // -_MAKE_MOTATE_PIN(kLED_RGBWPixelPinNumber, 'A', 0); // -_MAKE_MOTATE_PIN(kOutput1_PinNumber, 'A', 1); // -_MAKE_MOTATE_PIN(kOutput2_PinNumber, 'A', 2); // -_MAKE_MOTATE_PIN(kI2C1_SDAPinNumber, 'A', 3); // -_MAKE_MOTATE_PIN(kI2C1_SCLPinNumber, 'A', 4); // -_MAKE_MOTATE_PIN(kOutput11_PinNumber, 'A', 5); // -_MAKE_MOTATE_PIN(kExternalClock1_PinNumber, 'A', 6); // CPU_CLK -//_MAKE_MOTATE_PIN(kOutput7_PinNumber, 'A', 7); // -_MAKE_MOTATE_PIN(kServo1_PinNumber, 'A', 7); // -_MAKE_MOTATE_PIN(kSerial_RTSPinNumber, 'A', 8); // -_MAKE_MOTATE_PIN(kSerial_RXPinNumber, 'A', 9); // -_MAKE_MOTATE_PIN(kSerial_TXPinNumber, 'A', 10); // -_MAKE_MOTATE_PIN(kSocket2_EnablePinNumber, 'A', 11); // -_MAKE_MOTATE_PIN(kOutput6_PinNumber, 'A', 12); // -_MAKE_MOTATE_PIN(kOutput8_PinNumber, 'A', 13); // -_MAKE_MOTATE_PIN(kSocket1_StepPinNumber, 'A', 14); // -_MAKE_MOTATE_PIN(kOutput3_PinNumber, 'A', 15); // -_MAKE_MOTATE_PIN(kOutput4_PinNumber, 'A', 16); // -_MAKE_MOTATE_PIN(kADC4_PinNumber, 'A', 17); // -_MAKE_MOTATE_PIN(kADC3_PinNumber, 'A', 18); // -_MAKE_MOTATE_PIN(kADC2_PinNumber, 'A', 19); // -_MAKE_MOTATE_PIN(kADC1_PinNumber, 'A', 20); // -_MAKE_MOTATE_PIN(kSerial_CTSPinNumber, 'A', 21); // -_MAKE_MOTATE_PIN(kSocket1_EnablePinNumber, 'A', 22); // -_MAKE_MOTATE_PIN(kOutput10_PinNumber, 'A', 23); // -//_MAKE_MOTATE_PIN(kServo1_PinNumber, 'A', 23); // -_MAKE_MOTATE_PIN(kSocket3_EnablePinNumber, 'A', 24); // -_MAKE_MOTATE_PIN(kSocket2_DirPinNumber, 'A', 25); // -_MAKE_MOTATE_PIN(kOutput5_PinNumber, 'A', 26); // On Timer 2! -_MAKE_MOTATE_PIN(kSocket3_DirPinNumber, 'A', 27); // On Timer 2! +_MAKE_MOTATE_PIN(kLED_RGBWPixelPinNumber, 'A', 0); // +_MAKE_MOTATE_PIN(kOutput1_PinNumber, 'A', 1); // TC 0,1 +_MAKE_MOTATE_PIN(kOutput2_PinNumber, 'A', 2); // PWM 1 +_MAKE_MOTATE_PIN(kI2C1_SDAPinNumber, 'A', 3); // +_MAKE_MOTATE_PIN(kI2C1_SCLPinNumber, 'A', 4); // +_MAKE_MOTATE_PIN(kOutput11_PinNumber, 'A', 5); // PWM 8+3 +_MAKE_MOTATE_PIN(kExternalClock1_PinNumber, 'A', 6); // CPU_CLK +//_MAKE_MOTATE_PIN(kOutput7_PinNumber, 'A', 7); // PWM 3 +_MAKE_MOTATE_PIN(kServo1_PinNumber, 'A', 7); // +_MAKE_MOTATE_PIN(kSerial_RTSPinNumber, 'A', 8); // +_MAKE_MOTATE_PIN(kSerial_RXPinNumber, 'A', 9); // +_MAKE_MOTATE_PIN(kSerial_TXPinNumber, 'A', 10); // +_MAKE_MOTATE_PIN(kSocket2_EnablePinNumber, 'A', 11); // +_MAKE_MOTATE_PIN(kOutput6_PinNumber, 'A', 12); // PWM 8+0 +_MAKE_MOTATE_PIN(kOutput8_PinNumber, 'A', 13); // PWM 2 +_MAKE_MOTATE_PIN(kSocket1_StepPinNumber, 'A', 14); // +_MAKE_MOTATE_PIN(kOutput3_PinNumber, 'A', 15); // TC 1,0 +_MAKE_MOTATE_PIN(kOutput4_PinNumber, 'A', 16); // TC 1,1 +_MAKE_MOTATE_PIN(kADC4_PinNumber, 'A', 17); // +_MAKE_MOTATE_PIN(kADC3_PinNumber, 'A', 18); // +_MAKE_MOTATE_PIN(kADC2_PinNumber, 'A', 19); // +_MAKE_MOTATE_PIN(kADC1_PinNumber, 'A', 20); // +_MAKE_MOTATE_PIN(kSerial_CTSPinNumber, 'A', 21); // +_MAKE_MOTATE_PIN(kSocket1_EnablePinNumber, 'A', 22); // +_MAKE_MOTATE_PIN(kOutput10_PinNumber, 'A', 23); // PWM 8+2 +//_MAKE_MOTATE_PIN(kServo1_PinNumber, 'A', 23); // +_MAKE_MOTATE_PIN(kSocket3_EnablePinNumber, 'A', 24); // +_MAKE_MOTATE_PIN(kSocket2_DirPinNumber, 'A', 25); // +_MAKE_MOTATE_PIN(kOutput5_PinNumber, 'A', 26); // TC 2,0 +_MAKE_MOTATE_PIN(kSocket3_DirPinNumber, 'A', 27); // On Timer 2! _MAKE_MOTATE_PIN(kUnassigned1, 'A', 28); // DIAG1 -_MAKE_MOTATE_PIN(kUnassigned2, 'A', 29); // -_MAKE_MOTATE_PIN(kInput1_PinNumber, 'A', 30); // -_MAKE_MOTATE_PIN(kInput4_PinNumber, 'A', 31); // +_MAKE_MOTATE_PIN(kUnassigned2, 'A', 29); // +_MAKE_MOTATE_PIN(kInput1_PinNumber, 'A', 30); // +_MAKE_MOTATE_PIN(kInput4_PinNumber, 'A', 31); // _MAKE_MOTATE_PIN(kInput12_PinNumber, 'B', 0); // _MAKE_MOTATE_PIN(kInput11_PinNumber, 'B', 1); // _MAKE_MOTATE_PIN(kSocket1_SPISlaveSelectPinNumber, 'B', 2); // -_MAKE_MOTATE_PIN(kOutputSAFE_PinNumber, 'B', 3); // +_MAKE_MOTATE_PIN(kOutputSAFE_PinNumber, 'B', 3); // //_MAKE_MOTATE_PIN( , 'B', 4); // TDI //_MAKE_MOTATE_PIN( , 'B', 5); // TRACESDO //_MAKE_MOTATE_PIN( , 'B', 6); // SWDIO @@ -165,42 +165,42 @@ _MAKE_MOTATE_PIN(kOutputSAFE_PinNumber, 'B', 3); // //_MAKE_MOTATE_PIN( , 'B', 10); // USB_D- //_MAKE_MOTATE_PIN( , 'B', 11); // USB_D+ //_MAKE_MOTATE_PIN( , 'B', 12); // ERASE -_MAKE_MOTATE_PIN(kLED_USBRXPinNumber, 'B', 13); // LED_1 (Heartbeat) - PWM2 -_MAKE_MOTATE_PIN(kSocket4_SPISlaveSelectPinNumber, 'B', 14); // NOT CONNECTED +_MAKE_MOTATE_PIN(kLED_USBRXPinNumber, 'B', 13); // LED_1 (Heartbeat) - PWM2 +_MAKE_MOTATE_PIN(kSocket4_SPISlaveSelectPinNumber, 'B', 14); // NOT CONNECTED //_MAKE_MOTATE_PIN( , 'D', 0); // USB_VBUS -_MAKE_MOTATE_PIN(kInput9_PinNumber, 'D', 1); // -_MAKE_MOTATE_PIN(kInput10_PinNumber, 'D', 2); // -_MAKE_MOTATE_PIN(kInput8_PinNumber, 'D', 3); // -_MAKE_MOTATE_PIN(kInput7_PinNumber, 'D', 4); // -_MAKE_MOTATE_PIN(kInput6_PinNumber, 'D', 5); // -_MAKE_MOTATE_PIN(kInput5_PinNumber, 'D', 6); // -_MAKE_MOTATE_PIN(kInput3_PinNumber, 'D', 7); // -_MAKE_MOTATE_PIN(kInput2_PinNumber, 'D', 8); // ] -_MAKE_MOTATE_PIN(kUnassigned3, 'D', 9); // DIAG0 -_MAKE_MOTATE_PIN(kUnassigned4, 'D', 10); // -_MAKE_MOTATE_PIN(kSocket5_StepPinNumber, 'D', 11); // -_MAKE_MOTATE_PIN(kSocket3_SPISlaveSelectPinNumber, 'D', 12); // -_MAKE_MOTATE_PIN(kSocket5_DirPinNumber, 'D', 13); // -_MAKE_MOTATE_PIN(kSocket5_EnablePinNumber, 'D', 14); // -_MAKE_MOTATE_PIN(kUnassigned5, 'D', 15); // -_MAKE_MOTATE_PIN(kSocket4_StepPinNumber, 'D', 16); // -_MAKE_MOTATE_PIN(kSocket4_DirPinNumber, 'D', 17); // -_MAKE_MOTATE_PIN(kSocket3_StepPinNumber, 'D', 18); // -_MAKE_MOTATE_PIN(kUnassigned6, 'D', 19); // -_MAKE_MOTATE_PIN(kSPI0_MISOPinNumber, 'D', 20); // -_MAKE_MOTATE_PIN(kSPI0_MOSIPinNumber, 'D', 21); // -_MAKE_MOTATE_PIN(kSPI0_SCKPinNumber, 'D', 22); // -_MAKE_MOTATE_PIN(kUnassigned7, 'D', 23); // -_MAKE_MOTATE_PIN(kSocket2_StepPinNumber, 'D', 24); // -_MAKE_MOTATE_PIN(kSocket2_SPISlaveSelectPinNumber, 'D', 25); // -_MAKE_MOTATE_PIN(kOutput9_PinNumber, 'D', 26); // -_MAKE_MOTATE_PIN(kSocket1_DirPinNumber, 'D', 27); // -_MAKE_MOTATE_PIN(kSocket4_EnablePinNumber, 'D', 28); // -_MAKE_MOTATE_PIN(kUnassigned8, 'D', 29); // -_MAKE_MOTATE_PIN(kUnassigned9, 'D', 30); // INTERRUPT_OUT -_MAKE_MOTATE_PIN(kUnassigned10, 'D', 31); // +_MAKE_MOTATE_PIN(kInput9_PinNumber, 'D', 1); // +_MAKE_MOTATE_PIN(kInput10_PinNumber, 'D', 2); // +_MAKE_MOTATE_PIN(kInput8_PinNumber, 'D', 3); // +_MAKE_MOTATE_PIN(kInput7_PinNumber, 'D', 4); // +_MAKE_MOTATE_PIN(kInput6_PinNumber, 'D', 5); // +_MAKE_MOTATE_PIN(kInput5_PinNumber, 'D', 6); // +_MAKE_MOTATE_PIN(kInput3_PinNumber, 'D', 7); // +_MAKE_MOTATE_PIN(kInput2_PinNumber, 'D', 8); // ] +_MAKE_MOTATE_PIN(kUnassigned3, 'D', 9); // DIAG0 +_MAKE_MOTATE_PIN(kUnassigned4, 'D', 10); // +_MAKE_MOTATE_PIN(kSocket5_StepPinNumber, 'D', 11); // +_MAKE_MOTATE_PIN(kSocket3_SPISlaveSelectPinNumber, 'D', 12); // +_MAKE_MOTATE_PIN(kSocket5_DirPinNumber, 'D', 13); // +_MAKE_MOTATE_PIN(kSocket5_EnablePinNumber, 'D', 14); // +_MAKE_MOTATE_PIN(kUnassigned5, 'D', 15); // +_MAKE_MOTATE_PIN(kSocket4_StepPinNumber, 'D', 16); // +_MAKE_MOTATE_PIN(kSocket4_DirPinNumber, 'D', 17); // +_MAKE_MOTATE_PIN(kSocket3_StepPinNumber, 'D', 18); // +_MAKE_MOTATE_PIN(kUnassigned6, 'D', 19); // +_MAKE_MOTATE_PIN(kSPI0_MISOPinNumber, 'D', 20); // +_MAKE_MOTATE_PIN(kSPI0_MOSIPinNumber, 'D', 21); // +_MAKE_MOTATE_PIN(kSPI0_SCKPinNumber, 'D', 22); // +_MAKE_MOTATE_PIN(kUnassigned7, 'D', 23); // +_MAKE_MOTATE_PIN(kSocket2_StepPinNumber, 'D', 24); // +_MAKE_MOTATE_PIN(kSocket2_SPISlaveSelectPinNumber, 'D', 25); // +_MAKE_MOTATE_PIN(kOutput9_PinNumber, 'D', 26); // PWM 2 +_MAKE_MOTATE_PIN(kSocket1_DirPinNumber, 'D', 27); // +_MAKE_MOTATE_PIN(kSocket4_EnablePinNumber, 'D', 28); // +_MAKE_MOTATE_PIN(kUnassigned8, 'D', 29); // +_MAKE_MOTATE_PIN(kUnassigned9, 'D', 30); // INTERRUPT_OUT +_MAKE_MOTATE_PIN(kUnassigned10, 'D', 31); // } // namespace Motate diff --git a/g2core/settings/settings_Ultimaker_2_Plus.h b/g2core/settings/settings_Ultimaker_2_Plus.h index c42263538..d0bd02890 100644 --- a/g2core/settings/settings_Ultimaker_2_Plus.h +++ b/g2core/settings/settings_Ultimaker_2_Plus.h @@ -175,7 +175,7 @@ #define Z_VELOCITY_MAX 2000 #define Z_FEEDRATE_MAX Z_VELOCITY_MAX #define Z_TRAVEL_MIN 0 -#define Z_TRAVEL_MAX 230 +#define Z_TRAVEL_MAX 215 #define Z_JERK_MAX 1500 #define Z_JERK_HIGH_SPEED 3000 #define Z_HOMING_INPUT 6 @@ -267,12 +267,12 @@ } #else #define TEMPERATURE_SENSOR_1_TYPE PT100 - #define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} + #define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0} #endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_1 #define EXTRUDER_1_OUTPUT_PIN kOutput2_PinNumber -#define EXTRUDER_1_FAN_PIN kOutput3_PinNumber +#define EXTRUDER_1_FAN_PIN kOutput8_PinNumber #define HAS_TEMPERATURE_SENSOR_2 true #if HAS_TEMPERATURE_SENSOR_2 @@ -284,7 +284,7 @@ } #else #define TEMPERATURE_SENSOR_2_TYPE PT100 - #define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 4700, /*inline_resistance*/0.75} + #define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 4700, /*inline_resistance*/0} #endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_2 @@ -300,7 +300,7 @@ } #else #define TEMPERATURE_SENSOR_3_TYPE PT100 - #define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} + #define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0} #endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_3 From cb4273b2de3a6a01de57e873af6e891596a4260b Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Thu, 16 Mar 2017 18:11:17 -0500 Subject: [PATCH 048/193] =?UTF-8?q?Adde=20ability=20for=20each=20heater=20?= =?UTF-8?q?to=20have=20it=E2=80=99s=20own=20min=20temp=20rise=20over=20tim?= =?UTF-8?q?e.?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- g2core/temperature.cpp | 17 ++++++++++------- 1 file changed, 10 insertions(+), 7 deletions(-) diff --git a/g2core/temperature.cpp b/g2core/temperature.cpp index f1b812c73..66f839c7f 100755 --- a/g2core/temperature.cpp +++ b/g2core/temperature.cpp @@ -65,7 +65,6 @@ #endif #ifndef BED_OUTPUT_INIT #define BED_OUTPUT_INIT -//#define BED_OUTPUT_INIT {kPWMPinInverted, fet_pin3_freq} #endif // These could be moved to settings @@ -109,8 +108,11 @@ #ifndef TEMP_MIN_RISE_DEGREES_OVER_TIME #define TEMP_MIN_RISE_DEGREES_OVER_TIME (float)10.0 #endif +#ifndef TEMP_MIN_BED_RISE_DEGREES_OVER_TIME +#define TEMP_MIN_BED_RISE_DEGREES_OVER_TIME (float)3.0 +#endif #ifndef TEMP_MIN_RISE_TIME -#define TEMP_MIN_RISE_TIME (float)(60.0 * 1000.0) // 20 seconds +#define TEMP_MIN_RISE_TIME (float)(60.0 * 1000.0) // one minute #endif #ifndef TEMP_MIN_RISE_DEGREES_FROM_TARGET #define TEMP_MIN_RISE_DEGREES_FROM_TARGET (float)10.0 @@ -420,11 +422,12 @@ struct PID { bool _at_set_point; Timeout _rise_time_timeout; // used to keep track of if we are increasing temperature fast enough + float _min_rise_over_time; // the amount of degrees that it must rise in the given time float _rise_time_checkpoint; // when we start the timer, we set _rise_time_checkpoint to the minimum goal bool _enable; // set true to enable this heater - PID(float P, float I, float D, float startSetPoint = 0.0) : _p_factor{P/100.0f}, _i_factor{I/100.0f}, _d_factor{D/100.0f}, _set_point{startSetPoint}, _at_set_point{false} {}; + PID(float P, float I, float D, float min_rise_over_time, float startSetPoint = 0.0) : _p_factor{P/100.0f}, _i_factor{I/100.0f}, _d_factor{D/100.0f}, _set_point{startSetPoint}, _at_set_point{false}, _min_rise_over_time(min_rise_over_time) {}; float getNewOutput(float input) { // If the input is < 0, the sensor failed @@ -469,7 +472,7 @@ struct PID { if (!_rise_time_timeout.isSet() && (_set_point > (input + TEMP_MIN_RISE_DEGREES_FROM_TARGET))) { _rise_time_timeout.set(TEMP_MIN_RISE_TIME); - _rise_time_checkpoint = min(input + TEMP_MIN_RISE_DEGREES_OVER_TIME, _set_point + TEMP_SETPOINT_HYSTERESIS); + _rise_time_checkpoint = min(input + _min_rise_over_time, _set_point + TEMP_SETPOINT_HYSTERESIS); } } @@ -526,9 +529,9 @@ struct PID { // NOTICE, the JSON alters incoming values for these! // {he1p:9} == 9.0/100.0 here -PID pid1 { 9.0, 0.11, 400.0 }; // default values -PID pid2 { 7.5, 0.12, 400.0 }; // default values -PID pid3 { 7.5, 0.12, 400.0 }; // default values +PID pid1 { 9.0, 0.11, 400.0, TEMP_MIN_RISE_DEGREES_OVER_TIME }; // default values +PID pid2 { 7.5, 0.12, 400.0, TEMP_MIN_RISE_DEGREES_OVER_TIME }; // default values +PID pid3 { 7.5, 0.12, 400.0, TEMP_MIN_BED_RISE_DEGREES_OVER_TIME }; // default values Timeout pid_timeout; From ac3fd4785bfbff2f77ccff6e0d9a3b22dbb5bde7 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Thu, 16 Mar 2017 18:11:25 -0500 Subject: [PATCH 049/193] Update motate for PWM fixes. --- Motate | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Motate b/Motate index 25a835471..f803b6283 160000 --- a/Motate +++ b/Motate @@ -1 +1 @@ -Subproject commit 25a835471c912c0969122aaed15e7e0cd3d086f0 +Subproject commit f803b628396cd595bce92f269f62cef893544a1f From 6e343c1f6ddfad2c125bdae55db7a143df9bc867 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Fri, 17 Mar 2017 00:13:48 -0500 Subject: [PATCH 050/193] Fix marlin compatibility bed controls not working. --- g2core/gcode_parser.cpp | 2 +- g2core/marlin_compatibility.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/g2core/gcode_parser.cpp b/g2core/gcode_parser.cpp index 60e9956c0..2005f9e92 100644 --- a/g2core/gcode_parser.cpp +++ b/g2core/gcode_parser.cpp @@ -1140,7 +1140,7 @@ static stat_t _execute_gcode_block_marlin() if (gf.S_word) { temp = gv.S_word; } if (gf.P_word) { temp = gv.P_word; } // we treat them the same, for now - uint8_t tool = (gv.next_action == NEXT_ACTION_MARLIN_SET_EXTRUDER_TEMP) ? cm.gm.tool_select : 2; // heat bed is 2 here, normally 3 + uint8_t tool = (gv.next_action == NEXT_ACTION_MARLIN_SET_EXTRUDER_TEMP) ? cm.gm.tool_select : 3; ritorno(marlin_set_temperature(tool, temp, gf.marlin_wait_for_temp)); gf.P_word = false; diff --git a/g2core/marlin_compatibility.cpp b/g2core/marlin_compatibility.cpp index 667d5d887..964df8bbc 100644 --- a/g2core/marlin_compatibility.cpp +++ b/g2core/marlin_compatibility.cpp @@ -330,7 +330,7 @@ stat_t marlin_set_temperature(uint8_t tool, float temperature, bool wait) { if (MarlinSetTempState::Idle != set_temp_state) { return (STAT_BUFFER_FULL_FATAL); // we shouldn't be here } - if ((tool < 1) || (tool > 2)) { + if ((tool < 1) || (tool > 3)) { return STAT_INPUT_VALUE_RANGE_ERROR; } From ee805beba2d250bce32ea766c5678997d9ad21f7 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Fri, 17 Mar 2017 00:14:08 -0500 Subject: [PATCH 051/193] Enable marlin compatibility for UM2+ --- g2core/settings/settings_Ultimaker_2_Plus.h | 17 ++++++++++------- 1 file changed, 10 insertions(+), 7 deletions(-) diff --git a/g2core/settings/settings_Ultimaker_2_Plus.h b/g2core/settings/settings_Ultimaker_2_Plus.h index d0bd02890..5c3c52a4b 100644 --- a/g2core/settings/settings_Ultimaker_2_Plus.h +++ b/g2core/settings/settings_Ultimaker_2_Plus.h @@ -57,6 +57,7 @@ // Communications and reporting settings +#define MARLIN_COMPAT_ENABLED true // enable marlin compatibility mode #define COMM_MODE JSON_MODE // one of: TEXT_MODE, JSON_MODE #define XIO_ENABLE_FLOW_CONTROL FLOW_CONTROL_RTS // FLOW_CONTROL_OFF, FLOW_CONTROL_RTS #define XIO_UART_MUTES_WHEN_USB_CONNECTED 1 // Mute the UART when USB connects @@ -103,7 +104,7 @@ #define M1_MICROSTEPS 32 // 1mi 1,2,4,8,16,32 #define M1_POLARITY 0 // 1po 0=normal, 1=reversed #define M1_POWER_MODE MOTOR_POWER_MODE // 1pm standard -#define M1_POWER_LEVEL 0.9 // 1mp +#define M1_POWER_LEVEL 0.7 // 1mp // 80 steps/mm at 1/16 microstepping = 40 mm/rev #define M2_MOTOR_MAP AXIS_Y @@ -111,9 +112,9 @@ // Marlin says 80 steps/unit, and 16 microsteps, with a 200-step/rev motor #define M2_TRAVEL_PER_REV 40 #define M2_MICROSTEPS 32 -#define M2_POLARITY 0 +#define M2_POLARITY 1 #define M2_POWER_MODE MOTOR_POWER_MODE -#define M2_POWER_LEVEL 0.9 +#define M2_POWER_LEVEL 0.7 #define M3_MOTOR_MAP AXIS_Z #define M3_STEP_ANGLE 1.8 @@ -122,15 +123,15 @@ #define M3_MICROSTEPS 32 #define M3_POLARITY 0 #define M3_POWER_MODE MOTOR_POWER_MODE -#define M3_POWER_LEVEL 0.9 +#define M3_POWER_LEVEL 0.7 #define M4_MOTOR_MAP AXIS_A #define M4_STEP_ANGLE 1.8 #define M4_TRAVEL_PER_REV 360 // degrees moved per motor rev #define M4_MICROSTEPS 32 -#define M4_POLARITY 1 +#define M4_POLARITY 0 #define M4_POWER_MODE MOTOR_POWER_MODE -#define M4_POWER_LEVEL 0.9 +#define M4_POWER_LEVEL 0.7 // 96 steps/mm at 1/16 microstepping = 33.3333 mm/rev #define M5_MOTOR_MAP AXIS_B @@ -165,7 +166,7 @@ #define Y_JERK_MAX 6000 #define Y_JERK_HIGH_SPEED 6000 #define Y_HOMING_INPUT 3 -#define Y_HOMING_DIRECTION 0 +#define Y_HOMING_DIRECTION 1 #define Y_SEARCH_VELOCITY 3000 #define Y_LATCH_VELOCITY 200 #define Y_LATCH_BACKOFF 5 @@ -185,6 +186,8 @@ #define Z_LATCH_BACKOFF 2 #define Z_ZERO_BACKOFF 0 +#define G55_Z_OFFSET 0.5 + // Rotary values are chosen to make the motor react the same as X for testing /*************************************************************************************** * To calculate the speeds here, in Wolfram Alpha-speak: From 1648e96653c8d707a94eeca57d2d4563947ffbfb Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Tue, 21 Mar 2017 22:20:54 -0500 Subject: [PATCH 052/193] Update PT100 to use differential ADC in a wheatstone config. --- g2core/temperature.cpp | 54 +++++++++++++++++++++++++++--------------- 1 file changed, 35 insertions(+), 19 deletions(-) diff --git a/g2core/temperature.cpp b/g2core/temperature.cpp index 66f839c7f..264d4582f 100755 --- a/g2core/temperature.cpp +++ b/g2core/temperature.cpp @@ -246,31 +246,44 @@ struct Thermistor { }; -template +template struct PT100 { float pullup_resistance; float inline_resistance; + bool wheatstone; - ADCPin adc_pin {kNormal, [&]{this->adc_has_new_value();} }; + ADC_t adc_pin {kNormal, [&]{this->adc_has_new_value();} }; float raw_adc_voltage = 0.0; int32_t raw_adc_value = 0; - typedef PT100 type; + typedef PT100 type; - PT100(const float pullup_resistance_, const float inline_resistance_) - : pullup_resistance{ pullup_resistance_ }, inline_resistance{ inline_resistance_ } { + PT100(const float pullup_resistance_, const float inline_resistance_, const bool wheatstone_ = false) + : pullup_resistance{ pullup_resistance_ }, + inline_resistance{ inline_resistance_ }, + wheatstone{wheatstone_} + { adc_pin.setInterrupts(kPinInterruptOnChange|kInterruptPriorityLow); - adc_pin.setVoltageRange(kSystemVoltage, 0.0687, 0.165, 6400.0); - } + adc_pin.setVoltageRange(kSystemVoltage, + get_voltage_of_temp(min_temp), + get_voltage_of_temp(max_temp), + wheatstone, // if wheatstone, then differential + 6400.0); + }; - float temperature_exact() { - // Sanity check: - if (raw_adc_voltage < 0.06) { - return -1; // invalid temperature from a thermistor + float get_voltage_of_temp(float t) { + // R = 100(1 + A*T + B*T^2); A = 3.9083*10^-3; B = -5.775*10^-7 + float r = 100 * (1 + 0.0039083*t + -0.0000005775*t*t) + inline_resistance; + + if (wheatstone) { + return (r - pullup_resistance)/(2.0*(pullup_resistance + r)); } + return r/(r+pullup_resistance)*kSystemVoltage; + }; - float v = raw_adc_voltage; - float r = ((pullup_resistance * v) / (kSystemVoltage - v)) - inline_resistance; // resistance of thermistor + float temperature_exact() { + float r = get_resistance(); + if (r < 100) { return -1; } // from https://www.maximintegrated.com/en/app-notes/index.mvp/id/3450 // run through wolfram as: @@ -279,12 +292,15 @@ struct PT100 { }; float get_resistance() { - if (raw_adc_voltage < 0.001) { - return -1; // invalid temperature from a thermistor + float r; + if (wheatstone) { + float v = raw_adc_voltage / kSystemVoltage; + r = pullup_resistance*(1-2.0*v)/(2.0*v+1.0) - inline_resistance; + } else { + float v = raw_adc_voltage; + r = ((pullup_resistance * v) / (kSystemVoltage - v)) - inline_resistance; } - - float v = raw_adc_voltage; - return ((pullup_resistance * v) / (kSystemVoltage - v)) - inline_resistance; // resistance of thermistor + return r; }; uint16_t get_raw_value() { @@ -301,7 +317,7 @@ struct PT100 { // Call back function from the ADC to tell it that the ADC has a new sample... void adc_has_new_value() { - raw_adc_voltage = (raw_adc_voltage * 2.0 + adc_pin.getVoltage())/3.0; + raw_adc_voltage = (raw_adc_voltage * 10.0 + adc_pin.getVoltage())/11.0; raw_adc_value = adc_pin.getRaw(); }; }; From 54cb9e65346e0ef1b43346402d5853f345ffecf0 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Tue, 21 Mar 2017 22:21:17 -0500 Subject: [PATCH 053/193] Configure Ultimaker2+ configs to use a wheatstone config --- g2core/settings/settings_Ultimaker_2_Plus.h | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/g2core/settings/settings_Ultimaker_2_Plus.h b/g2core/settings/settings_Ultimaker_2_Plus.h index 5c3c52a4b..3c04e7579 100644 --- a/g2core/settings/settings_Ultimaker_2_Plus.h +++ b/g2core/settings/settings_Ultimaker_2_Plus.h @@ -269,8 +269,8 @@ /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ } #else - #define TEMPERATURE_SENSOR_1_TYPE PT100 - #define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0} + #define TEMPERATURE_SENSOR_1_TYPE PT100> + #define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 100, /*inline_resistance*/0, /*wheatstone*/ true} #endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_1 @@ -286,8 +286,8 @@ /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ } #else - #define TEMPERATURE_SENSOR_2_TYPE PT100 - #define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 4700, /*inline_resistance*/0} + #define TEMPERATURE_SENSOR_2_TYPE PT100> + #define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 100, /*inline_resistance*/0} #endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_2 @@ -302,8 +302,8 @@ /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ } #else - #define TEMPERATURE_SENSOR_3_TYPE PT100 - #define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0} + #define TEMPERATURE_SENSOR_3_TYPE PT100> + #define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 100, /*inline_resistance*/0, /*wheatstone*/ true} #endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_3 From fc674c6d3ae2aec98a04f7bd6f0b76312cd61a17 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Tue, 21 Mar 2017 22:21:40 -0500 Subject: [PATCH 054/193] Update Motate to pull in support for differential ADC on SamS70 --- Motate | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Motate b/Motate index f803b6283..508cd27ec 160000 --- a/Motate +++ b/Motate @@ -1 +1 @@ -Subproject commit f803b628396cd595bce92f269f62cef893544a1f +Subproject commit 508cd27ec332718d335bc62a26e6ec8935929b5c From 806aa81e68de6ccf86b5784a82a735e2e911d8a1 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Thu, 30 Mar 2017 18:55:31 -0500 Subject: [PATCH 055/193] Ultimaker Interim commit --- Motate | 2 +- g2core/board/gquintic.mk | 4 +- .../gquintic/{hardware.cpp => 0_hardware.cpp} | 4 + g2core/board/gquintic/board_stepper.cpp | 33 +- g2core/board/gquintic/board_stepper.h | 22 +- g2core/board/gquintic/board_xio.cpp | 2 +- g2core/board/gquintic/gquintic-b-pinout.h | 6 +- g2core/board/gquintic/hardware.h | 21 +- g2core/device/max31865/max31865.h | 416 ++++++++++++++++++ g2core/device/trinamic/tmc2130.h | 6 +- g2core/g2core.xcodeproj/project.pbxproj | 42 +- g2core/settings/settings_Ultimaker_2_Plus.h | 12 +- g2core/settings/settings_axidraw_v3.h | 6 +- g2core/temperature.cpp | 33 +- 14 files changed, 540 insertions(+), 69 deletions(-) rename g2core/board/gquintic/{hardware.cpp => 0_hardware.cpp} (98%) create mode 100644 g2core/device/max31865/max31865.h diff --git a/Motate b/Motate index 508cd27ec..3d0d332dc 160000 --- a/Motate +++ b/Motate @@ -1 +1 @@ -Subproject commit 508cd27ec332718d335bc62a26e6ec8935929b5c +Subproject commit 3d0d332dc5be522166b801d7f4aa74c35ed001e2 diff --git a/g2core/board/gquintic.mk b/g2core/board/gquintic.mk index 7f267ed8a..8ccba539f 100755 --- a/g2core/board/gquintic.mk +++ b/g2core/board/gquintic.mk @@ -29,14 +29,14 @@ ifeq ("$(BASE_BOARD)","gquintic") DEVICE_DEFINES += MOTATE_CONFIG_HAS_USBSERIAL=1 ENABLE_TCM=1 - FIRST_LINK_SOURCES += $(sort $(wildcard ${MOTATE_PATH}/Atmel_sam_common/*.cpp)) $(sort $(wildcard ${MOTATE_PATH}/Atmel_sams70/*.cpp)) + FIRST_LINK_SOURCES += $(sort $(wildcard ${MOTATE_PATH}/Atmel_sam_common/*.cpp)) $(sort $(wildcard ${MOTATE_PATH}/Atmel_sams70/*.cpp) $(wildcard ${BOARD_PATH}/*.cpp)) CHIP = SAMS70N19 export CHIP CHIP_LOWERCASE = sams70n19 BOARD_PATH = ./board/gquintic - SOURCE_DIRS += ${BOARD_PATH} device/trinamic device/step_dir_hobbyservo + SOURCE_DIRS += ${BOARD_PATH} device/trinamic device/step_dir_hobbyservo device/max31865 PLATFORM_BASE = ${MOTATE_PATH}/platform/atmel_sam include $(PLATFORM_BASE).mk diff --git a/g2core/board/gquintic/hardware.cpp b/g2core/board/gquintic/0_hardware.cpp similarity index 98% rename from g2core/board/gquintic/hardware.cpp rename to g2core/board/gquintic/0_hardware.cpp index e11d595c0..9a2879bc0 100755 --- a/g2core/board/gquintic/hardware.cpp +++ b/g2core/board/gquintic/0_hardware.cpp @@ -39,12 +39,16 @@ //Motate::ClockOutputPin external_clk_pin {16000000}; // 16MHz optimally Motate::OutputPin external_clk_pin {Motate::kStartLow}; +SPI_CS_PinMux_used_t spiCSPinMux; +SPIBus_used_t spiBus; + /* * hardware_init() - lowest level hardware init */ void hardware_init() { + spiBus.init(); board_hardware_init(); external_clk_pin = 0; // Force external clock to 0 for now. } diff --git a/g2core/board/gquintic/board_stepper.cpp b/g2core/board/gquintic/board_stepper.cpp index cc58f61dc..b588fb42a 100755 --- a/g2core/board/gquintic/board_stepper.cpp +++ b/g2core/board/gquintic/board_stepper.cpp @@ -28,47 +28,38 @@ #include "board_stepper.h" - -Motate::SPIChipSelectPinMux - spiCSPinMux; -SPIBus_used_t spiBus; - // These are identical to board_stepper.h, except for the word "extern" and the initialization -Trinamic2130 - motor_1{spiBus, spiCSPinMux.getCS(4)}; +//Trinamic2130 +// motor_1{spiBus, spiCSPinMux.getCS(4)}; Trinamic2130 - motor_2{spiBus, spiCSPinMux.getCS(3)}; + motor_1{spiBus, spiCSPinMux.getCS(3)}; Trinamic2130 - motor_3{spiBus, spiCSPinMux.getCS(2)}; + motor_2{spiBus, spiCSPinMux.getCS(2)}; Trinamic2130 - motor_4{spiBus, spiCSPinMux.getCS(1)}; + motor_3{spiBus, spiCSPinMux.getCS(1)}; Trinamic2130 - motor_5{spiBus, spiCSPinMux.getCS(0)}; + motor_4{spiBus, spiCSPinMux.getCS(0)}; -StepDirHobbyServo motor_6; +StepDirHobbyServo motor_5; -Stepper* Motors[MOTORS] = {&motor_1, &motor_2, &motor_3, &motor_4, &motor_5, &motor_6}; +Stepper* Motors[MOTORS] = {&motor_1, &motor_2, &motor_3, &motor_4, &motor_5}; +//Stepper* Motors[MOTORS] = {&motor_1, &motor_2, &motor_3, &motor_4, &motor_5, &motor_6}; void board_stepper_init() { - spiBus.init(); - for (uint8_t motor = 0; motor < MOTORS; motor++) { Motors[motor]->init(); } } diff --git a/g2core/board/gquintic/board_stepper.h b/g2core/board/gquintic/board_stepper.h index c2cf6ebe1..e8eac9d68 100755 --- a/g2core/board/gquintic/board_stepper.h +++ b/g2core/board/gquintic/board_stepper.h @@ -32,35 +32,33 @@ #include "tmc2130.h" #include "step_dir_hobbyservo.h" -typedef Motate::SPIBus SPIBus_used_t; - // These are identical to board_stepper.h, except for the word "extern" and the initialization -extern Trinamic2130 - motor_1; +//extern Trinamic2130 +// motor_1; extern Trinamic2130 - motor_2; + motor_1; extern Trinamic2130 - motor_3; + motor_2; extern Trinamic2130 - motor_4; + motor_3; extern Trinamic2130 - motor_5; -extern StepDirHobbyServo motor_6; + motor_4; +extern StepDirHobbyServo motor_5; extern Stepper* Motors[MOTORS]; diff --git a/g2core/board/gquintic/board_xio.cpp b/g2core/board/gquintic/board_xio.cpp index c48356be1..8c8817654 100755 --- a/g2core/board/gquintic/board_xio.cpp +++ b/g2core/board/gquintic/board_xio.cpp @@ -75,7 +75,7 @@ void board_hardware_init(void) // called 1st } -void board_xio_init(void) // called later than board_hardware_init (there are thing in between) +void board_xio_init(void) // called later than board_hardware_init (there are things in between) { // Init SPI #if XIO_HAS_SPI diff --git a/g2core/board/gquintic/gquintic-b-pinout.h b/g2core/board/gquintic/gquintic-b-pinout.h index c0bcf0e38..e3b329798 100755 --- a/g2core/board/gquintic/gquintic-b-pinout.h +++ b/g2core/board/gquintic/gquintic-b-pinout.h @@ -148,7 +148,7 @@ _MAKE_MOTATE_PIN(kSocket2_DirPinNumber, 'A', 25); // _MAKE_MOTATE_PIN(kOutput5_PinNumber, 'A', 26); // TC 2,0 _MAKE_MOTATE_PIN(kSocket3_DirPinNumber, 'A', 27); // On Timer 2! _MAKE_MOTATE_PIN(kUnassigned1, 'A', 28); // DIAG1 -_MAKE_MOTATE_PIN(kUnassigned2, 'A', 29); // +_MAKE_MOTATE_PIN(kUnassigned2, 'A', 29); // NO PHYSICAL PIN _MAKE_MOTATE_PIN(kInput1_PinNumber, 'A', 30); // _MAKE_MOTATE_PIN(kInput4_PinNumber, 'A', 31); // @@ -192,13 +192,13 @@ _MAKE_MOTATE_PIN(kUnassigned6, 'D', 19); // _MAKE_MOTATE_PIN(kSPI0_MISOPinNumber, 'D', 20); // _MAKE_MOTATE_PIN(kSPI0_MOSIPinNumber, 'D', 21); // _MAKE_MOTATE_PIN(kSPI0_SCKPinNumber, 'D', 22); // -_MAKE_MOTATE_PIN(kUnassigned7, 'D', 23); // +_MAKE_MOTATE_PIN(kUnassigned7, 'D', 23); // NO PHYSICAL PIN _MAKE_MOTATE_PIN(kSocket2_StepPinNumber, 'D', 24); // _MAKE_MOTATE_PIN(kSocket2_SPISlaveSelectPinNumber, 'D', 25); // _MAKE_MOTATE_PIN(kOutput9_PinNumber, 'D', 26); // PWM 2 _MAKE_MOTATE_PIN(kSocket1_DirPinNumber, 'D', 27); // _MAKE_MOTATE_PIN(kSocket4_EnablePinNumber, 'D', 28); // -_MAKE_MOTATE_PIN(kUnassigned8, 'D', 29); // +_MAKE_MOTATE_PIN(kUnassigned8, 'D', 29); // NO PHYSICAL PIN _MAKE_MOTATE_PIN(kUnassigned9, 'D', 30); // INTERRUPT_OUT _MAKE_MOTATE_PIN(kUnassigned10, 'D', 31); // diff --git a/g2core/board/gquintic/hardware.h b/g2core/board/gquintic/hardware.h index d82ce5034..40f9baf08 100644 --- a/g2core/board/gquintic/hardware.h +++ b/g2core/board/gquintic/hardware.h @@ -58,7 +58,7 @@ enum hwPlatform { #define AXES 6 // number of axes supported in this version #define HOMING_AXES 4 // number of axes that can be homed (assumes Zxyabc sequence) -#define MOTORS 6 // number of motors on the board - 5 Trinamics + 1 servo +#define MOTORS 5 // number of motors on the board - 5 Trinamics + 1 servo #define COORDS 6 // number of supported coordinate systems (index starts at 1) #define PWMS 2 // number of supported PWM channels #define TOOLS 32 // number of entries in tool table (index starts at 1) @@ -69,6 +69,7 @@ enum hwPlatform { //////////////////////////// #include "MotatePins.h" +#include "MotateSPI.h" #include "MotateTimers.h" // for TimerChanel<> and related... #include "MotateServiceCall.h" // for ServiceCall<> @@ -134,19 +135,19 @@ typedef TimerChannel<11, 0> fwd_plan_timer_type; // request exec timer in step Motate::service_call_number kSPI_ServiceCallNumber = 3; -// Pin assignments +/**** SPI Setup ****/ -pin_number indicator_led_pin_num = Motate::kLED_USBRXPinNumber; -static OutputPin IndicatorLed; +typedef Motate::SPIBus SPIBus_used_t; +extern SPIBus_used_t spiBus; + +typedef Motate::SPIChipSelectPinMux SPI_CS_PinMux_used_t; +extern SPI_CS_PinMux_used_t spiCSPinMux; /**** Motate Global Pin Allocations ****/ -//static OutputPin spi_ss1_pin; -//static OutputPin spi_ss2_pin; -//static OutputPin spi_ss3_pin; -//static OutputPin spi_ss4_pin; -//static OutputPin spi_ss5_pin; -//static OutputPin spi_ss6_pin; +pin_number indicator_led_pin_num = Motate::kLED_USBRXPinNumber; +static OutputPin IndicatorLed; + static OutputPin kinen_sync_pin; static OutputPin grbl_reset_pin; diff --git a/g2core/device/max31865/max31865.h b/g2core/device/max31865/max31865.h new file mode 100644 index 000000000..c393ab98e --- /dev/null +++ b/g2core/device/max31865/max31865.h @@ -0,0 +1,416 @@ +/* + * max31865/max31865.h - suppport for talking to the MAX31865 RTD (PT100) sensor amp/ADC + * This file is part of the G2 project + * + * Copyright (c) 2017 Alden S. Hart, Jr. + * Copyright (c) 2017 Robert Giseburt + * + * This file ("the software") is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License, version 2 as published by the + * Free Software Foundation. You should have received a copy of the GNU General Public + * License, version 2 along with the software. If not, see . + * + * As a special exception, you may use this file as part of a software library without + * restriction. Specifically, if other files instantiate templates or use macros or + * inline functions from this file, or you compile this file and link it with other + * files to produce an executable, this file does not by itself cause the resulting + * executable to be covered by the GNU General Public License. This exception does not + * however invalidate any other reasons why the executable file might be covered by the + * GNU General Public License. + * + * THE SOFTWARE IS DISTRIBUTED IN THE HOPE THAT IT WILL BE USEFUL, BUT WITHOUT ANY + * WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES + * OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT + * SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF + * OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + */ + +// Many thanks to Adafruit! +// More specifically, for their driver at +// https://github.com/adafruit/Adafruit_MAX31865 +// and their breakout board at https://adafru.it/3328 + +#ifndef max31865_h +#define max31865_h + +#include "MotateSPI.h" +#include "MotateBuffer.h" +#include "MotateUtilities.h" // for to/fromLittle/BigEndian + +using Motate::OutputPin; +using Motate::kStartHigh; +using Motate::SPIMessage; +using Motate::SPIInterrupt; +using Motate::SPIDeviceMode; +using Motate::fromBigEndian; +using Motate::toBigEndian; + +// Complete class for MAX31865 drivers. +template +struct MAX31865 final { + // SPI and message handling properties + device_t _device; + SPIMessage _message; + + // Record if we're transmitting to prevent altering the buffers while they + // are being transmitted still. + volatile bool _transmitting = false; + + // We don't want to transmit until we're inited + bool _inited = false; + + // Record what register we just requested, so we know what register the + // the response is for (and to read the response.) + int16_t _active_register = -1; + + // Timer to keep track of when we need to do another periodic update + Motate::Timeout _check_timer; + + // Constructor - this is the only time we directly use the SBIBus + template + MAX31865(SPIBus_t &spi_bus, const chipSelect_t &_cs, bool is_three_pin = false, bool fifty_hz = true) : + _device{spi_bus.getDevice(_cs, + 5000000, + SPIDeviceMode::kSPIMode2 | SPIDeviceMode::kSPI8Bit, + 400, // min_between_cs_delay_ns + 400, // cs_to_sck_delay_ns + 80 // between_word_delay_ns + )} + { + init(is_three_pin, fifty_hz); + }; + + // Prevent copying, and prevent moving (so we know if it happens) + MAX31865(const MAX31865 &) = delete; + MAX31865(MAX31865 &&other) : _device{std::move(other._device)} {}; + + + // ########### + // From here on we store actual values from the MAX31865, and marshall data + // from the in_buffer buffer to them, or from the values to the out_buffer. + + // Note that this includes _startNextReadWrite() and _doneReadingCallback(), + // which are what calls the functions to put data into the out_buffer and + // read data from the in_buffer, respectively. + + // Also, _init() is last, so it can setup a newly created MAX31865 object. + + enum { + CONFIG_reg = 0x00, + RTD_reg = 0x01, + HFAULT_reg = 0x03, + LFAULT_reg = 0x05, + FAULTSTAT_reg = 0x07, + }; + + // IMPORTANT NOTE: The endianness of the ARM is little endian, but other processors + // may be different. + + uint8_t _scribble_buffer[4]; + + struct { + uint8_t address; + union { + uint8_t value; + struct { + uint8_t fifty_or_sixty : 1; // 0 + uint8_t clear_fault : 1; // 1 + uint8_t fault_detection : 2; // 3-2 + uint8_t three_wire : 1; // 4 + uint8_t one_shot : 1; // 5 + uint8_t auto_mode : 1; // 6 + uint8_t v_bias : 1; // 7 + } __attribute__ ((packed)); + }; + } _config; + bool _config_needs_read = false; + bool _config_needs_written = false; + void _postReadConf() {}; + + struct { + uint8_t address; + uint8_t high; + uint8_t low; + } _rtd_value_raw; + float _rtd_value = -1; + bool _rtd_value_needs_read = false; + void _postReadRTD() { + bool fault_detected = _rtd_value_raw.low & 0x01; + uint16_t rtd_value_int = (_rtd_value_raw.high << 7) | (_rtd_value_raw.low >> 1); + _rtd_value = 32768.0/(float)rtd_value_int; + if (fault_detected) { + _fault_status_needs_read = true; + } + if (_interrupt_handler) { + _interrupt_handler(); + } + }; + + struct { + uint8_t address; + uint8_t high; + uint8_t low; + } _fault_high; + bool _fault_high_needs_read = false; + bool _fault_high_needs_written = false; + void _postReadFaultHigh() {}; + + struct { + uint8_t address; + uint8_t high; + uint8_t low; + } _fault_low; + bool _fault_low_needs_read = false; + bool _fault_low_needs_written = false; + void _postReadFaultLow() {}; + + struct { + uint8_t address; + union { + volatile uint8_t value; + struct { + uint8_t _unused : 2; // 1-0 + uint8_t over_under_voltage : 1; // 2 + uint8_t open_detection : 1; // 3 + uint8_t ref_too_low : 1; // 4 + uint8_t ref_too_high : 1; // 5 + uint8_t under_threhold : 1; // 6 + uint8_t over_threshold : 1; // 7 + } __attribute__ ((packed)); + }; + } _fault_status; + bool _fault_status_needs_read = false; + void _postReadFaultStatus() { + /* here is where we would call alarm or something!! */ + }; + + void _startNextReadWrite() + { + if (_transmitting || !_inited) { return; } + _transmitting = true; // preemptively say we're transmitting .. as a mutex + + // We request the next register, and keep track of how long it is. + uint8_t next_reg = 0; + uint8_t *data_buffer = nullptr; + int8_t register_size; + + // We write before we read -- so we don't lose what we set in the registers when writing + + // check if we need to write registers + if (_config_needs_written) { next_reg = 0x80 | CONFIG_reg; data_buffer = (uint8_t*)&_config; register_size = 1; _config_needs_written = false; } else + if (_fault_high_needs_written) { next_reg = 0x80 | HFAULT_reg; data_buffer = (uint8_t*)&_fault_high; register_size = 2; _fault_high_needs_written = false; } else + if (_fault_low_needs_written) { next_reg = 0x80 | LFAULT_reg; data_buffer = (uint8_t*)&_fault_low; register_size = 2; _fault_low_needs_written = false; } else + + // check if we need to read reagisters + if (_config_needs_read) { next_reg = CONFIG_reg; data_buffer = (uint8_t*)&_config; register_size = 1; _config_needs_read = false; } else + if (_rtd_value_needs_read) { next_reg = RTD_reg; data_buffer = (uint8_t*)&_rtd_value_raw; register_size = 2; _rtd_value_needs_read = false; } else + if (_fault_high_needs_read) { next_reg = HFAULT_reg; data_buffer = (uint8_t*)&_fault_high; register_size = 2; _fault_high_needs_read = false; } else + if (_fault_low_needs_read) { next_reg = LFAULT_reg; data_buffer = (uint8_t*)&_fault_low; register_size = 2; _fault_low_needs_read = false; } else + if (_fault_status_needs_read) { next_reg = FAULTSTAT_reg; data_buffer = (uint8_t*)&_fault_status; register_size = 1; _fault_status_needs_read = false; } else + + // otherwise we're done here + { + _active_register = -1; + _transmitting = false; // we're not really transmitting. + return; + } + + _active_register = next_reg; + *data_buffer = next_reg; + + if (next_reg & 0x80) { + // writing, copy what we're + _scribble_buffer[0] = data_buffer[0]; + _scribble_buffer[1] = 0xFF; + _scribble_buffer[2] = 0xFF; + _scribble_buffer[3] = 0xFF; + + _message.setup(data_buffer, _scribble_buffer, 1+register_size, SPIMessage::DeassertAfter, SPIMessage::EndTransaction); + } else { + _scribble_buffer[0] = data_buffer[0]; + _scribble_buffer[1] = 0xFF; + _scribble_buffer[2] = 0xFF; + _scribble_buffer[3] = 0xFF; + + _message.setup(_scribble_buffer, data_buffer, 1+register_size, SPIMessage::DeassertAfter, SPIMessage::EndTransaction); + } + _device.queueMessage(&_message); + }; + + void _doneReadingCallback() + { + _transmitting = false; + + // Check to make sure it was a read, and handle it accordingly + if (0 == (_active_register & 0x80)) { + switch (_active_register) { + case CONFIG_reg: _postReadConf(); break; + case RTD_reg: _postReadRTD(); break; + case HFAULT_reg: _postReadFaultHigh(); break; + case LFAULT_reg: _postReadFaultLow(); break; + case FAULTSTAT_reg: _postReadFaultStatus(); break; + + default: + break; + } + } + + _active_register = -1; + _startNextReadWrite(); + }; + + void init(bool is_three_pin = false, bool fifty_hz = false) + { + _message.message_done_callback = [&] { this->_doneReadingCallback(); }; + + // Establish default values, and then prepare to read the registers we can to establish starting values + + _config.v_bias = false; // effectively enable the device + _config.auto_mode = false; // automatically run conversions + _config.one_shot = false; // this is a command + _config.fault_detection = 0; // this is a command - run automatic fault detection + _config.clear_fault = false; // this is a command, and we want to execture it + _config.fifty_or_sixty = fifty_hz; // this is a command + _config_needs_written = false; + //_config_needs_read = true; + + _fault_high = {HFAULT_reg, 0xff, 0xff}; //_fault_high_needs_read = true; + _fault_low = {LFAULT_reg, 0x00, 0x00}; //_fault_low_needs_read = true; + + _inited = true; + //_startNextReadWrite(); + _check_timer.set(fifty_hz ? 1000/50 : 1000/60); + }; + + // interface to make this a drop-in replacement (after init) for an ADCPin + + float _vref = 3.3; + std::function _interrupt_handler; + + enum { + INITING, + SETUP_WIRES, + CLEAR_FAULT, + SETUP_BIAS, + NEEDS_SAMPLED, + WAITING_FOR_SAMPLE + } _state; + + void startSampling() + { + if (_check_timer.isPast()) { + if (INITING == _state) { + _config_needs_read = true; + _fault_high_needs_read = true; + _fault_low_needs_read = true; + + _check_timer.set(10); + _startNextReadWrite(); + _state = SETUP_WIRES; + } + else if (SETUP_WIRES == _state) { + _config.three_wire = false; + _config_needs_written = true; + _config_needs_read = true; + + _check_timer.set(10); + _startNextReadWrite(); + _state = CLEAR_FAULT; + } + else if (CLEAR_FAULT == _state) { + _config.clear_fault = true; + _config_needs_written = true; + _config_needs_read = true; + + _check_timer.set(10); + _startNextReadWrite(); + _state = SETUP_BIAS; + } + else if (SETUP_BIAS == _state) { + _config.v_bias = true; + _config_needs_written = true; + _config_needs_read = true; + + _check_timer.set(10); + _startNextReadWrite(); + _state = NEEDS_SAMPLED; + } + else if (NEEDS_SAMPLED == _state) { + _config.one_shot = true; + _config_needs_written = true; + _config_needs_read = true; + + _check_timer.set(70); + _startNextReadWrite(); + _state = WAITING_FOR_SAMPLE; + } + else if (WAITING_FOR_SAMPLE == _state) { + _rtd_value_needs_read = true; + + _check_timer.set(1); + _startNextReadWrite(); + _state = SETUP_BIAS; + } + } + }; + + int32_t getRaw() { + uint16_t rtd_value_int = (_rtd_value_raw.high << 7) | (_rtd_value_raw.low >> 1); + return rtd_value_int; + }; + int32_t getValue() { + return _rtd_value; + }; + int32_t getBottom() { + return 0; + }; + float getBottomVoltage() { + return 0; + }; + int32_t getTop() { + return 32767; + }; + float getTopVoltage() { + return _vref; + }; + + void setVoltageRange(const float vref, const float min_expected = 0, const float max_expected = -1, const bool differential = false, const float ideal_steps = 1) + { + _vref = vref; + + // uint16_t min_expected_int = (uint16_t)((min_expected/vref) * 32767.0) << 1; + // fault_low.high = (min_expected_int >> 8) & 0xff; + // fault_low.low = min_expected_int & 0xff; + // fault_low_needs_written = true; + // + // if (max_expected > 0) { + // uint16_t max_expected_int = (uint16_t)((max_expected/vref) * 32767.0) << 1; + // fault_high.high = (max_expected_int >> 8) & 0xff; + // fault_high.low = max_expected_int & 0xff; + // fault_high_needs_written = true; + // } + + // differential should always be false + // we can't control the resolution, so ignore ideal_steps too + }; + float getVoltage() { + return _rtd_value * _vref; + }; + operator float() { return getVoltage(); }; + + void setInterrupts(const uint32_t interrupts) { + // ignore this -- it's too dangerous to accidentally change the SPI interrupts + }; + + // We can only support interrupt inferface option 2: a function with a closure or function pointer + void setInterruptHandler(std::function &&handler) { + _interrupt_handler = std::move(handler); + }; + void setInterruptHandler(const std::function &handler) { + _interrupt_handler = handler; + }; + +}; + +#endif // max31865_h diff --git a/g2core/device/trinamic/tmc2130.h b/g2core/device/trinamic/tmc2130.h index d522c7dcc..1c189470f 100644 --- a/g2core/device/trinamic/tmc2130.h +++ b/g2core/device/trinamic/tmc2130.h @@ -91,11 +91,11 @@ struct Trinamic2130 final : Stepper { template Trinamic2130(SPIBus_t &spi_bus, const chipSelect_t &_cs) : _device{spi_bus.getDevice(_cs, - 4000000, //1MHz - SPIDeviceMode::kSPIMode2 | SPIDeviceMode::kSPI8Bit, + 4000000, //4MHz + SPIDeviceMode::kSPIMode1 | SPIDeviceMode::kSPI8Bit, 0, // min_between_cs_delay_ns 10, // cs_to_sck_delay_ns - 0 // between_word_delay_ns + 1 // between_word_delay_ns )} {}; diff --git a/g2core/g2core.xcodeproj/project.pbxproj b/g2core/g2core.xcodeproj/project.pbxproj index 66321df61..56400b461 100644 --- a/g2core/g2core.xcodeproj/project.pbxproj +++ b/g2core/g2core.xcodeproj/project.pbxproj @@ -232,6 +232,20 @@ passBuildSettingsInEnvironment = 1; productName = g3_due; }; + D43DFE011E8C84B400A2030D /* G2 gQuadratic Ultimaker2+ */ = { + isa = PBXLegacyTarget; + buildArgumentsString = "$(ACTION) VERBOSE=1 COLOR=0 CONFIG=Ultimaker2Plus DEBUG=0"; + buildConfigurationList = D43DFE021E8C84B400A2030D /* Build configuration list for PBXLegacyTarget "G2 gQuadratic Ultimaker2+" */; + buildPhases = ( + ); + buildToolPath = /usr/bin/make; + buildWorkingDirectory = .; + dependencies = ( + ); + name = "G2 gQuadratic Ultimaker2+"; + passBuildSettingsInEnvironment = 1; + productName = g3_due; + }; D43FF7141D537A5C00FB5B53 /* G2 gQuadratic Test */ = { isa = PBXLegacyTarget; buildArgumentsString = "$(ACTION) VERBOSE=1 COLOR=0 CONFIG=TestQuadratic DEBUG=2"; @@ -290,7 +304,7 @@ }; D492E5AE1E54C2B4005ED97D /* G2 gQuadratic AxiDraw v3 */ = { isa = PBXLegacyTarget; - buildArgumentsString = "$(ACTION) VERBOSE=1 COLOR=0 CONFIG=AxiDrawv3 DEBUG=2"; + buildArgumentsString = "$(ACTION) VERBOSE=1 COLOR=0 CONFIG=AxiDrawv3 DEBUG=0"; buildConfigurationList = D492E5AF1E54C2B4005ED97D /* Build configuration list for PBXLegacyTarget "G2 gQuadratic AxiDraw v3" */; buildPhases = ( ); @@ -426,6 +440,7 @@ D457112317053BFB00EA19A8 /* index */, D4782AB61D9E39EC00B32136 /* G2 EggBot */, D492E5AE1E54C2B4005ED97D /* G2 gQuadratic AxiDraw v3 */, + D43DFE011E8C84B400A2030D /* G2 gQuadratic Ultimaker2+ */, ); }; /* End PBXProject section */ @@ -505,6 +520,22 @@ }; name = Release; }; + D43DFE031E8C84B400A2030D /* Debug */ = { + isa = XCBuildConfiguration; + buildSettings = { + PATH = "$PATH:/usr/local/gcc-arm-none-eabi/bin"; + PRODUCT_NAME = "$(TARGET_NAME)"; + }; + name = Debug; + }; + D43DFE041E8C84B400A2030D /* Release */ = { + isa = XCBuildConfiguration; + buildSettings = { + PATH = "$PATH:/usr/local/gcc-arm-none-eabi/bin"; + PRODUCT_NAME = "$(TARGET_NAME)"; + }; + name = Release; + }; D43FF7161D537A5C00FB5B53 /* Debug */ = { isa = XCBuildConfiguration; buildSettings = { @@ -817,6 +848,15 @@ defaultConfigurationIsVisible = 0; defaultConfigurationName = Release; }; + D43DFE021E8C84B400A2030D /* Build configuration list for PBXLegacyTarget "G2 gQuadratic Ultimaker2+" */ = { + isa = XCConfigurationList; + buildConfigurations = ( + D43DFE031E8C84B400A2030D /* Debug */, + D43DFE041E8C84B400A2030D /* Release */, + ); + defaultConfigurationIsVisible = 0; + defaultConfigurationName = Release; + }; D43FF7151D537A5C00FB5B53 /* Build configuration list for PBXLegacyTarget "G2 gQuadratic Test" */ = { isa = XCConfigurationList; buildConfigurations = ( diff --git a/g2core/settings/settings_Ultimaker_2_Plus.h b/g2core/settings/settings_Ultimaker_2_Plus.h index 3c04e7579..7edf42aec 100644 --- a/g2core/settings/settings_Ultimaker_2_Plus.h +++ b/g2core/settings/settings_Ultimaker_2_Plus.h @@ -259,6 +259,8 @@ //** Temperature Sensors ** +#include "device/max31865/max31865.h" + #define HAS_TEMPERATURE_SENSOR_1 true #if HAS_TEMPERATURE_SENSOR_1 // Must choose Thermistor or PT100 @@ -269,8 +271,10 @@ /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ } #else - #define TEMPERATURE_SENSOR_1_TYPE PT100> - #define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 100, /*inline_resistance*/0, /*wheatstone*/ true} + //#define TEMPERATURE_SENSOR_1_TYPE PT100> + //#define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 2200, /*inline_resistance*/0.003, /*differential*/ true} + #define TEMPERATURE_SENSOR_1_TYPE PT100> + #define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 2200, /*inline_resistance*/0.003, /*differential*/ false, spiBus, spiCSPinMux.getCS(6)} #endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_1 @@ -287,7 +291,7 @@ } #else #define TEMPERATURE_SENSOR_2_TYPE PT100> - #define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 100, /*inline_resistance*/0} + #define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 2200, /*inline_resistance*/0} #endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_2 @@ -303,7 +307,7 @@ } #else #define TEMPERATURE_SENSOR_3_TYPE PT100> - #define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 100, /*inline_resistance*/0, /*wheatstone*/ true} + #define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 2200, /*inline_resistance*/0.003, /*differential*/ true} #endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_3 diff --git a/g2core/settings/settings_axidraw_v3.h b/g2core/settings/settings_axidraw_v3.h index 0e78157c6..6d2b39782 100755 --- a/g2core/settings/settings_axidraw_v3.h +++ b/g2core/settings/settings_axidraw_v3.h @@ -27,11 +27,13 @@ */ /***********************************************************************/ -/**** TestV9 profile - naked board *************************************/ +/**** AxiDraw v3 Configuration *****************************************/ /***********************************************************************/ +#include "hardware.h" + // ***> NOTE: The init message must be a single line with no CRs or LFs -#define INIT_MESSAGE "Initializing configs to WaterColorBot v2 settings" +#define INIT_MESSAGE "Initializing configs to AxiDraw v3 settings" #define JUNCTION_INTEGRATION_TIME 2.5 // cornering - usually between 0.5 and 2.0 (higher is faster) #define CHORDAL_TOLERANCE 0.01 // chordal accuracy for arc drawing (in mm) diff --git a/g2core/temperature.cpp b/g2core/temperature.cpp index 264d4582f..ea2546f59 100755 --- a/g2core/temperature.cpp +++ b/g2core/temperature.cpp @@ -250,7 +250,7 @@ template struct PT100 { float pullup_resistance; float inline_resistance; - bool wheatstone; + bool differential; ADC_t adc_pin {kNormal, [&]{this->adc_has_new_value();} }; float raw_adc_voltage = 0.0; @@ -258,16 +258,31 @@ struct PT100 { typedef PT100 type; - PT100(const float pullup_resistance_, const float inline_resistance_, const bool wheatstone_ = false) + PT100(const float pullup_resistance_, const float inline_resistance_, const bool differential_ = false) : pullup_resistance{ pullup_resistance_ }, inline_resistance{ inline_resistance_ }, - wheatstone{wheatstone_} + differential{differential_} { adc_pin.setInterrupts(kPinInterruptOnChange|kInterruptPriorityLow); adc_pin.setVoltageRange(kSystemVoltage, get_voltage_of_temp(min_temp), get_voltage_of_temp(max_temp), - wheatstone, // if wheatstone, then differential + differential, + 6400.0); + }; + + template + PT100(const float pullup_resistance_, const float inline_resistance_, const bool differential_ = false, Ts&&... additional_values) + : pullup_resistance{ pullup_resistance_ }, + inline_resistance{ inline_resistance_ }, + differential{differential_}, + adc_pin {additional_values...} + { + adc_pin.setInterrupts(kPinInterruptOnChange|kInterruptPriorityLow); + adc_pin.setVoltageRange(kSystemVoltage, + get_voltage_of_temp(min_temp), + get_voltage_of_temp(max_temp), + differential, 6400.0); }; @@ -275,8 +290,8 @@ struct PT100 { // R = 100(1 + A*T + B*T^2); A = 3.9083*10^-3; B = -5.775*10^-7 float r = 100 * (1 + 0.0039083*t + -0.0000005775*t*t) + inline_resistance; - if (wheatstone) { - return (r - pullup_resistance)/(2.0*(pullup_resistance + r)); + if (differential) { + return (kSystemVoltage * r)/(2.0 * pullup_resistance + r); } return r/(r+pullup_resistance)*kSystemVoltage; }; @@ -293,9 +308,9 @@ struct PT100 { float get_resistance() { float r; - if (wheatstone) { + if (differential) { float v = raw_adc_voltage / kSystemVoltage; - r = pullup_resistance*(1-2.0*v)/(2.0*v+1.0) - inline_resistance; + r = (v * 2.0 * pullup_resistance)/(1.0 - v) - inline_resistance; } else { float v = raw_adc_voltage; r = ((pullup_resistance * v) / (kSystemVoltage - v)) - inline_resistance; @@ -317,7 +332,7 @@ struct PT100 { // Call back function from the ADC to tell it that the ADC has a new sample... void adc_has_new_value() { - raw_adc_voltage = (raw_adc_voltage * 10.0 + adc_pin.getVoltage())/11.0; + raw_adc_voltage = (raw_adc_voltage*10.0 + adc_pin.getVoltage())/11.0; raw_adc_value = adc_pin.getRaw(); }; }; From 443e6f7e8bd28a9588dc45d6a9b81e1d18170d8a Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Thu, 30 Mar 2017 19:26:25 -0500 Subject: [PATCH 056/193] Fixed missing interrupt call from max31865 synthetic ADC --- g2core/device/max31865/max31865.h | 68 +++++++++++++++++++++++-------- g2core/temperature.cpp | 2 +- 2 files changed, 51 insertions(+), 19 deletions(-) diff --git a/g2core/device/max31865/max31865.h b/g2core/device/max31865/max31865.h index c393ab98e..db4f56f30 100644 --- a/g2core/device/max31865/max31865.h +++ b/g2core/device/max31865/max31865.h @@ -69,7 +69,12 @@ struct MAX31865 final { // Constructor - this is the only time we directly use the SBIBus template - MAX31865(SPIBus_t &spi_bus, const chipSelect_t &_cs, bool is_three_pin = false, bool fifty_hz = true) : + MAX31865(SPIBus_t &spi_bus, + const chipSelect_t &_cs, + bool is_three_pin = false, + bool fifty_hz = true + ) + : _device{spi_bus.getDevice(_cs, 5000000, SPIDeviceMode::kSPIMode2 | SPIDeviceMode::kSPI8Bit, @@ -81,6 +86,26 @@ struct MAX31865 final { init(is_three_pin, fifty_hz); }; + template + MAX31865(std::function &&_interrupt, + SPIBus_t &spi_bus, + const chipSelect_t &_cs, + bool is_three_pin = false, + bool fifty_hz = true + ) + : + _device{spi_bus.getDevice(_cs, + 5000000, + SPIDeviceMode::kSPIMode2 | SPIDeviceMode::kSPI8Bit, + 400, // min_between_cs_delay_ns + 400, // cs_to_sck_delay_ns + 80 // between_word_delay_ns + )}, + _interrupt_handler{std::move(_interrupt)} + { + init(is_three_pin, fifty_hz); + }; + // Prevent copying, and prevent moving (so we know if it happens) MAX31865(const MAX31865 &) = delete; MAX31865(MAX31865 &&other) : _device{std::move(other._device)} {}; @@ -96,6 +121,15 @@ struct MAX31865 final { // Also, _init() is last, so it can setup a newly created MAX31865 object. + enum { + INITING, + SETUP_WIRES, + CLEAR_FAULT, + SETUP_BIAS, + NEEDS_SAMPLED, + WAITING_FOR_SAMPLE + } _state; + enum { CONFIG_reg = 0x00, RTD_reg = 0x01, @@ -126,7 +160,15 @@ struct MAX31865 final { } _config; bool _config_needs_read = false; bool _config_needs_written = false; - void _postReadConf() {}; + void _postReadConf() { + if (WAITING_FOR_SAMPLE == _state) { + if (!_config.one_shot) { + _rtd_value_needs_read = true; + } else { +// _config_needs_read = true; + } + } + }; struct { uint8_t address; @@ -138,13 +180,14 @@ struct MAX31865 final { void _postReadRTD() { bool fault_detected = _rtd_value_raw.low & 0x01; uint16_t rtd_value_int = (_rtd_value_raw.high << 7) | (_rtd_value_raw.low >> 1); - _rtd_value = 32768.0/(float)rtd_value_int; + _rtd_value = (float)rtd_value_int / 32768.0; if (fault_detected) { _fault_status_needs_read = true; } if (_interrupt_handler) { _interrupt_handler(); } + _state = NEEDS_SAMPLED; }; struct { @@ -288,15 +331,6 @@ struct MAX31865 final { float _vref = 3.3; std::function _interrupt_handler; - enum { - INITING, - SETUP_WIRES, - CLEAR_FAULT, - SETUP_BIAS, - NEEDS_SAMPLED, - WAITING_FOR_SAMPLE - } _state; - void startSampling() { if (_check_timer.isPast()) { @@ -305,7 +339,7 @@ struct MAX31865 final { _fault_high_needs_read = true; _fault_low_needs_read = true; - _check_timer.set(10); + _check_timer.set(1); _startNextReadWrite(); _state = SETUP_WIRES; } @@ -323,7 +357,7 @@ struct MAX31865 final { _config_needs_written = true; _config_needs_read = true; - _check_timer.set(10); + _check_timer.set(1); _startNextReadWrite(); _state = SETUP_BIAS; } @@ -341,16 +375,14 @@ struct MAX31865 final { _config_needs_written = true; _config_needs_read = true; - _check_timer.set(70); + _check_timer.set(1); _startNextReadWrite(); _state = WAITING_FOR_SAMPLE; } else if (WAITING_FOR_SAMPLE == _state) { - _rtd_value_needs_read = true; - + _config_needs_read = true; _check_timer.set(1); _startNextReadWrite(); - _state = SETUP_BIAS; } } }; diff --git a/g2core/temperature.cpp b/g2core/temperature.cpp index ea2546f59..034adc392 100755 --- a/g2core/temperature.cpp +++ b/g2core/temperature.cpp @@ -276,7 +276,7 @@ struct PT100 { : pullup_resistance{ pullup_resistance_ }, inline_resistance{ inline_resistance_ }, differential{differential_}, - adc_pin {additional_values...} + adc_pin {[&]{this->adc_has_new_value();}, additional_values...} { adc_pin.setInterrupts(kPinInterruptOnChange|kInterruptPriorityLow); adc_pin.setVoltageRange(kSystemVoltage, From ace207608d018da8677f6ac289348c57276abf88 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Wed, 5 Apr 2017 08:38:11 -0500 Subject: [PATCH 057/193] Minor cleanup, tuning, and notes --- g2core/board/gquintic/gquintic-b-pinout.h | 8 +- g2core/plan_line.cpp | 12 +-- g2core/settings/settings_Ultimaker_2_Plus.h | 102 +++++++++----------- g2core/temperature.cpp | 45 ++++++--- 4 files changed, 84 insertions(+), 83 deletions(-) diff --git a/g2core/board/gquintic/gquintic-b-pinout.h b/g2core/board/gquintic/gquintic-b-pinout.h index e3b329798..3113edb6d 100755 --- a/g2core/board/gquintic/gquintic-b-pinout.h +++ b/g2core/board/gquintic/gquintic-b-pinout.h @@ -135,10 +135,10 @@ _MAKE_MOTATE_PIN(kOutput8_PinNumber, 'A', 13); // PWM 2 _MAKE_MOTATE_PIN(kSocket1_StepPinNumber, 'A', 14); // _MAKE_MOTATE_PIN(kOutput3_PinNumber, 'A', 15); // TC 1,0 _MAKE_MOTATE_PIN(kOutput4_PinNumber, 'A', 16); // TC 1,1 -_MAKE_MOTATE_PIN(kADC4_PinNumber, 'A', 17); // -_MAKE_MOTATE_PIN(kADC3_PinNumber, 'A', 18); // -_MAKE_MOTATE_PIN(kADC2_PinNumber, 'A', 19); // -_MAKE_MOTATE_PIN(kADC1_PinNumber, 'A', 20); // +_MAKE_MOTATE_PIN(kADC4_PinNumber, 'A', 17); // AFEC0,6 +_MAKE_MOTATE_PIN(kADC3_PinNumber, 'A', 18); // AFEC0,7 +_MAKE_MOTATE_PIN(kADC2_PinNumber, 'A', 19); // AFEC0,8 +_MAKE_MOTATE_PIN(kADC1_PinNumber, 'A', 20); // AFEC0,9 _MAKE_MOTATE_PIN(kSerial_CTSPinNumber, 'A', 21); // _MAKE_MOTATE_PIN(kSocket1_EnablePinNumber, 'A', 22); // _MAKE_MOTATE_PIN(kOutput10_PinNumber, 'A', 23); // PWM 8+2 diff --git a/g2core/plan_line.cpp b/g2core/plan_line.cpp index ab00ce8ce..892330e8a 100644 --- a/g2core/plan_line.cpp +++ b/g2core/plan_line.cpp @@ -537,7 +537,7 @@ static void _calculate_jerk(mpBuf_t* bf) const float q = 2.40281141413; // (sqrt(10)/(3^(1/4))) const float sqrt_j = sqrt(bf->jerk); bf->sqrt_j = sqrt_j; - bf->q_recip_2_sqrt_j = q / (2 * sqrt_j); + bf->q_recip_2_sqrt_j = q / (2.0 * sqrt_j); } /* @@ -712,11 +712,11 @@ static void _calculate_junction_vmax(mpBuf_t* bf) if (delta > EPSILON) { // formula (4): (See Note 1, above) - // velocity = min(velocity, (cm.a[axis].max_junction_accel / delta)); - if ((cm.a[axis].max_junction_accel / delta) < velocity) { - velocity = (cm.a[axis].max_junction_accel / delta); - // bf->jerk_axis = axis; - } + velocity = min(velocity, (cm.a[axis].max_junction_accel / delta)); +// if ((cm.a[axis].max_junction_accel / delta) < velocity) { +// velocity = (cm.a[axis].max_junction_accel / delta); +// // bf->jerk_axis = axis; +// } } } } diff --git a/g2core/settings/settings_Ultimaker_2_Plus.h b/g2core/settings/settings_Ultimaker_2_Plus.h index 7edf42aec..6ffe628d0 100644 --- a/g2core/settings/settings_Ultimaker_2_Plus.h +++ b/g2core/settings/settings_Ultimaker_2_Plus.h @@ -39,7 +39,7 @@ //**** GLOBAL / GENERAL SETTINGS ****************************************************** -#define JUNCTION_INTEGRATION_TIME 1.15 // cornering - between 0.10 and 2.00 (higher is faster) +#define JUNCTION_INTEGRATION_TIME 0.8 // cornering - between 0.10 and 2.00 (higher is faster) #define CHORDAL_TOLERANCE 0.01 // chordal accuracy for arc drawing (in mm) #define SOFT_LIMIT_ENABLE 0 // 0=off, 1=on @@ -81,8 +81,8 @@ //#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","he1t","he1st","he1at","he1op","pid1p","pid1i","pid1d","feed","vel","unit","path","stat" // Defaults for thermistor tuning -#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","he1t","he1st","he1at","he1tr","he1tv","he1op","he2t","he2st","he2at","he2tr","he2tv","he1op","he3t","he3st","he3at","he3tr","he3tv","he1op","feed","vel","unit","path","stat" - +#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","he1t","he1st","he1at","he1tr","he1tv","he1op","he2t","he2st","he2at","he2tr","he2tv","he2op","he3t","he3st","he3at","he3tr","he3tv","he3op","feed","vel","unit","path","stat" +//{sr:{"line":t,"posx":t,"posy":t,"posz":t,"posa":t,"he1t":t,"he1st":t,"he1at":t,"he1tr":t,"he1tv":t,"he1op":t,"he3t":t,"he3st":t,"he3at":t,"he3tr":t,"he3tv":t,"he3op":t,"feed":t,"vel":t,"unit":t,"path":t,"stat":t}} // Gcode startup defaults #define GCODE_DEFAULT_UNITS MILLIMETERS // MILLIMETERS or INCHES #define GCODE_DEFAULT_PLANE CANON_PLANE_XY // CANON_PLANE_XY, CANON_PLANE_XZ, or CANON_PLANE_YZ @@ -104,7 +104,7 @@ #define M1_MICROSTEPS 32 // 1mi 1,2,4,8,16,32 #define M1_POLARITY 0 // 1po 0=normal, 1=reversed #define M1_POWER_MODE MOTOR_POWER_MODE // 1pm standard -#define M1_POWER_LEVEL 0.7 // 1mp +#define M1_POWER_LEVEL 0.9 // 1mp // 80 steps/mm at 1/16 microstepping = 40 mm/rev #define M2_MOTOR_MAP AXIS_Y @@ -114,7 +114,7 @@ #define M2_MICROSTEPS 32 #define M2_POLARITY 1 #define M2_POWER_MODE MOTOR_POWER_MODE -#define M2_POWER_LEVEL 0.7 +#define M2_POWER_LEVEL 0.9 #define M3_MOTOR_MAP AXIS_Z #define M3_STEP_ANGLE 1.8 @@ -122,8 +122,8 @@ #define M3_TRAVEL_PER_REV 8 #define M3_MICROSTEPS 32 #define M3_POLARITY 0 -#define M3_POWER_MODE MOTOR_POWER_MODE -#define M3_POWER_LEVEL 0.7 +#define M3_POWER_MODE MOTOR_ALWAYS_POWERED +#define M3_POWER_LEVEL 0.9 #define M4_MOTOR_MAP AXIS_A #define M4_STEP_ANGLE 1.8 @@ -145,7 +145,7 @@ // *** axis settings ********************************************************************************** #define X_AXIS_MODE AXIS_STANDARD // xam see canonical_machine.h cmAxisMode for valid values -#define X_VELOCITY_MAX 15000 // xvm G0 max velocity in mm/min +#define X_VELOCITY_MAX 12000 // xvm G0 max velocity in mm/min #define X_FEEDRATE_MAX X_VELOCITY_MAX // xfr G1 max feed rate in mm/min #define X_TRAVEL_MIN 0 // xtn minimum travel - used by soft limits and homing #define X_TRAVEL_MAX 230 // xtm travel between switches or crashes @@ -159,7 +159,7 @@ #define X_ZERO_BACKOFF 0.5 // xzb mm #define Y_AXIS_MODE AXIS_STANDARD -#define Y_VELOCITY_MAX 15000 +#define Y_VELOCITY_MAX 12000 #define Y_FEEDRATE_MAX Y_VELOCITY_MAX #define Y_TRAVEL_MIN 0 #define Y_TRAVEL_MAX 224.5 @@ -177,23 +177,22 @@ #define Z_FEEDRATE_MAX Z_VELOCITY_MAX #define Z_TRAVEL_MIN 0 #define Z_TRAVEL_MAX 215 -#define Z_JERK_MAX 1500 -#define Z_JERK_HIGH_SPEED 3000 +#define Z_JERK_MAX 500 +#define Z_JERK_HIGH_SPEED 1000 #define Z_HOMING_INPUT 6 #define Z_HOMING_DIRECTION 1 -#define Z_SEARCH_VELOCITY 300 +#define Z_SEARCH_VELOCITY 1000 #define Z_LATCH_VELOCITY 100 #define Z_LATCH_BACKOFF 2 #define Z_ZERO_BACKOFF 0 -#define G55_Z_OFFSET 0.5 +#define G55_Z_OFFSET 0.6 // Rotary values are chosen to make the motor react the same as X for testing /*************************************************************************************** * To calculate the speeds here, in Wolfram Alpha-speak: * - * c=2*pi*r, r=0.609, d=c/360, s=((S*60)/d), S=40 for s - * c=2*pi*r, r=4.28394, d=c/360, s=((S*60)/d), S=40 for s + * c=2*pi*r, r=1.428, d=c/360, s=((S*60)/d), S=40 for s * * Change r to A_RADIUS, and S to the desired speed, in mm/s or mm/s/s/s. * @@ -207,52 +206,34 @@ ***************************************************************************************/ #define A_AXIS_MODE AXIS_RADIUS -// Marlin says 282 steps/unit, and 8 microsteps, with a 200-step/rev motor = 5.6737588652 mm/rev circumference -// Which yields a radius of 0.9030067693 -#define A_RADIUS 0.9030067693 -//#define A_VELOCITY_MAX 25920.0 // ~40 mm/s, 2,400 mm/min -//#define A_FEEDRATE_MAX 25920.0/2.0 // ~20 mm/s, 1,200 mm/min -#define A_VELOCITY_MAX 77760.0 // G0 rate ~120 mm/s, 2,400 mm/min -#define A_FEEDRATE_MAX 16050 // ~10 mm/s -//#define A_FEEDRATE_MAX 9720.0 // 9720.0 = G1 rate ~15 mm/s, 900 mm/min +#define A_RADIUS 1.428 +#define A_VELOCITY_MAX 144443.0 // G0 rate ~60 mm/s, 3,600 mm/min +#define A_FEEDRATE_MAX 60184.6 // ~25 mm/s #define A_TRAVEL_MIN 0 #define A_TRAVEL_MAX 10 -//#define A_JERK_MAX 81000 // 250 million mm/min^3 = 324000 -#define A_JERK_MAX 162000 // 250 million mm/min^3 = 324000 -//#define A_JERK_MAX 324000 // 500 million mm/min^3 = 324000 -//#define A_JERK_MAX 648000 // 1,000 million mm/min^3 = 648000 -// * a million IF it's over a million -// c=2*pi*r, r=5.30516476972984, d=c/360, s=((1000*60)/d) +#define A_JERK_MAX 144443.2 // ~60 million mm/min^3 #define A_HOMING_INPUT 0 #define A_HOMING_DIRECTION 0 #define A_SEARCH_VELOCITY 2000 #define A_LATCH_VELOCITY 2000 #define A_LATCH_BACKOFF 5 #define A_ZERO_BACKOFF 2 -#define A_JERK_HIGH_SPEED A_JERK_MAX - -#define B_AXIS_MODE AXIS_DISABLED -#define B_RADIUS 0.9030067693 -//#define B_VELOCITY_MAX 25920.0 // ~40 mm/s, 2,400 mm/min -//#define B_FEEDRATE_MAX 25920.0/2.0 // ~20 mm/s, 1,200 mm/min -#define B_VELOCITY_MAX 77760.0 // G0 rate ~120 mm/s, 2,400 mm/min -#define B_FEEDRATE_MAX 16050 // ~10 mm/s -//#define B_FEEDRATE_MAX 9720.0 // 9720.0 = G1 rate ~15 mm/s, 900 mm/min +#define A_JERK_HIGH_SPEED 361108.0 // ~150 million mm/min^3 + +#define B_AXIS_MODE AXIS_RADIUS +#define B_RADIUS 1.428 +#define B_VELOCITY_MAX 144443.0 // G0 rate ~60 mm/s, 3,600 mm/min +#define B_FEEDRATE_MAX 96295.4 // ~40 mm/s #define B_TRAVEL_MIN 0 #define B_TRAVEL_MAX 10 -//#define B_JERK_MAX 81000 // 250 million mm/min^3 = 324000 -#define B_JERK_MAX 162000 // 250 million mm/min^3 = 324000 -//#define B_JERK_MAX 324000 // 500 million mm/min^3 = 324000 -//#define B_JERK_MAX 648000 // 1,000 million mm/min^3 = 648000 -// * a million IF it's over a million -// c=2*pi*r, r=5.30516476972984, d=c/360, s=((1000*60)/d) +#define B_JERK_MAX 180554.0 // ~75 million mm/min^3 #define B_HOMING_INPUT 0 #define B_HOMING_DIRECTION 0 #define B_SEARCH_VELOCITY 2000 #define B_LATCH_VELOCITY 2000 #define B_LATCH_BACKOFF 5 #define B_ZERO_BACKOFF 2 -#define B_JERK_HIGH_SPEED B_JERK_MAX +#define B_JERK_HIGH_SPEED 361108.0 // ~150 million mm/min^3 //*** Input / output settings *** @@ -271,14 +252,14 @@ /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ } #else - //#define TEMPERATURE_SENSOR_1_TYPE PT100> - //#define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 2200, /*inline_resistance*/0.003, /*differential*/ true} +// #define TEMPERATURE_SENSOR_1_TYPE PT100> +// #define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 2200, /*inline_resistance*/0.003, /*differential*/ true} #define TEMPERATURE_SENSOR_1_TYPE PT100> - #define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 2200, /*inline_resistance*/0.003, /*differential*/ false, spiBus, spiCSPinMux.getCS(6)} + #define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 430, /*inline_resistance*/0, spiBus, spiCSPinMux.getCS(5)} #endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_1 -#define EXTRUDER_1_OUTPUT_PIN kOutput2_PinNumber +#define EXTRUDER_1_OUTPUT_PIN kOutput1_PinNumber #define EXTRUDER_1_FAN_PIN kOutput8_PinNumber #define HAS_TEMPERATURE_SENSOR_2 true @@ -290,8 +271,8 @@ /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ } #else - #define TEMPERATURE_SENSOR_2_TYPE PT100> - #define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 2200, /*inline_resistance*/0} + #define TEMPERATURE_SENSOR_2_TYPE PT100> + #define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 2200, /*inline_resistance*/0.003, /*differential*/ true} #endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_2 @@ -306,8 +287,11 @@ /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ } #else - #define TEMPERATURE_SENSOR_3_TYPE PT100> - #define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 2200, /*inline_resistance*/0.003, /*differential*/ true} +// #define TEMPERATURE_SENSOR_3_TYPE PT100> +// #define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 2200, /*inline_resistance*/0.003, /*differential*/ true} + #define TEMPERATURE_SENSOR_3_TYPE PT100> + #define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 430, /*inline_resistance*/0, spiBus, spiCSPinMux.getCS(6)} + #endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_3 @@ -392,7 +376,7 @@ #define DO5_MODE IO_ACTIVE_HIGH #define DO6_MODE IO_ACTIVE_HIGH #define DO7_MODE IO_ACTIVE_HIGH -#define DO8_MODE IO_ACTIVE_LOW // 5V Fan +#define DO8_MODE IO_ACTIVE_HIGH // 5V Fan //SAFEin (Output) signal #define DO9_MODE IO_ACTIVE_HIGH @@ -410,15 +394,15 @@ /*** Extruders / Heaters ***/ -#define MIX_FAN_VALUE 0.4 // (he1fm) at MIN_FAN_TEMP the fan comes on at this spped (0.0-1.0) -#define MAX_FAN_VALUE 0.75 // (he1fp) at MAX_FAN_TEMP the fan is at this spped (0.0-1.0) +#define MIN_FAN_VALUE 0.4 // (he1fm) at MIN_FAN_TEMP the fan comes on at this spped (0.0-1.0) +#define MAX_FAN_VALUE 1.0 // (he1fp) at MAX_FAN_TEMP the fan is at this spped (0.0-1.0) #define MIN_FAN_TEMP 50.0 // (he1fl) at this temp the fan starts to ramp up linearly #define MAX_FAN_TEMP 100.0 // (he1fh) at this temperature the fan is at "full speed" (MAX_FAN_VALUE) #define H1_DEFAULT_ENABLE true -#define H1_DEFAULT_P 7.0 -#define H1_DEFAULT_I 0.05 -#define H1_DEFAULT_D 150.0 +#define H1_DEFAULT_P 5.0 +#define H1_DEFAULT_I 0.025 +#define H1_DEFAULT_D 800 #define H2_DEFAULT_ENABLE false #define H2_DEFAULT_P 7.0 diff --git a/g2core/temperature.cpp b/g2core/temperature.cpp index 034adc392..c9a9bd924 100755 --- a/g2core/temperature.cpp +++ b/g2core/temperature.cpp @@ -251,6 +251,7 @@ struct PT100 { float pullup_resistance; float inline_resistance; bool differential; + bool gives_raw_resistance = false; ADC_t adc_pin {kNormal, [&]{this->adc_has_new_value();} }; float raw_adc_voltage = 0.0; @@ -261,7 +262,8 @@ struct PT100 { PT100(const float pullup_resistance_, const float inline_resistance_, const bool differential_ = false) : pullup_resistance{ pullup_resistance_ }, inline_resistance{ inline_resistance_ }, - differential{differential_} + differential{differential_}, + gives_raw_resistance{false} { adc_pin.setInterrupts(kPinInterruptOnChange|kInterruptPriorityLow); adc_pin.setVoltageRange(kSystemVoltage, @@ -272,23 +274,28 @@ struct PT100 { }; template - PT100(const float pullup_resistance_, const float inline_resistance_, const bool differential_ = false, Ts&&... additional_values) + PT100(const float pullup_resistance_, const float inline_resistance_, Ts&&... additional_values) : pullup_resistance{ pullup_resistance_ }, inline_resistance{ inline_resistance_ }, - differential{differential_}, + differential{false}, + gives_raw_resistance{true}, adc_pin {[&]{this->adc_has_new_value();}, additional_values...} { adc_pin.setInterrupts(kPinInterruptOnChange|kInterruptPriorityLow); adc_pin.setVoltageRange(kSystemVoltage, - get_voltage_of_temp(min_temp), - get_voltage_of_temp(max_temp), - differential, - 6400.0); + get_resistance_of_temp(min_temp), + get_resistance_of_temp(max_temp), + false, // ignored + 1); // ignored }; - float get_voltage_of_temp(float t) { + float get_resistance_of_temp(float t) { // R = 100(1 + A*T + B*T^2); A = 3.9083*10^-3; B = -5.775*10^-7 - float r = 100 * (1 + 0.0039083*t + -0.0000005775*t*t) + inline_resistance; + return 100 * (1 + 0.0039083*t + -0.0000005775*t*t) + inline_resistance; + }; + + float get_voltage_of_temp(float t) { + float r = get_resistance_of_temp(t); if (differential) { return (kSystemVoltage * r)/(2.0 * pullup_resistance + r); @@ -298,7 +305,7 @@ struct PT100 { float temperature_exact() { float r = get_resistance(); - if (r < 100) { return -1; } +// if (r < 100) { return -1; } // from https://www.maximintegrated.com/en/app-notes/index.mvp/id/3450 // run through wolfram as: @@ -308,10 +315,14 @@ struct PT100 { float get_resistance() { float r; - if (differential) { + if (gives_raw_resistance) { + r = raw_adc_voltage; + } + else if (differential) { float v = raw_adc_voltage / kSystemVoltage; r = (v * 2.0 * pullup_resistance)/(1.0 - v) - inline_resistance; - } else { + } + else { float v = raw_adc_voltage; r = ((pullup_resistance * v) / (kSystemVoltage - v)) - inline_resistance; } @@ -332,8 +343,14 @@ struct PT100 { // Call back function from the ADC to tell it that the ADC has a new sample... void adc_has_new_value() { - raw_adc_voltage = (raw_adc_voltage*10.0 + adc_pin.getVoltage())/11.0; - raw_adc_value = adc_pin.getRaw(); + if (gives_raw_resistance) { + raw_adc_value = adc_pin.getRaw(); + float v = (raw_adc_value*pullup_resistance)/32768; + raw_adc_voltage = (raw_adc_voltage*10.0 + v)/11.0; + } else { + raw_adc_value = adc_pin.getRaw(); + raw_adc_voltage = (raw_adc_voltage*10.0 + raw_adc_value)/11.0; + } }; }; From 099ff5b4605080c88e5e9f209593be8a378702a7 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Wed, 5 Apr 2017 08:38:50 -0500 Subject: [PATCH 058/193] Update motate reference for SPI fixes From ea07e9e43dd947164065e4663d57ad5a4e079efe Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Tue, 11 Apr 2017 08:50:41 -0500 Subject: [PATCH 059/193] Made PLANNER_POOL_SIZE adjustable int he hardware files, and bumped it to 96 for the gquintic --- g2core/board/gquintic/hardware.h | 2 ++ g2core/planner.h | 2 ++ 2 files changed, 4 insertions(+) diff --git a/g2core/board/gquintic/hardware.h b/g2core/board/gquintic/hardware.h index 40f9baf08..ae2bde94f 100644 --- a/g2core/board/gquintic/hardware.h +++ b/g2core/board/gquintic/hardware.h @@ -126,6 +126,8 @@ using Motate::OutputPin; #define MIN_SEGMENT_MS ((float)0.125) // S70 can handle much much smaller segements +#define PLANNER_BUFFER_POOL_SIZE (96) + /**** Motate Definitions ****/ // Timer definitions. See stepper.h and other headers for setup diff --git a/g2core/planner.h b/g2core/planner.h index b572e641b..cf352e9f3 100644 --- a/g2core/planner.h +++ b/g2core/planner.h @@ -244,7 +244,9 @@ typedef enum { /*** Most of these factors are the result of a lot of tweaking. Change with caution.***/ +#ifndef PLANNER_BUFFER_POOL_SIZE #define PLANNER_BUFFER_POOL_SIZE (48) // Suggest 12 min. Limit is 255 +#endif #define PLANNER_BUFFER_HEADROOM (4) // Buffers to reserve in planner before processing new input line #define JERK_MULTIPLIER ((float)1000000) // DO NOT CHANGE - must always be 1 million From 3b4e9bb9600b705048b37776c6162dc8f0cd8e25 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Tue, 11 Apr 2017 08:51:35 -0500 Subject: [PATCH 060/193] Ultimaker 2+: Tweaks to speeds and turned on TRAVERSE_AT_HIGH_JERK --- g2core/settings/settings_Ultimaker_2_Plus.h | 60 +++++++++++++-------- 1 file changed, 39 insertions(+), 21 deletions(-) diff --git a/g2core/settings/settings_Ultimaker_2_Plus.h b/g2core/settings/settings_Ultimaker_2_Plus.h index 6ffe628d0..3fe1a93c9 100644 --- a/g2core/settings/settings_Ultimaker_2_Plus.h +++ b/g2core/settings/settings_Ultimaker_2_Plus.h @@ -55,6 +55,8 @@ #define COOLANT_FLOOD_POLARITY 1 // 0=active low, 1=active high #define COOLANT_PAUSE_ON_HOLD false +#define TRAVERSE_AT_HIGH_JERK true // EXPERIMENTAL!! + // Communications and reporting settings #define MARLIN_COMPAT_ENABLED true // enable marlin compatibility mode @@ -101,43 +103,43 @@ #define M1_STEP_ANGLE 1.8 // 1sa // Marlin says 80 steps/unit, and 16 microsteps, with a 200-step/rev motor #define M1_TRAVEL_PER_REV 40 // 1tr -#define M1_MICROSTEPS 32 // 1mi 1,2,4,8,16,32 +#define M1_MICROSTEPS 64 // 1mi 1,2,4,8,16,32 #define M1_POLARITY 0 // 1po 0=normal, 1=reversed #define M1_POWER_MODE MOTOR_POWER_MODE // 1pm standard -#define M1_POWER_LEVEL 0.9 // 1mp +#define M1_POWER_LEVEL 0.3 // 1pl // 80 steps/mm at 1/16 microstepping = 40 mm/rev #define M2_MOTOR_MAP AXIS_Y #define M2_STEP_ANGLE 1.8 // Marlin says 80 steps/unit, and 16 microsteps, with a 200-step/rev motor #define M2_TRAVEL_PER_REV 40 -#define M2_MICROSTEPS 32 +#define M2_MICROSTEPS 64 #define M2_POLARITY 1 #define M2_POWER_MODE MOTOR_POWER_MODE -#define M2_POWER_LEVEL 0.9 +#define M2_POWER_LEVEL 0.3 #define M3_MOTOR_MAP AXIS_Z #define M3_STEP_ANGLE 1.8 // Marlin says 200 steps/unit, and 8 microsteps, with a 200-step/rev motor #define M3_TRAVEL_PER_REV 8 -#define M3_MICROSTEPS 32 +#define M3_MICROSTEPS 64 #define M3_POLARITY 0 #define M3_POWER_MODE MOTOR_ALWAYS_POWERED -#define M3_POWER_LEVEL 0.9 +#define M3_POWER_LEVEL 0.3 #define M4_MOTOR_MAP AXIS_A #define M4_STEP_ANGLE 1.8 #define M4_TRAVEL_PER_REV 360 // degrees moved per motor rev -#define M4_MICROSTEPS 32 +#define M4_MICROSTEPS 64 #define M4_POLARITY 0 #define M4_POWER_MODE MOTOR_POWER_MODE -#define M4_POWER_LEVEL 0.7 +#define M4_POWER_LEVEL 0.3 // 96 steps/mm at 1/16 microstepping = 33.3333 mm/rev #define M5_MOTOR_MAP AXIS_B #define M5_STEP_ANGLE 1.8 #define M5_TRAVEL_PER_REV 360 // degrees moved per motor rev -#define M5_MICROSTEPS 32 +#define M5_MICROSTEPS 128 #define M5_POLARITY 0 #define M5_POWER_MODE MOTOR_POWER_MODE #define M5_POWER_LEVEL 0.3 @@ -145,12 +147,12 @@ // *** axis settings ********************************************************************************** #define X_AXIS_MODE AXIS_STANDARD // xam see canonical_machine.h cmAxisMode for valid values -#define X_VELOCITY_MAX 12000 // xvm G0 max velocity in mm/min +#define X_VELOCITY_MAX 18000 // xvm G0 max velocity in mm/min #define X_FEEDRATE_MAX X_VELOCITY_MAX // xfr G1 max feed rate in mm/min #define X_TRAVEL_MIN 0 // xtn minimum travel - used by soft limits and homing #define X_TRAVEL_MAX 230 // xtm travel between switches or crashes -#define X_JERK_MAX 6000 // xjm yes, that's "100 billion" mm/(min^3) -#define X_JERK_HIGH_SPEED 6000 // xjh +#define X_JERK_MAX 10000 // xjm yes, that's "100 billion" mm/(min^3) +#define X_JERK_HIGH_SPEED 10000 // xjh #define X_HOMING_INPUT 1 // xhi input used for homing or 0 to disable #define X_HOMING_DIRECTION 0 // xhd 0=search moves negative, 1= search moves positive #define X_SEARCH_VELOCITY 2500 // xsv move in negative direction @@ -159,12 +161,12 @@ #define X_ZERO_BACKOFF 0.5 // xzb mm #define Y_AXIS_MODE AXIS_STANDARD -#define Y_VELOCITY_MAX 12000 +#define Y_VELOCITY_MAX 18000 #define Y_FEEDRATE_MAX Y_VELOCITY_MAX #define Y_TRAVEL_MIN 0 #define Y_TRAVEL_MAX 224.5 -#define Y_JERK_MAX 6000 -#define Y_JERK_HIGH_SPEED 6000 +#define Y_JERK_MAX 10000 +#define Y_JERK_HIGH_SPEED 10000 #define Y_HOMING_INPUT 3 #define Y_HOMING_DIRECTION 1 #define Y_SEARCH_VELOCITY 3000 @@ -177,7 +179,8 @@ #define Z_FEEDRATE_MAX Z_VELOCITY_MAX #define Z_TRAVEL_MIN 0 #define Z_TRAVEL_MAX 215 -#define Z_JERK_MAX 500 +//#define Z_JERK_MAX 500 +#define Z_JERK_MAX 800 #define Z_JERK_HIGH_SPEED 1000 #define Z_HOMING_INPUT 6 #define Z_HOMING_DIRECTION 1 @@ -186,7 +189,7 @@ #define Z_LATCH_BACKOFF 2 #define Z_ZERO_BACKOFF 0 -#define G55_Z_OFFSET 0.6 +#define G55_Z_OFFSET 0.35 // Rotary values are chosen to make the motor react the same as X for testing /*************************************************************************************** @@ -207,18 +210,33 @@ #define A_AXIS_MODE AXIS_RADIUS #define A_RADIUS 1.428 -#define A_VELOCITY_MAX 144443.0 // G0 rate ~60 mm/s, 3,600 mm/min -#define A_FEEDRATE_MAX 60184.6 // ~25 mm/s +//#define A_VELOCITY_MAX 288886.4 +//#define A_VELOCITY_MAX 144443.0 // G0 rate ~60 mm/s, 3,600 mm/min +#define A_VELOCITY_MAX 72221.5 // G0 rate ~30 mm/s, 3,600 mm/min +//define A_VELOCITY_MAX 48147.7 // G0 rate ~20 mm/s + +//#define A_FEEDRATE_MAX 48147.7 // ~20 mm/s +//#define A_FEEDRATE_MAX 36110.8 // ~15 mm/s +//#define A_FEEDRATE_MAX 24073.9 // ~10 mm/s +//#define A_FEEDRATE_MAX 12036.95 // ~5 mm/s +//#define A_FEEDRATE_MAX 6018.475 // ~2.5 mm/s +//#define A_FEEDRATE_MAX 1000.0 // ~0.415 mm/s +#define A_FEEDRATE_MAX 800.0 +//#define A_FEEDRATE_MAX 500.0 // ~0.2075 mm/s #define A_TRAVEL_MIN 0 #define A_TRAVEL_MAX 10 -#define A_JERK_MAX 144443.2 // ~60 million mm/min^3 +//#define A_JERK_MAX 288886.4 // ~120 million mm/min^3 +//#define A_JERK_MAX 144443.2 // ~60 million mm/min^3 +#define A_JERK_MAX 48147.7 // ~20 million mm/min^3 #define A_HOMING_INPUT 0 #define A_HOMING_DIRECTION 0 #define A_SEARCH_VELOCITY 2000 #define A_LATCH_VELOCITY 2000 #define A_LATCH_BACKOFF 5 #define A_ZERO_BACKOFF 2 -#define A_JERK_HIGH_SPEED 361108.0 // ~150 million mm/min^3 +//#define A_JERK_HIGH_SPEED 288886.4 // ~120 million mm/min^3 +//#define A_JERK_HIGH_SPEED 240739.0 // ~100 million mm/min^3 +#define A_JERK_HIGH_SPEED 144443.2 // ~60 million mm/min^3 #define B_AXIS_MODE AXIS_RADIUS #define B_RADIUS 1.428 From f04256dd2e055bf22b857871572695a25bb6921d Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Wed, 12 Apr 2017 20:24:31 -0500 Subject: [PATCH 061/193] gQuintic: bump DDA clock to 400khz --- g2core/board/gquintic/hardware.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/g2core/board/gquintic/hardware.h b/g2core/board/gquintic/hardware.h index ae2bde94f..73e46778d 100644 --- a/g2core/board/gquintic/hardware.h +++ b/g2core/board/gquintic/hardware.h @@ -121,7 +121,7 @@ using Motate::OutputPin; /**** Stepper DDA and dwell timer settings ****/ //#define FREQUENCY_DDA 200000UL // Hz step frequency. Interrupts actually fire at 2x (400 KHz) -#define FREQUENCY_DDA 300000UL // Hz step frequency. Interrupts actually fire at 2x (300 KHz) +#define FREQUENCY_DDA 400000UL // Hz step frequency. Interrupts actually fire at 2x (300 KHz) #define FREQUENCY_DWELL 1000UL #define MIN_SEGMENT_MS ((float)0.125) // S70 can handle much much smaller segements From 7b629124f7a255d074d455eea4afe62c7215366c Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Wed, 12 Apr 2017 20:24:58 -0500 Subject: [PATCH 062/193] Marlin: fix M4 to be in milliseconds for Marlin flavor gcode --- g2core/gcode_parser.cpp | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/g2core/gcode_parser.cpp b/g2core/gcode_parser.cpp index 2005f9e92..78cc2f184 100644 --- a/g2core/gcode_parser.cpp +++ b/g2core/gcode_parser.cpp @@ -1096,6 +1096,14 @@ static stat_t _execute_gcode_block_marlin() cm.gm.tool = cm.gm.tool_select; // Also, in Marlin, tool changes are effective immediately :facepalm: } + if (mst.marlin_flavor && + (gv.next_action == NEXT_ACTION_DWELL) && + gf.P_word + ) + { // G4 - dwell - adjust for Marlin + gv.P_word = gv.P_word / 1000.0; // In marlin, the P word is in microseconds, convert to seconds + } + // Deal with E if (gf.marlin_relative_extruder_mode) { // M82, M83 marlin_set_extruder_mode(gv.marlin_relative_extruder_mode); From 5b0aa6be8a7239842c70b0fa13dd44371bc50236 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Wed, 12 Apr 2017 20:25:38 -0500 Subject: [PATCH 063/193] Adjust dwell to internally be in milliseconds (giving more overhead before overflow) --- g2core/planner.cpp | 4 ++-- g2core/stepper.cpp | 8 ++++---- g2core/stepper.h | 2 +- 3 files changed, 7 insertions(+), 7 deletions(-) diff --git a/g2core/planner.cpp b/g2core/planner.cpp index 83408aee3..5a0115370 100644 --- a/g2core/planner.cpp +++ b/g2core/planner.cpp @@ -382,7 +382,7 @@ static stat_t _exec_json_wait(mpBuf_t *bf) nv_get_nvObj(nv); bool new_value = !fp_ZERO(nv->value); if (old_value != new_value) { - st_prep_dwell((uint32_t)(0.1 * 1000000.0));// 1ms converted to uSec + st_prep_dwell(1.0); // 1ms exactly return STAT_OK; } } @@ -421,7 +421,7 @@ stat_t mp_dwell(float seconds) static stat_t _exec_dwell(mpBuf_t *bf) { - st_prep_dwell((uint32_t)(bf->block_time * 1000000.0));// convert seconds to uSec + st_prep_dwell(bf->block_time * 1000.0);// convert seconds to ms if (mp_free_run_buffer()) { cm_cycle_end(); // free buffer & perform cycle_end if planner is empty } diff --git a/g2core/stepper.cpp b/g2core/stepper.cpp index 4772805f2..f3340a191 100644 --- a/g2core/stepper.cpp +++ b/g2core/stepper.cpp @@ -778,11 +778,11 @@ void st_prep_command(void *bf) * st_prep_dwell() - Add a dwell to the move buffer */ -void st_prep_dwell(float microseconds) +void st_prep_dwell(float milliseconds) { st_pre.block_type = BLOCK_TYPE_DWELL; // we need dwell_ticks to be at least 1 - st_pre.dwell_ticks = std::max((uint32_t)((microseconds/1000000) * FREQUENCY_DWELL), 1UL); + st_pre.dwell_ticks = std::max((uint32_t)((milliseconds/1000.0) * FREQUENCY_DWELL), 1UL); st_pre.buffer_state = PREP_BUFFER_OWNED_BY_LOADER; // signal that prep buffer is ready } @@ -791,9 +791,9 @@ void st_prep_dwell(float microseconds) * (only usable while exec isn't running, e.g. in feedhold or stopped states...) * add a dwell to the loader without going through the planner buffers */ -void st_request_out_of_band_dwell(float microseconds) +void st_request_out_of_band_dwell(float milliseconds) { - st_prep_dwell(microseconds); + st_prep_dwell(milliseconds); st_pre.buffer_state = PREP_BUFFER_OWNED_BY_LOADER; // signal that prep buffer is ready st_request_load_move(); } diff --git a/g2core/stepper.h b/g2core/stepper.h index 4b2f7824e..890c7eb7a 100644 --- a/g2core/stepper.h +++ b/g2core/stepper.h @@ -566,7 +566,7 @@ void st_request_exec_move(void) HOT_FUNC; void st_request_load_move(void) HOT_FUNC; void st_prep_null(void); void st_prep_command(void *bf); // use a void pointer since we don't know about mpBuf_t yet) -void st_prep_dwell(float microseconds); +void st_prep_dwell(float milliseconds); void st_request_out_of_band_dwell(float microseconds); stat_t st_prep_line(float travel_steps[], float following_error[], float segment_time) HOT_FUNC; From ac7a7d43f5ac319e473dd24bb613c1b3f5481832 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Wed, 12 Apr 2017 20:26:00 -0500 Subject: [PATCH 064/193] Annotate motor power modes in comments --- g2core/stepper.h | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/g2core/stepper.h b/g2core/stepper.h index 890c7eb7a..28ae10ad7 100644 --- a/g2core/stepper.h +++ b/g2core/stepper.h @@ -275,11 +275,11 @@ typedef enum { // used w/start and stop flags to sequen } stPowerState; typedef enum { - MOTOR_DISABLED = 0, // motor enable is deactivated - MOTOR_ALWAYS_POWERED, // motor is always powered while machine is ON - MOTOR_POWERED_IN_CYCLE, // motor fully powered during cycles, de-powered out of cycle - MOTOR_POWERED_ONLY_WHEN_MOVING, // motor only powered while moving - idles shortly after it's stopped - even in cycle - MOTOR_POWER_MODE_MAX_VALUE // for input range checking + MOTOR_DISABLED = 0, // [0] motor enable is deactivated + MOTOR_ALWAYS_POWERED, // [1] motor is always powered while machine is ON + MOTOR_POWERED_IN_CYCLE, // [2] motor fully powered during cycles, de-powered out of cycle + MOTOR_POWERED_ONLY_WHEN_MOVING, // [3] motor only powered while moving - idles shortly after it's stopped - even in cycle + MOTOR_POWER_MODE_MAX_VALUE // [4] for input range checking } stPowerMode; // Min/Max timeouts allowed for motor disable. Allow for inertial stop; must be non-zero From d34a362ed6519b6b70447f5c66f997d7dbfff5fe Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Wed, 12 Apr 2017 20:26:19 -0500 Subject: [PATCH 065/193] Ultimaker2+: More settings adjustments --- g2core/settings/settings_Ultimaker_2_Plus.h | 40 ++++++++++----------- 1 file changed, 20 insertions(+), 20 deletions(-) diff --git a/g2core/settings/settings_Ultimaker_2_Plus.h b/g2core/settings/settings_Ultimaker_2_Plus.h index 3fe1a93c9..4fbfcadd8 100644 --- a/g2core/settings/settings_Ultimaker_2_Plus.h +++ b/g2core/settings/settings_Ultimaker_2_Plus.h @@ -103,20 +103,20 @@ #define M1_STEP_ANGLE 1.8 // 1sa // Marlin says 80 steps/unit, and 16 microsteps, with a 200-step/rev motor #define M1_TRAVEL_PER_REV 40 // 1tr -#define M1_MICROSTEPS 64 // 1mi 1,2,4,8,16,32 +#define M1_MICROSTEPS 128 // 1mi 1,2,4,8,16,32 #define M1_POLARITY 0 // 1po 0=normal, 1=reversed -#define M1_POWER_MODE MOTOR_POWER_MODE // 1pm standard -#define M1_POWER_LEVEL 0.3 // 1pl +#define M1_POWER_MODE MOTOR_POWERED_IN_CYCLE // 1pm standard +#define M1_POWER_LEVEL 0.5 // 1pl // 80 steps/mm at 1/16 microstepping = 40 mm/rev #define M2_MOTOR_MAP AXIS_Y #define M2_STEP_ANGLE 1.8 // Marlin says 80 steps/unit, and 16 microsteps, with a 200-step/rev motor #define M2_TRAVEL_PER_REV 40 -#define M2_MICROSTEPS 64 +#define M2_MICROSTEPS 128 #define M2_POLARITY 1 -#define M2_POWER_MODE MOTOR_POWER_MODE -#define M2_POWER_LEVEL 0.3 +#define M2_POWER_MODE MOTOR_POWERED_IN_CYCLE +#define M2_POWER_LEVEL 0.5 #define M3_MOTOR_MAP AXIS_Z #define M3_STEP_ANGLE 1.8 @@ -124,8 +124,8 @@ #define M3_TRAVEL_PER_REV 8 #define M3_MICROSTEPS 64 #define M3_POLARITY 0 -#define M3_POWER_MODE MOTOR_ALWAYS_POWERED -#define M3_POWER_LEVEL 0.3 +#define M3_POWER_MODE MOTOR_POWERED_IN_CYCLE +#define M3_POWER_LEVEL 0.5 #define M4_MOTOR_MAP AXIS_A #define M4_STEP_ANGLE 1.8 @@ -133,7 +133,7 @@ #define M4_MICROSTEPS 64 #define M4_POLARITY 0 #define M4_POWER_MODE MOTOR_POWER_MODE -#define M4_POWER_LEVEL 0.3 +#define M4_POWER_LEVEL 0.8 // 96 steps/mm at 1/16 microstepping = 33.3333 mm/rev #define M5_MOTOR_MAP AXIS_B @@ -142,7 +142,7 @@ #define M5_MICROSTEPS 128 #define M5_POLARITY 0 #define M5_POWER_MODE MOTOR_POWER_MODE -#define M5_POWER_LEVEL 0.3 +#define M5_POWER_LEVEL 0.8 // *** axis settings ********************************************************************************** @@ -151,13 +151,13 @@ #define X_FEEDRATE_MAX X_VELOCITY_MAX // xfr G1 max feed rate in mm/min #define X_TRAVEL_MIN 0 // xtn minimum travel - used by soft limits and homing #define X_TRAVEL_MAX 230 // xtm travel between switches or crashes -#define X_JERK_MAX 10000 // xjm yes, that's "100 billion" mm/(min^3) -#define X_JERK_HIGH_SPEED 10000 // xjh +#define X_JERK_MAX 7000 // xjm yes, that's "100 billion" mm/(min^3) +#define X_JERK_HIGH_SPEED 7000 // xjh #define X_HOMING_INPUT 1 // xhi input used for homing or 0 to disable #define X_HOMING_DIRECTION 0 // xhd 0=search moves negative, 1= search moves positive #define X_SEARCH_VELOCITY 2500 // xsv move in negative direction #define X_LATCH_VELOCITY 200 // xlv mm/min -#define X_LATCH_BACKOFF 5 // xlb mm +#define X_LATCH_BACKOFF 10 // xlb mm #define X_ZERO_BACKOFF 0.5 // xzb mm #define Y_AXIS_MODE AXIS_STANDARD @@ -165,17 +165,17 @@ #define Y_FEEDRATE_MAX Y_VELOCITY_MAX #define Y_TRAVEL_MIN 0 #define Y_TRAVEL_MAX 224.5 -#define Y_JERK_MAX 10000 -#define Y_JERK_HIGH_SPEED 10000 +#define Y_JERK_MAX 7000 +#define Y_JERK_HIGH_SPEED 7000 #define Y_HOMING_INPUT 3 #define Y_HOMING_DIRECTION 1 #define Y_SEARCH_VELOCITY 3000 #define Y_LATCH_VELOCITY 200 -#define Y_LATCH_BACKOFF 5 +#define Y_LATCH_BACKOFF 10 #define Y_ZERO_BACKOFF 0.5 #define Z_AXIS_MODE AXIS_STANDARD -#define Z_VELOCITY_MAX 2000 +#define Z_VELOCITY_MAX 1500 #define Z_FEEDRATE_MAX Z_VELOCITY_MAX #define Z_TRAVEL_MIN 0 #define Z_TRAVEL_MAX 215 @@ -186,10 +186,10 @@ #define Z_HOMING_DIRECTION 1 #define Z_SEARCH_VELOCITY 1000 #define Z_LATCH_VELOCITY 100 -#define Z_LATCH_BACKOFF 2 +#define Z_LATCH_BACKOFF 5 #define Z_ZERO_BACKOFF 0 -#define G55_Z_OFFSET 0.35 +#define G55_Z_OFFSET 0.3 // Rotary values are chosen to make the motor react the same as X for testing /*************************************************************************************** @@ -278,7 +278,7 @@ #endif // HAS_TEMPERATURE_SENSOR_1 #define EXTRUDER_1_OUTPUT_PIN kOutput1_PinNumber -#define EXTRUDER_1_FAN_PIN kOutput8_PinNumber +#define EXTRUDER_1_FAN_PIN kOutput5_PinNumber #define HAS_TEMPERATURE_SENSOR_2 true #if HAS_TEMPERATURE_SENSOR_2 From 8f2673298967f243fe191a49a3e683a1566b8b4e Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Wed, 12 Apr 2017 20:26:37 -0500 Subject: [PATCH 066/193] Motate: update reference for USB fixes --- Motate | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Motate b/Motate index 3d0d332dc..2f44927a3 160000 --- a/Motate +++ b/Motate @@ -1 +1 @@ -Subproject commit 3d0d332dc5be522166b801d7f4aa74c35ed001e2 +Subproject commit 2f44927a3f647a858330f8781efc56eba767ea33 From 8ad5211b8a46674958849f541bb56b36f2d3d2d3 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Tue, 18 Apr 2017 15:24:27 -0500 Subject: [PATCH 067/193] Updates to UM2+ settings, switched to the new ADCDifferentialPair for UM2+ --- g2core/device/max31865/max31865.h | 5 +- g2core/settings/settings_Ultimaker_2_Plus.h | 20 ++-- g2core/temperature.cpp | 100 +++++++++++++++++--- 3 files changed, 102 insertions(+), 23 deletions(-) diff --git a/g2core/device/max31865/max31865.h b/g2core/device/max31865/max31865.h index db4f56f30..5f4610406 100644 --- a/g2core/device/max31865/max31865.h +++ b/g2core/device/max31865/max31865.h @@ -407,7 +407,10 @@ struct MAX31865 final { return _vref; }; - void setVoltageRange(const float vref, const float min_expected = 0, const float max_expected = -1, const bool differential = false, const float ideal_steps = 1) + void setVoltageRange(const float vref, + const float min_expected = 0, + const float max_expected = -1, + const float ideal_steps = 1) { _vref = vref; diff --git a/g2core/settings/settings_Ultimaker_2_Plus.h b/g2core/settings/settings_Ultimaker_2_Plus.h index 4fbfcadd8..d229763f1 100644 --- a/g2core/settings/settings_Ultimaker_2_Plus.h +++ b/g2core/settings/settings_Ultimaker_2_Plus.h @@ -105,7 +105,7 @@ #define M1_TRAVEL_PER_REV 40 // 1tr #define M1_MICROSTEPS 128 // 1mi 1,2,4,8,16,32 #define M1_POLARITY 0 // 1po 0=normal, 1=reversed -#define M1_POWER_MODE MOTOR_POWERED_IN_CYCLE // 1pm standard +#define M1_POWER_MODE MOTOR_POWERED_IN_CYCLE // 1pm standard #define M1_POWER_LEVEL 0.5 // 1pl // 80 steps/mm at 1/16 microstepping = 40 mm/rev @@ -270,17 +270,17 @@ /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ } #else -// #define TEMPERATURE_SENSOR_1_TYPE PT100> -// #define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 2200, /*inline_resistance*/0.003, /*differential*/ true} - #define TEMPERATURE_SENSOR_1_TYPE PT100> - #define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 430, /*inline_resistance*/0, spiBus, spiCSPinMux.getCS(5)} + #define TEMPERATURE_SENSOR_1_TYPE PT100> + #define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 2200, /*inline_resistance*/0.0, /*differential*/ true} +// #define TEMPERATURE_SENSOR_1_TYPE PT100> +// #define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 430, /*inline_resistance*/0, spiBus, spiCSPinMux.getCS(5)} #endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_1 #define EXTRUDER_1_OUTPUT_PIN kOutput1_PinNumber #define EXTRUDER_1_FAN_PIN kOutput5_PinNumber -#define HAS_TEMPERATURE_SENSOR_2 true +#define HAS_TEMPERATURE_SENSOR_2 false #if HAS_TEMPERATURE_SENSOR_2 #if 0 // 1 if a Thermistor, 0 if a PT100 #define TEMPERATURE_SENSOR_2_TYPE Thermistor @@ -289,12 +289,14 @@ /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ } #else - #define TEMPERATURE_SENSOR_2_TYPE PT100> - #define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 2200, /*inline_resistance*/0.003, /*differential*/ true} +// #define TEMPERATURE_SENSOR_2_TYPE PT100> +// #define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 2200, /*inline_resistance*/0.0, /*differential*/ true} + #define TEMPERATURE_SENSOR_2_TYPE PT100> + #define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 430, /*inline_resistance*/0, spiBus, spiCSPinMux.getCS(5)} #endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_2 -#define EXTRUDER_2_OUTPUT_PIN kOutput1_PinNumber +#define EXTRUDER_2_OUTPUT_PIN kOutput2_PinNumber #define HAS_TEMPERATURE_SENSOR_3 true #if HAS_TEMPERATURE_SENSOR_3 diff --git a/g2core/temperature.cpp b/g2core/temperature.cpp index c9a9bd924..1531aae0c 100755 --- a/g2core/temperature.cpp +++ b/g2core/temperature.cpp @@ -154,6 +154,70 @@ struct TemperatureSensor { }; }; +template +struct ValueHistory { + + float variance_max = 2.0; + ValueHistory() {}; + ValueHistory(float v_max) : variance_max{v_max} {}; + + struct sample_t { + float value; + float value_sq; + void set(float v) { value = v; value_sq = v*v; } + }; + sample_t samples[sample_count]; + uint16_t next_sample = 0; + void _bump_index(uint16_t &v) { + ++v; + if (v == sample_count) { + v = 0; + } + }; + uint16_t sampled = 0; + + float rolling_sum = 0; + float rolling_sum_sq = 0; + float rolling_mean = 0; + void add_sample(float t) { + rolling_sum -= samples[next_sample].value; + rolling_sum_sq -= samples[next_sample].value_sq; + + samples[next_sample].set(t); + + rolling_sum += samples[next_sample].value; + rolling_sum_sq += samples[next_sample].value_sq; + + _bump_index(next_sample); + if (sampled < sample_count) { ++sampled; } + + rolling_mean = rolling_sum/(float)sampled; + }; + + float get_std_dev() { + // Important note: this is a POPULATION standard deviation, not a population standard deviation + float variance = (rolling_sum_sq/(float)sampled) - (rolling_mean*rolling_mean); + return sqrt(fabs(variance)); + }; + + float value() { + // we'll shoot through the samples and ignore the outliers + uint16_t samples_kept = 0; + float temp = 0; + float std_dev = get_std_dev(); + + for (uint16_t i=0; i struct Thermistor { float c1, c2, c3, pullup_resistance; @@ -248,28 +312,31 @@ struct Thermistor { template struct PT100 { - float pullup_resistance; - float inline_resistance; + const float pullup_resistance; + const float inline_resistance; bool differential; bool gives_raw_resistance = false; - ADC_t adc_pin {kNormal, [&]{this->adc_has_new_value();} }; + ADC_t adc_pin; float raw_adc_voltage = 0.0; int32_t raw_adc_value = 0; + const float variance_max = 1.1; + ValueHistory<20> history {variance_max}; + typedef PT100 type; PT100(const float pullup_resistance_, const float inline_resistance_, const bool differential_ = false) : pullup_resistance{ pullup_resistance_ }, inline_resistance{ inline_resistance_ }, differential{differential_}, - gives_raw_resistance{false} + gives_raw_resistance{false}, + adc_pin{kDifferentialPair, [&]{this->adc_has_new_value();} } { adc_pin.setInterrupts(kPinInterruptOnChange|kInterruptPriorityLow); adc_pin.setVoltageRange(kSystemVoltage, get_voltage_of_temp(min_temp), get_voltage_of_temp(max_temp), - differential, 6400.0); }; @@ -279,22 +346,21 @@ struct PT100 { inline_resistance{ inline_resistance_ }, differential{false}, gives_raw_resistance{true}, - adc_pin {[&]{this->adc_has_new_value();}, additional_values...} + adc_pin{[&]{this->adc_has_new_value();}, additional_values...} { adc_pin.setInterrupts(kPinInterruptOnChange|kInterruptPriorityLow); adc_pin.setVoltageRange(kSystemVoltage, get_resistance_of_temp(min_temp), get_resistance_of_temp(max_temp), - false, // ignored 1); // ignored }; - float get_resistance_of_temp(float t) { + constexpr float get_resistance_of_temp(float t) { // R = 100(1 + A*T + B*T^2); A = 3.9083*10^-3; B = -5.775*10^-7 return 100 * (1 + 0.0039083*t + -0.0000005775*t*t) + inline_resistance; }; - float get_voltage_of_temp(float t) { + constexpr float get_voltage_of_temp(float t) { float r = get_resistance_of_temp(t); if (differential) { @@ -305,7 +371,7 @@ struct PT100 { float temperature_exact() { float r = get_resistance(); -// if (r < 100) { return -1; } + if (r < 0.0) { return -1; } // from https://www.maximintegrated.com/en/app-notes/index.mvp/id/3450 // run through wolfram as: @@ -315,6 +381,12 @@ struct PT100 { float get_resistance() { float r; + raw_adc_voltage = history.value(); + + if (isnan(raw_adc_voltage)) { + return -1; + } + if (gives_raw_resistance) { r = raw_adc_voltage; } @@ -334,6 +406,7 @@ struct PT100 { }; float get_voltage() { +// return history.value(); return raw_adc_voltage; }; @@ -345,11 +418,12 @@ struct PT100 { void adc_has_new_value() { if (gives_raw_resistance) { raw_adc_value = adc_pin.getRaw(); - float v = (raw_adc_value*pullup_resistance)/32768; - raw_adc_voltage = (raw_adc_voltage*10.0 + v)/11.0; + raw_adc_voltage = (raw_adc_value*pullup_resistance)/32768; + history.add_sample(raw_adc_voltage); } else { raw_adc_value = adc_pin.getRaw(); - raw_adc_voltage = (raw_adc_voltage*10.0 + raw_adc_value)/11.0; +// raw_adc_voltage = (raw_adc_voltage*10.0 + adc_pin.getVoltage())/11.0; + history.add_sample(adc_pin.getVoltage()); } }; }; From 287182f785624b3f0046342f013bc03bd203f86a Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Tue, 18 Apr 2017 15:24:44 -0500 Subject: [PATCH 068/193] Minor typo fix in AxiDraw settings. --- g2core/settings/settings_axidraw_v3.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/g2core/settings/settings_axidraw_v3.h b/g2core/settings/settings_axidraw_v3.h index 6d2b39782..3b5df8ed7 100755 --- a/g2core/settings/settings_axidraw_v3.h +++ b/g2core/settings/settings_axidraw_v3.h @@ -110,7 +110,7 @@ #define M1_MICROSTEPS A_B_MICROSTEPS // 1mi 1,2,4,8 #define M1_POLARITY 0 // 1po 0=normal, 1=reversed #define M1_POWER_MODE MOTOR_POWER_MODE // 1pm standard -#define M1_POWER_LEVEL A_B_POWER_LEVEL +#define M1_POWER_LEVEL A_B_POWER_LEVEL // 1pl #define M2_MOTOR_MAP AXIS_COREXY_B #define M2_STEP_ANGLE 1.8 From 3dded28098ee549ed397443d4d5eb8fbbaa1fe0d Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Tue, 18 Apr 2017 15:25:04 -0500 Subject: [PATCH 069/193] Update Motate reference for ADCDifferentialPair. --- Motate | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Motate b/Motate index 2f44927a3..152891e70 160000 --- a/Motate +++ b/Motate @@ -1 +1 @@ -Subproject commit 2f44927a3f647a858330f8781efc56eba767ea33 +Subproject commit 152891e708c094629870abacf0f59bc08f5a1cad From 5b1a0f4cb5631f2a3b60a6cdabea2b8e14953c00 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Fri, 21 Apr 2017 11:41:07 -0500 Subject: [PATCH 070/193] Rearranged heater to not collide/interact with GPIO (to be undone later) --- g2core/board/gquintic/gquintic-b-pinout.h | 35 ++++++++++--------- .../board/gquintic/motate_pin_assignments.h | 9 +++-- g2core/settings/settings_Ultimaker_2_Plus.h | 35 +++++++++++++------ 3 files changed, 49 insertions(+), 30 deletions(-) diff --git a/g2core/board/gquintic/gquintic-b-pinout.h b/g2core/board/gquintic/gquintic-b-pinout.h index 3113edb6d..2df8401c3 100755 --- a/g2core/board/gquintic/gquintic-b-pinout.h +++ b/g2core/board/gquintic/gquintic-b-pinout.h @@ -94,17 +94,20 @@ // So we have to explicitly enable them as PWM pins. // Generated with: // perl -e 'for($i=1;$i<14;$i++) { print "#define OUTPUT${i}_PWM 0\n";}' -#define OUTPUT1_PWM 1 // TC 0,1 - Fet 1 -#define OUTPUT2_PWM 1 // PWM 1 - Fet 2 +//#define OUTPUT1_PWM 1 // TC 0,1 - Fet 1 +//#define OUTPUT2_PWM 1 // PWM 0,1 - Fet 2 +#define OUTPUT1_PWM 0 // Used by EX1 +#define OUTPUT2_PWM 0 // Used by EX2 #define OUTPUT3_PWM 1 // TC 1,0 - Fan 1 #define OUTPUT4_PWM 1 // TC 1,1 - Fan 2 #define OUTPUT5_PWM 1 // TC 2,0 - Fan 3 -#define OUTPUT6_PWM 1 // PWM 8+0 -#define OUTPUT7_PWM 1 // PWM 3 -#define OUTPUT8_PWM 1 // PWM 2 -#define OUTPUT9_PWM 0 // PWM 2 -#define OUTPUT10_PWM 1 // PWM 8+2 -#define OUTPUT11_PWM 1 // PWM 8+3 - Fet 3 +#define OUTPUT6_PWM 1 // PWM 1,0 +#define OUTPUT7_PWM 1 // PWM 0,3 +#define OUTPUT8_PWM 1 // PWM 0,2 +#define OUTPUT9_PWM 0 // PWM 0,2 +#define OUTPUT10_PWM 1 // PWM 1,2 +#define OUTPUT11_PWM 0 // Used by Heatbed +//#define OUTPUT11_PWM 1 // PWM 1,3 - Fet 3 #define OUTPUT12_PWM 0 // Unused #define OUTPUT13_PWM 0 // Unused @@ -118,20 +121,20 @@ namespace Motate { // _MAKE_MOTATE_PIN(kLED_RGBWPixelPinNumber, 'A', 0); // -_MAKE_MOTATE_PIN(kOutput1_PinNumber, 'A', 1); // TC 0,1 -_MAKE_MOTATE_PIN(kOutput2_PinNumber, 'A', 2); // PWM 1 +_MAKE_MOTATE_PIN(kHeaterOutput1_PinNumber, 'A', 1); // TC 0,1 +_MAKE_MOTATE_PIN(kHeaterOutput2_PinNumber, 'A', 2); // PWM 0,1 _MAKE_MOTATE_PIN(kI2C1_SDAPinNumber, 'A', 3); // _MAKE_MOTATE_PIN(kI2C1_SCLPinNumber, 'A', 4); // -_MAKE_MOTATE_PIN(kOutput11_PinNumber, 'A', 5); // PWM 8+3 +_MAKE_MOTATE_PIN(kHeaterOutput11_PinNumber, 'A', 5); // PWM 1,3 _MAKE_MOTATE_PIN(kExternalClock1_PinNumber, 'A', 6); // CPU_CLK -//_MAKE_MOTATE_PIN(kOutput7_PinNumber, 'A', 7); // PWM 3 -_MAKE_MOTATE_PIN(kServo1_PinNumber, 'A', 7); // +_MAKE_MOTATE_PIN(kOutput7_PinNumber, 'A', 7); // PWM 0,3 +//_MAKE_MOTATE_PIN(kServo1_PinNumber, 'A', 7); // _MAKE_MOTATE_PIN(kSerial_RTSPinNumber, 'A', 8); // _MAKE_MOTATE_PIN(kSerial_RXPinNumber, 'A', 9); // _MAKE_MOTATE_PIN(kSerial_TXPinNumber, 'A', 10); // _MAKE_MOTATE_PIN(kSocket2_EnablePinNumber, 'A', 11); // -_MAKE_MOTATE_PIN(kOutput6_PinNumber, 'A', 12); // PWM 8+0 -_MAKE_MOTATE_PIN(kOutput8_PinNumber, 'A', 13); // PWM 2 +_MAKE_MOTATE_PIN(kOutput6_PinNumber, 'A', 12); // PWM 1,0 +_MAKE_MOTATE_PIN(kOutput8_PinNumber, 'A', 13); // PWM 0,2 _MAKE_MOTATE_PIN(kSocket1_StepPinNumber, 'A', 14); // _MAKE_MOTATE_PIN(kOutput3_PinNumber, 'A', 15); // TC 1,0 _MAKE_MOTATE_PIN(kOutput4_PinNumber, 'A', 16); // TC 1,1 @@ -141,7 +144,7 @@ _MAKE_MOTATE_PIN(kADC2_PinNumber, 'A', 19); // AFEC0,8 _MAKE_MOTATE_PIN(kADC1_PinNumber, 'A', 20); // AFEC0,9 _MAKE_MOTATE_PIN(kSerial_CTSPinNumber, 'A', 21); // _MAKE_MOTATE_PIN(kSocket1_EnablePinNumber, 'A', 22); // -_MAKE_MOTATE_PIN(kOutput10_PinNumber, 'A', 23); // PWM 8+2 +_MAKE_MOTATE_PIN(kOutput10_PinNumber, 'A', 23); // PWM 1,2 //_MAKE_MOTATE_PIN(kServo1_PinNumber, 'A', 23); // _MAKE_MOTATE_PIN(kSocket3_EnablePinNumber, 'A', 24); // _MAKE_MOTATE_PIN(kSocket2_DirPinNumber, 'A', 25); // diff --git a/g2core/board/gquintic/motate_pin_assignments.h b/g2core/board/gquintic/motate_pin_assignments.h index 30505ad7e..ab6849e66 100755 --- a/g2core/board/gquintic/motate_pin_assignments.h +++ b/g2core/board/gquintic/motate_pin_assignments.h @@ -179,8 +179,10 @@ pin_number kGRBL_CommonEnablePinNumber = -1; // g2ref extensions // These first 5 may replace the Spindle and Coolant pins, above -pin_number kOutput1_PinNumber = 130; // DO_1: Extruder1_PWM -pin_number kOutput2_PinNumber = 131; // DO_2: Extruder2_PWM +pin_number kHeaterOutput1_PinNumber = 130; // DO_1: Extruder1_PWM +pin_number kHeaterOutput2_PinNumber = 131; // DO_2: Extruder2_PWM +pin_number kOutput1_PinNumber = -1; // DO_1: Extruder1_PWM +pin_number kOutput2_PinNumber = -1; // DO_2: Extruder2_PWM pin_number kOutput3_PinNumber = 132; // DO_3: Fan1A_PWM pin_number kOutput4_PinNumber = 133; // DO_4: Fan1B_PWM pin_number kOutput5_PinNumber = 134; // DO_5: Fan2A_PWM @@ -191,7 +193,8 @@ pin_number kOutput8_PinNumber = 137; // See Coolant Enable pin_number kOutput9_PinNumber = 138; // DO_09: May be resued for Servo1 pin_number kOutput10_PinNumber = 139; // DO_10: May be resued for Servo2 -pin_number kOutput11_PinNumber = 140; // DO_11: Heated Bed FET +pin_number kHeaterOutput11_PinNumber = 140; // DO_11: Heated Bed FET +pin_number kOutput11_PinNumber = -1; // DO_11: Heated Bed FET pin_number kOutput12_PinNumber = 141; // DO_12: Indicator_LED pin_number kOutput13_PinNumber = -1; // 142; pin_number kOutput14_PinNumber = -1; // 143; diff --git a/g2core/settings/settings_Ultimaker_2_Plus.h b/g2core/settings/settings_Ultimaker_2_Plus.h index d229763f1..72808b329 100644 --- a/g2core/settings/settings_Ultimaker_2_Plus.h +++ b/g2core/settings/settings_Ultimaker_2_Plus.h @@ -277,7 +277,7 @@ #endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_1 -#define EXTRUDER_1_OUTPUT_PIN kOutput1_PinNumber +#define EXTRUDER_1_OUTPUT_PIN kHeaterOutput1_PinNumber #define EXTRUDER_1_FAN_PIN kOutput5_PinNumber #define HAS_TEMPERATURE_SENSOR_2 false @@ -296,7 +296,7 @@ #endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_2 -#define EXTRUDER_2_OUTPUT_PIN kOutput2_PinNumber +#define EXTRUDER_2_OUTPUT_PIN kHeaterOutput2_PinNumber #define HAS_TEMPERATURE_SENSOR_3 true #if HAS_TEMPERATURE_SENSOR_3 @@ -315,7 +315,7 @@ #endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_3 -#define BED_OUTPUT_PIN kOutput11_PinNumber +#define BED_OUTPUT_PIN kHeaterOutput11_PinNumber //** Digital Inputs ** /* @@ -382,10 +382,10 @@ #define DI9_FUNCTION INPUT_FUNCTION_NONE //Extruder1_PWM -#define DO1_MODE IO_ACTIVE_HIGH +#define DO1_MODE IO_ACTIVE_HIGH // unavailable, is the extruder output //Extruder2_PWM -#define DO2_MODE IO_ACTIVE_HIGH +#define DO2_MODE IO_ACTIVE_HIGH // unavailable, is the extruder output //Fan1A_PWM #define DO3_MODE IO_ACTIVE_HIGH @@ -404,7 +404,7 @@ #define DO10_MODE IO_ACTIVE_HIGH //Header Bed FET -#define DO11_MODE IO_ACTIVE_LOW +#define DO11_MODE IO_ACTIVE_LOW // unavailable, is the extruder output //Indicator_LED #define DO12_MODE IO_ACTIVE_HIGH @@ -419,17 +419,30 @@ #define MIN_FAN_TEMP 50.0 // (he1fl) at this temp the fan starts to ramp up linearly #define MAX_FAN_TEMP 100.0 // (he1fh) at this temperature the fan is at "full speed" (MAX_FAN_VALUE) +// PID debug string: {sr:{"he1t":t,"he1st":t,"pid1p":t, "pid1i":t, "pid1d":t, "pid1f":t, "he1op":t, "line":t, "stat":t}} + #define H1_DEFAULT_ENABLE true -#define H1_DEFAULT_P 5.0 -#define H1_DEFAULT_I 0.025 -#define H1_DEFAULT_D 800 +#define H1_DEFAULT_P 1 +#define H1_DEFAULT_I 0.005 +#define H1_DEFAULT_D 500 +#define H1_DEFAULT_F 0.0015 +#if 0 + +{he1p:1} +{he1i:0.005} +{he1d:500} +{he1f:0.0015} + +#endif #define H2_DEFAULT_ENABLE false #define H2_DEFAULT_P 7.0 #define H2_DEFAULT_I 0.05 #define H2_DEFAULT_D 150.0 +#define H2_DEFAULT_F 0.0 #define H3_DEFAULT_ENABLE true #define H3_DEFAULT_P 9.0 -#define H3_DEFAULT_I 0.12 -#define H3_DEFAULT_D 400.0 +#define H3_DEFAULT_I 0.012 +#define H3_DEFAULT_D 100 +#define H3_DEFAULT_F 0.0 From f0a038573601c2642114bee3ec388d254c7b6fa9 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Fri, 21 Apr 2017 11:42:58 -0500 Subject: [PATCH 071/193] Rework of temperature control, PID, and PWM outputs. --- g2core/temperature.cpp | 185 +++++++++++++++++++++++++++++++++-------- g2core/temperature.h | 3 + 2 files changed, 152 insertions(+), 36 deletions(-) diff --git a/g2core/temperature.cpp b/g2core/temperature.cpp index 1531aae0c..6402e0dae 100755 --- a/g2core/temperature.cpp +++ b/g2core/temperature.cpp @@ -52,19 +52,23 @@ #define HAS_TEMPERATURE_SENSOR_3 false #endif #ifndef EXTRUDER_1_OUTPUT_PIN +#warning using default extruder 1 output pin #define EXTRUDER_1_OUTPUT_PIN kOutput1_PinNumber #endif #ifndef EXTRUDER_1_FAN_PIN #define EXTRUDER_1_FAN_PIN kOutput3_PinNumber #endif #ifndef EXTRUDER_2_OUTPUT_PIN +#warning using default extruder 2 output pin #define EXTRUDER_2_OUTPUT_PIN kOutput2_PinNumber #endif #ifndef BED_OUTPUT_PIN #define BED_OUTPUT_PIN kOutput11_PinNumber #endif #ifndef BED_OUTPUT_INIT -#define BED_OUTPUT_INIT +#define BED_OUTPUT_INIT {kNormal, fet_pin3_freq} +// OR +//#define BED_OUTPUT_INIT {kPWMPinInverted, fet_pin3_freq}; #endif // These could be moved to settings @@ -206,13 +210,18 @@ struct ValueHistory { float temp = 0; float std_dev = get_std_dev(); - for (uint16_t i=0; i fet_pin1;// {kPWMPinInverted}; +PWMOutputPin fet_pin1 {kNormal, fet_pin1_freq};// {kPWMPinInverted, fet_pin1_freq}; #else -PWMOutputPin<-1> fet_pin1;// {kPWMPinInverted}; +//PWMOutputPin<-1> fet_pin1;// {kPWMPinInverted}; #endif // DO_2: Extruder2_PWM -const int16_t fet_pin2_freq = 100; +const int32_t fet_pin2_freq = 2000; #if TEMPERATURE_OUTPUT_ON == 1 -PWMOutputPin fet_pin2;// {kPWMPinInverted}; +PWMOutputPin fet_pin2 {kNormal, fet_pin2_freq};// {kPWMPinInverted, fet_pin1_freq}; #else -PWMOutputPin<-1> fet_pin2;// {kPWMPinInverted}; +//PWMOutputPin<-1> fet_pin2;// {kPWMPinInverted}; #endif // DO_11: Heated Bed FET // Warning, HeatBED is likely NOT a PWM pin, so it'll be binary output (duty cucle >= 50%). -const int16_t fet_pin3_freq = 100; +const int32_t fet_pin3_freq = 100; #if TEMPERATURE_OUTPUT_ON == 1 PWMOutputPin fet_pin3 BED_OUTPUT_INIT; #else -PWMOutputPin<-1> fet_pin3;// {kPWMPinInverted}; +//PWMOutputPin<-1> fet_pin3;// {kPWMPinInverted}; #endif @@ -527,15 +536,17 @@ SysTickEvent adc_tick_event {[&] { struct PID { static constexpr float output_max = 1.0; - static constexpr float derivative_contribution = 0.05; + static constexpr float derivative_contribution = 1.0/10.0; float _p_factor; // the scale for P values float _i_factor; // the scale for I values float _d_factor; // the scale for D values + float _f_factor; // the scale for O values float _proportional = 0.0; // _proportional storage float _integral = 0.0; // _integral storage float _derivative = 0.0; // _derivative storage + float _feed_forward = 0.0; // _feed_forward storage float _previous_input = 0.0; // _derivative storage float _set_point; @@ -547,9 +558,11 @@ struct PID { float _min_rise_over_time; // the amount of degrees that it must rise in the given time float _rise_time_checkpoint; // when we start the timer, we set _rise_time_checkpoint to the minimum goal + float _average_output = 0; + bool _enable; // set true to enable this heater - PID(float P, float I, float D, float min_rise_over_time, float startSetPoint = 0.0) : _p_factor{P/100.0f}, _i_factor{I/100.0f}, _d_factor{D/100.0f}, _set_point{startSetPoint}, _at_set_point{false}, _min_rise_over_time(min_rise_over_time) {}; + PID(float P, float I, float D, float F, float min_rise_over_time, float startSetPoint = 0.0) : _p_factor{P/100.0f}, _i_factor{I/100.0f}, _d_factor{D/100.0f}, _f_factor{F/100.0f}, _set_point{startSetPoint}, _at_set_point{false}, _min_rise_over_time(min_rise_over_time) {}; float getNewOutput(float input) { // If the input is < 0, the sensor failed @@ -598,39 +611,89 @@ struct PID { } } + // Now tha we've done all the checks, square the error, maintaining the sign. + // The is because the energy required to heat an object is the number of degrees of change needed squared. + if (e > 0) { + e = e*e; + } else { + e = -(e*e); + } + + // P = Proportional + float p = _p_factor * e; // For output's sake, we'll store this, otherwise we don't need it: _proportional = p; + + // I = Integral + + // Now, to restrict windup, prevent the integral from contributing too much, AND to keep it sane: + // 1) Limit the i contribution to the output + // 2) Limit the _integral maximum value + // 3) Reset _integral to e if output has to be clamped (after output is computed) _integral += e; + float i = _integral * _i_factor; - if (_integral < 0.0) { - _integral = 0.0; + if (i > 0.75) { + i = 0.75; + _integral = 0.75 / _i_factor; + } else if (i < -0.75) { + i = -0.75; + _integral = -0.75 / _i_factor; } - float i = _integral * _i_factor; + // D = derivative + + // This needs to be smoothed somewhat, so we use a exponential moving average. + // See https://en.wikipedia.org/wiki/Moving_average#Exponential_moving_average + + + _derivative = (input - _previous_input)*(derivative_contribution) + (_derivative * (1.0-derivative_contribution)); + float d = _derivative * _d_factor; - if (i > output_max) { - _integral = output_max / _i_factor; - i = output_max; + _feed_forward = (_set_point-21); // 21 is for a roughly ideal room temperature + if (_feed_forward > 0) { + _feed_forward = _feed_forward*_feed_forward; + } else { + _feed_forward = -(_feed_forward*_feed_forward); } + float f = _f_factor * _feed_forward; - _derivative = (_d_factor * (input - _previous_input))*(derivative_contribution) + (_derivative * (1.0-derivative_contribution)); _previous_input = input; // Now that we've computed all that, we'll decide when to ignore it + float output = p + i + f - d; + if (output < 0.0f) { + output = 0; + + // reset the integral to prevent windup + _integral = e; + } else if (output > output_max) { + output = output_max; + + // reset the integral to prevent windup + _integral = e; + } + // If the setpoint is "off" or the temperature is higher than MAX, always return OFF if ((_set_point < TEMP_OFF_BELOW) || (input > TEMP_MAX_SETPOINT)) { - return 0; // "off" + output = 0; // "off" + _average_output = 0; + return 0; // If we are too far from the set point, turn the heater full on - } else if (e > TEMP_FULL_ON_DIFFERENCE) { - return 1; //"on" } +// else if (e > TEMP_FULL_ON_DIFFERENCE) { +// output = 1; // "on" +// } - return std::min(output_max, p + i - _derivative); + // Keep track of our output with some averaging for output purposes + _average_output = (0.5*output) + (0.5*_average_output); + + return _average_output; // return the smoothed value }; bool atSetPoint() { @@ -651,9 +714,9 @@ struct PID { // NOTICE, the JSON alters incoming values for these! // {he1p:9} == 9.0/100.0 here -PID pid1 { 9.0, 0.11, 400.0, TEMP_MIN_RISE_DEGREES_OVER_TIME }; // default values -PID pid2 { 7.5, 0.12, 400.0, TEMP_MIN_RISE_DEGREES_OVER_TIME }; // default values -PID pid3 { 7.5, 0.12, 400.0, TEMP_MIN_BED_RISE_DEGREES_OVER_TIME }; // default values +PID pid1 { 9.0, 0.11, 400.0, 0, TEMP_MIN_RISE_DEGREES_OVER_TIME }; // default values +PID pid2 { 7.5, 0.12, 400.0, 0, TEMP_MIN_RISE_DEGREES_OVER_TIME }; // default values +PID pid3 { 7.5, 0.12, 400.0, 0, TEMP_MIN_BED_RISE_DEGREES_OVER_TIME }; // default values Timeout pid_timeout; @@ -699,9 +762,9 @@ HeaterFan heater_fan1; void temperature_init() { // setup heater PWM - fet_pin1.setFrequency(fet_pin1_freq); - fet_pin2.setFrequency(fet_pin2_freq); - fet_pin3.setFrequency(fet_pin3_freq); +// fet_pin1.setFrequency(fet_pin1_freq); +// fet_pin2.setFrequency(fet_pin2_freq); +// fet_pin3.setFrequency(fet_pin3_freq); // fan_pin1 = 0; // fan_pin1.setFrequency(200000); @@ -761,7 +824,8 @@ stat_t temperature_callback() if (pid1._enable) { temp = temperature_sensor_1.temperature_exact(); - fet_pin1 = pid1.getNewOutput(temp); + float out1 = pid1.getNewOutput(temp); + fet_pin1.write(out1); if (fabs(temp - last_reported_temp1) > kTempDiffSRTrigger) { last_reported_temp1 = temp; @@ -772,7 +836,8 @@ stat_t temperature_callback() if (pid2._enable) { temp = temperature_sensor_2.temperature_exact(); - fet_pin2 = pid2.getNewOutput(temp); + float out2 = pid2.getNewOutput(temp); + fet_pin2.write(out2); if (fabs(temp - last_reported_temp2) > kTempDiffSRTrigger) { last_reported_temp2 = temp; @@ -785,7 +850,8 @@ stat_t temperature_callback() if (pid3._enable) { temp = temperature_sensor_3.temperature_exact(); - fet_pin3 = pid3.getNewOutput(temp); + float out3 = pid3.getNewOutput(temp); + fet_pin3.write(out3); if (fabs(temp - last_reported_temp3) > kTempDiffSRTrigger) { last_reported_temp3 = temp; @@ -948,6 +1014,35 @@ stat_t cm_set_heater_d(nvObj_t *nv) return (STAT_OK); } +/* + * cm_get_heater_f()/cm_set_heater_f() - get/set the F parameter of the PIDF + */ +stat_t cm_get_heater_f(nvObj_t *nv) +{ + switch(_get_heater_number(nv)) { + case '1': { nv->value = pid1._f_factor * 100.0; break; } + case '2': { nv->value = pid2._f_factor * 100.0; break; } + case '3': { nv->value = pid3._f_factor * 100.0; break; } + + default: { nv->value = 0.0; break; } + } + nv->precision = GET_TABLE_WORD(precision); + nv->valuetype = TYPE_FLOAT; + + return (STAT_OK); +} +stat_t cm_set_heater_f(nvObj_t *nv) +{ + switch(_get_heater_number(nv)) { + case '1': { pid1._f_factor = nv->value / 100.0; break; } + case '2': { pid2._f_factor = nv->value / 100.0; break; } + case '3': { pid3._f_factor = nv->value / 100.0; break; } + + default: { break; } + } + return (STAT_OK); +} + /* * cm_get_set_temperature()/cm_set_set_temperature() - get/set the set value of the PID * @@ -1152,9 +1247,9 @@ stat_t cm_get_at_temperature(nvObj_t *nv) float cm_get_heater_output(const uint8_t heater) { switch(heater) { - case 1: { return (float)fet_pin1; } - case 2: { return (float)fet_pin2; } - case 3: { return (float)fet_pin3; } + case 1: { return pid1._average_output; } + case 2: { return pid2._average_output; } + case 3: { return pid3._average_output; } default: { break; } } @@ -1313,6 +1408,24 @@ stat_t cm_get_pid_d(nvObj_t *nv) return (STAT_OK); } +/* + * cm_get_pid_f() - get the active F of the PID (read-only) + */ +stat_t cm_get_pid_f(nvObj_t *nv) +{ + switch(_get_pid_number(nv)) { + case '1': { nv->value = pid1._feed_forward; break; } + case '2': { nv->value = pid2._feed_forward; break; } + case '3': { nv->value = pid3._feed_forward; break; } + + default: { nv->value = 0.0; break; } + } + nv->precision = GET_TABLE_WORD(precision); + nv->valuetype = TYPE_FLOAT; + + return (STAT_OK); +} + /*********************************************************************************** * TEXT MODE SUPPORT diff --git a/g2core/temperature.h b/g2core/temperature.h index 3912a9c41..d6e6cdf71 100755 --- a/g2core/temperature.h +++ b/g2core/temperature.h @@ -46,9 +46,12 @@ stat_t cm_get_heater_i(nvObj_t* nv); stat_t cm_set_heater_i(nvObj_t* nv); stat_t cm_get_heater_d(nvObj_t* nv); stat_t cm_set_heater_d(nvObj_t* nv); +stat_t cm_get_heater_f(nvObj_t* nv); +stat_t cm_set_heater_f(nvObj_t* nv); stat_t cm_get_pid_p(nvObj_t* nv); stat_t cm_get_pid_i(nvObj_t* nv); stat_t cm_get_pid_d(nvObj_t* nv); +stat_t cm_get_pid_f(nvObj_t* nv); float cm_get_set_temperature(const uint8_t heater); stat_t cm_get_set_temperature(nvObj_t* nv); From cda38cd25abbd85c3f63f9f1a68747b32d31e638 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Fri, 21 Apr 2017 11:43:18 -0500 Subject: [PATCH 072/193] Fixes for step/dir hobby servo PWMPin usage. --- g2core/device/step_dir_hobbyservo/step_dir_hobbyservo.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/g2core/device/step_dir_hobbyservo/step_dir_hobbyservo.h b/g2core/device/step_dir_hobbyservo/step_dir_hobbyservo.h index cfef808f4..e0a46c6a7 100644 --- a/g2core/device/step_dir_hobbyservo/step_dir_hobbyservo.h +++ b/g2core/device/step_dir_hobbyservo/step_dir_hobbyservo.h @@ -106,12 +106,12 @@ struct StepDirHobbyServo final : Stepper { void _enableImpl() override { _enabled = true; - _pwm_pin.setExactDutyCycle(_position_computed, true); + _pwm_pin.setExactDutyCycle(_position_computed); }; void _disableImpl() override { _enabled = false; - _pwm_pin.setExactDutyCycle(0, true); + _pwm_pin.setExactDutyCycle(0); }; void stepStart() override { @@ -135,7 +135,7 @@ struct StepDirHobbyServo final : Stepper { } _position_computed = _min_value + ((used_position/6400.0) * _value_range); - _pwm_pin.setExactDutyCycle(_position_computed, true); // apply the change + _pwm_pin.setExactDutyCycle(_position_computed); // apply the change }; void stepEnd() override { From a2ee622f62e535c252f605c6d0de3e6a7c40d29f Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Fri, 21 Apr 2017 11:43:44 -0500 Subject: [PATCH 073/193] Exposing F in PIDF via JSON. --- g2core/config_app.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/g2core/config_app.cpp b/g2core/config_app.cpp index 8494dd471..f39f4218f 100644 --- a/g2core/config_app.cpp +++ b/g2core/config_app.cpp @@ -477,14 +477,17 @@ const cfgItem_t cfgArray[] = { { "pid1","pid1p",_f0, 3, tx_print_nul, cm_get_pid_p, set_ro, (float *)&cs.null, 0 }, { "pid1","pid1i",_f0, 5, tx_print_nul, cm_get_pid_i, set_ro, (float *)&cs.null, 0 }, { "pid1","pid1d",_f0, 5, tx_print_nul, cm_get_pid_d, set_ro, (float *)&cs.null, 0 }, + { "pid1","pid1f",_f0, 5, tx_print_nul, cm_get_pid_f, set_ro, (float *)&cs.null, 0 }, { "pid2","pid2p",_f0, 3, tx_print_nul, cm_get_pid_p, set_ro, (float *)&cs.null, 0 }, { "pid2","pid2i",_f0, 5, tx_print_nul, cm_get_pid_i, set_ro, (float *)&cs.null, 0 }, { "pid2","pid2d",_f0, 5, tx_print_nul, cm_get_pid_d, set_ro, (float *)&cs.null, 0 }, + { "pid2","pid2f",_f0, 5, tx_print_nul, cm_get_pid_f, set_ro, (float *)&cs.null, 0 }, { "pid3","pid3p",_f0, 3, tx_print_nul, cm_get_pid_p, set_ro, (float *)&cs.null, 0 }, { "pid3","pid3i",_f0, 5, tx_print_nul, cm_get_pid_i, set_ro, (float *)&cs.null, 0 }, { "pid3","pid3d",_f0, 5, tx_print_nul, cm_get_pid_d, set_ro, (float *)&cs.null, 0 }, + { "pid3","pid3f",_f0, 5, tx_print_nul, cm_get_pid_f, set_ro, (float *)&cs.null, 0 }, // temperature configs - heater set values (read-write) // NOTICE: If you change these heater group keys, you MUST change the get/set functions too!! @@ -492,6 +495,7 @@ const cfgItem_t cfgArray[] = { { "he1","he1p", _fi, 3, tx_print_nul, cm_get_heater_p, cm_set_heater_p, (float *)&cs.null, H1_DEFAULT_P }, { "he1","he1i", _fi, 5, tx_print_nul, cm_get_heater_i, cm_set_heater_i, (float *)&cs.null, H1_DEFAULT_I }, { "he1","he1d", _fi, 5, tx_print_nul, cm_get_heater_d, cm_set_heater_d, (float *)&cs.null, H1_DEFAULT_D }, + { "he1","he1f", _fi, 5, tx_print_nul, cm_get_heater_f, cm_set_heater_f, (float *)&cs.null, H1_DEFAULT_F }, { "he1","he1st",_f0, 1, tx_print_nul, cm_get_set_temperature, cm_set_set_temperature, (float *)&cs.null, 0 }, { "he1","he1t", _f0, 1, tx_print_nul, cm_get_temperature, set_ro, (float *)&cs.null, 0 }, { "he1","he1op",_f0, 3, tx_print_nul, cm_get_heater_output, set_ro, (float *)&cs.null, 0 }, @@ -508,6 +512,7 @@ const cfgItem_t cfgArray[] = { { "he2","he2p", _fi, 3, tx_print_nul, cm_get_heater_p, cm_set_heater_p, (float *)&cs.null, H2_DEFAULT_P }, { "he2","he2i", _fi, 5, tx_print_nul, cm_get_heater_i, cm_set_heater_i, (float *)&cs.null, H2_DEFAULT_I }, { "he2","he2d", _fi, 5, tx_print_nul, cm_get_heater_d, cm_set_heater_d, (float *)&cs.null, H2_DEFAULT_D }, + { "he2","he2f", _fi, 5, tx_print_nul, cm_get_heater_f, cm_set_heater_f, (float *)&cs.null, H2_DEFAULT_F }, { "he2","he2st",_f0, 0, tx_print_nul, cm_get_set_temperature, cm_set_set_temperature, (float *)&cs.null, 0 }, { "he2","he2t", _f0, 1, tx_print_nul, cm_get_temperature, set_ro, (float *)&cs.null, 0 }, { "he2","he2op",_f0, 3, tx_print_nul, cm_get_heater_output, set_ro, (float *)&cs.null, 0 }, @@ -524,6 +529,7 @@ const cfgItem_t cfgArray[] = { { "he3","he3p", _fi, 3, tx_print_nul, cm_get_heater_p, cm_set_heater_p, (float *)&cs.null, H3_DEFAULT_P }, { "he3","he3i", _fi, 5, tx_print_nul, cm_get_heater_i, cm_set_heater_i, (float *)&cs.null, H3_DEFAULT_I }, { "he3","he3d", _fi, 5, tx_print_nul, cm_get_heater_d, cm_set_heater_d, (float *)&cs.null, H3_DEFAULT_D }, + { "he3","he3f", _fi, 5, tx_print_nul, cm_get_heater_f, cm_set_heater_f, (float *)&cs.null, H3_DEFAULT_F }, { "he3","he3st",_f0, 0, tx_print_nul, cm_get_set_temperature, cm_set_set_temperature, (float *)&cs.null, 0 }, { "he3","he3t", _f0, 1, tx_print_nul, cm_get_temperature, set_ro, (float *)&cs.null, 0 }, { "he3","he3op",_f0, 3, tx_print_nul, cm_get_heater_output, set_ro, (float *)&cs.null, 0 }, From 9cb5ca47df872f3af16c9ca27f466a773de633e5 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Fri, 21 Apr 2017 11:44:43 -0500 Subject: [PATCH 074/193] Update motate reference for PWMPin fixes --- Motate | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Motate b/Motate index 152891e70..f1260b95f 160000 --- a/Motate +++ b/Motate @@ -1 +1 @@ -Subproject commit 152891e708c094629870abacf0f59bc08f5a1cad +Subproject commit f1260b95f1e3c2db7032ed38de724f910a3046ac From 43ccc96d7eefa748f754788396728ed99ac85dd8 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Tue, 25 Apr 2017 09:11:08 -0500 Subject: [PATCH 075/193] Update to using the new arm toolchain. (Includes Motate update) --- Motate | 2 +- g2core/Makefile | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Motate b/Motate index f1260b95f..d12aa8dfe 160000 --- a/Motate +++ b/Motate @@ -1 +1 @@ -Subproject commit f1260b95f1e3c2db7032ed38de724f910a3046ac +Subproject commit d12aa8dfea220a9d44ef53123958dd384d315c2e diff --git a/g2core/Makefile b/g2core/Makefile index 346a8a330..8a98eec86 100755 --- a/g2core/Makefile +++ b/g2core/Makefile @@ -62,7 +62,7 @@ ifeq ($(DEBUG),3) DEVICE_DEFINES += DEBUG=1 IN_DEBUGGER=1 DEBUG_SEMIHOSTING=1 endif -TOOLS_VERSION = 6.2 +TOOLS_VERSION = "6.2u1" # Now invoke the Motate compile system include $(MOTATE_PATH)/Motate.mk From 86651f6a4cae7ca69b7367441af4794ce46f7815 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Tue, 25 Apr 2017 09:11:15 -0500 Subject: [PATCH 076/193] Remove redundant file --- .../step_dir_driver/step_dir_driver.cpp | 27 ------------------- 1 file changed, 27 deletions(-) delete mode 100644 g2core/device/step_dir_driver/step_dir_driver.cpp diff --git a/g2core/device/step_dir_driver/step_dir_driver.cpp b/g2core/device/step_dir_driver/step_dir_driver.cpp deleted file mode 100644 index b6b06db93..000000000 --- a/g2core/device/step_dir_driver/step_dir_driver.cpp +++ /dev/null @@ -1,27 +0,0 @@ -/* - * step_dir_driver.cpp - control over a Step/Direction/Enable stepper motor driver - * This file is part of the G2 project - * - * Copyright (c) 2016 Alden S. Hart, Jr. - * Copyright (c) 2016 Robert Giseburt - * - * This file ("the software") is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License, version 2 as published by the - * Free Software Foundation. You should have received a copy of the GNU General Public - * License, version 2 along with the software. If not, see . - * - * As a special exception, you may use this file as part of a software library without - * restriction. Specifically, if other files instantiate templates or use macros or - * inline functions from this file, or you compile this file and link it with other - * files to produce an executable, this file does not by itself cause the resulting - * executable to be covered by the GNU General Public License. This exception does not - * however invalidate any other reasons why the executable file might be covered by the - * GNU General Public License. - * - * THE SOFTWARE IS DISTRIBUTED IN THE HOPE THAT IT WILL BE USEFUL, BUT WITHOUT ANY - * WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES - * OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT - * SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF - * OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - */ From c58a1de0f3fd4b2c9b71da75bc597288990d4b97 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Tue, 25 Apr 2017 09:11:36 -0500 Subject: [PATCH 077/193] Update mb analyze (will not only work with quintic without mods) --- Resources/debug/mb.gdb | 99 ++++++++++++++++++++++++++++++++++- Resources/debug/mb_analyze.py | 76 ++++++++++++++++----------- 2 files changed, 143 insertions(+), 32 deletions(-) diff --git a/Resources/debug/mb.gdb b/Resources/debug/mb.gdb index e57e15739..f3165887d 100644 --- a/Resources/debug/mb.gdb +++ b/Resources/debug/mb.gdb @@ -3,12 +3,13 @@ set logging overwrite on set logging redirect on set logging file mb.txt set logging on +print sizeof(mb.bf)/sizeof(mb.bf[0]) print mb.r print mb.w print mp.p print mp.c # generated with: -# node -e 'for (i=0; i<48;i++) {console.log("print &mb.bf["+i+"]\nprint mb.bf["+i+"]");}' +# node -e 'for (i=0; i<96;i++) {console.log("print &mb.bf["+i+"]\nprint mb.bf["+i+"]");}' print &mb.bf[0] print mb.bf[0] print &mb.bf[1] @@ -105,5 +106,101 @@ print &mb.bf[46] print mb.bf[46] print &mb.bf[47] print mb.bf[47] +print &mb.bf[48] +print mb.bf[48] +print &mb.bf[49] +print mb.bf[49] +print &mb.bf[50] +print mb.bf[50] +print &mb.bf[51] +print mb.bf[51] +print &mb.bf[52] +print mb.bf[52] +print &mb.bf[53] +print mb.bf[53] +print &mb.bf[54] +print mb.bf[54] +print &mb.bf[55] +print mb.bf[55] +print &mb.bf[56] +print mb.bf[56] +print &mb.bf[57] +print mb.bf[57] +print &mb.bf[58] +print mb.bf[58] +print &mb.bf[59] +print mb.bf[59] +print &mb.bf[60] +print mb.bf[60] +print &mb.bf[61] +print mb.bf[61] +print &mb.bf[62] +print mb.bf[62] +print &mb.bf[63] +print mb.bf[63] +print &mb.bf[64] +print mb.bf[64] +print &mb.bf[65] +print mb.bf[65] +print &mb.bf[66] +print mb.bf[66] +print &mb.bf[67] +print mb.bf[67] +print &mb.bf[68] +print mb.bf[68] +print &mb.bf[69] +print mb.bf[69] +print &mb.bf[70] +print mb.bf[70] +print &mb.bf[71] +print mb.bf[71] +print &mb.bf[72] +print mb.bf[72] +print &mb.bf[73] +print mb.bf[73] +print &mb.bf[74] +print mb.bf[74] +print &mb.bf[75] +print mb.bf[75] +print &mb.bf[76] +print mb.bf[76] +print &mb.bf[77] +print mb.bf[77] +print &mb.bf[78] +print mb.bf[78] +print &mb.bf[79] +print mb.bf[79] +print &mb.bf[80] +print mb.bf[80] +print &mb.bf[81] +print mb.bf[81] +print &mb.bf[82] +print mb.bf[82] +print &mb.bf[83] +print mb.bf[83] +print &mb.bf[84] +print mb.bf[84] +print &mb.bf[85] +print mb.bf[85] +print &mb.bf[86] +print mb.bf[86] +print &mb.bf[87] +print mb.bf[87] +print &mb.bf[88] +print mb.bf[88] +print &mb.bf[89] +print mb.bf[89] +print &mb.bf[90] +print mb.bf[90] +print &mb.bf[91] +print mb.bf[91] +print &mb.bf[92] +print mb.bf[92] +print &mb.bf[93] +print mb.bf[93] +print &mb.bf[94] +print mb.bf[94] +print &mb.bf[95] +print mb.bf[95] set logging off shell python ../Resources/debug/mb_analyze.py mb.txt diff --git a/Resources/debug/mb_analyze.py b/Resources/debug/mb_analyze.py index 3e3368cb0..483cd9321 100644 --- a/Resources/debug/mb_analyze.py +++ b/Resources/debug/mb_analyze.py @@ -3,14 +3,14 @@ import sys STATES = { - 0 : 'EMPTY', - 1 : 'PLANNING', - 2 : 'QUEUED', - 3 : 'PENDING', - 4 : 'RUNNING' + 0: 'EMPTY', + 1: 'PLANNING', + 2: 'QUEUED', + 3: 'PENDING', + 4: 'RUNNING' } -TUMBLER = ['r', 'w', 'p', 'c'] +TUMBLER = ['size', 'r', 'w', 'p', 'c'] def load_pool(filename): @@ -25,8 +25,15 @@ def load_pool(filename): if buf: current_buffer = int(buf.groups()[0], 16) pool[TUMBLER[tumbler_pos]] = current_buffer - print "TUMBLER[tumbler_pos]: %s=%i" % (TUMBLER[tumbler_pos], current_buffer) - tumbler_pos += 1 + print 'TUMBLER[tumbler_pos]: %s=%d' % ( + TUMBLER[tumbler_pos], current_buffer + ) + else: + buf = re.search(' = ([0-9]+)', line) + current_buffer = int(buf.groups()[0], 10) + pool[TUMBLER[tumbler_pos]] = current_buffer + + tumbler_pos += 1 else: buf = re.search('\(mpBuf_t\s\*\)\s(0x[0-9a-fA-F]+)', line) if buf: @@ -42,7 +49,9 @@ def load_pool(filename): if current_buffer == pool['c']: pool[current_buffer]['is_c'] = True else: - match = re.search('([a-zA-Z_]+)\s=\s((?:0x[0-9a-fA-F]+|[0-9.]+(?:e[-+][0-9]+)?|[A-Z_]+)|true|false)', line) + match = re.search('([a-zA-Z_]+)\s=\s((?:0x[0-9a-fA-F]+|' + '[0-9.]+(?:e[-+][0-9]+)?|[A-Z_]+)|true|' + 'false)', line) if match: # print "current_buffer: %s" % current_buffer key, val = match.groups() @@ -85,6 +94,7 @@ def load_pool(filename): pool[current_buffer]['iterations'] = val return pool + def check_integrity(pool): key = pool.keys()[0] buffers = set() @@ -97,14 +107,16 @@ def check_integrity(pool): count += 1 - if count != 48: + if count != pool['size']: raise Exception("Buffer pool integrity is bad.") + def check_pool(filename): pool = load_pool(filename) check_integrity(pool) return pool + def print_pool(pool): for key in sorted(pool.keys()): buffer = pool[key] @@ -141,27 +153,29 @@ def print_pool(pool): else: junction_str = "!" - print '0x%08x [%02d] : N%04d (%02dx) %-22s %-8s L% 8.2f Ti% 8.2f C% 10.2f %1s[% 10.2f] X% 10.2f %1s[% 10.2f] J%1s% 10.2f %5s %20s (%5.2f)' % ( - key, - float(buffer['buffer_number']), - float(buffer['linenum']), - int(buffer['iterations']), - buffer['buffer_state'].strip(), - pointer, - float(buffer['length']), - float(buffer['move_time']), - float(buffer['cruise_velocity']), - cruise_str, - float(buffer['cruise_vmax']), - float(buffer['exit_velocity']), - exit_str, - float(buffer['exit_vmax']), - junction_str, - float(buffer['junction_vmax']), - buffer['plannable'], - buffer['hint'], - float(buffer['jerk'])/1000000.0 - ) + print '0x%08x [%02d] : N%06d (%02dx) %-22s %-8s L% 8.2f Ti% 8.2f '\ + 'C% 10.2f %1s[% 10.2f] X% 10.2f %1s[% 10.2f] J%1s% 10.2f ' \ + '%5s %20s (%5.2f)' % ( + key, + float(buffer['buffer_number']), # [] + float(buffer['linenum']), # N + int(buffer['iterations']), # () + buffer['buffer_state'].strip(), + pointer, # (w,p,r) + float(buffer['length']), # L + float(buffer['move_time']), # Ti + float(buffer['cruise_velocity']), # C + cruise_str, + float(buffer['cruise_vmax']), + float(buffer['exit_velocity']), # X + exit_str, + float(buffer['exit_vmax']), + junction_str, # J + float(buffer['junction_vmax']), + buffer['plannable'], + buffer['hint'], + float(buffer['jerk'])/1000000.0 + ) if __name__ == "__main__": pool = check_pool(sys.argv[1]) From 971835a27c86c2472ccee852f03f9c2e05c45ba6 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Tue, 25 Apr 2017 09:12:02 -0500 Subject: [PATCH 078/193] Fix URL referenced in quintic-b-pinout.h --- g2core/board/gquintic/gquintic-b-pinout.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/g2core/board/gquintic/gquintic-b-pinout.h b/g2core/board/gquintic/gquintic-b-pinout.h index 2df8401c3..5348a2765 100755 --- a/g2core/board/gquintic/gquintic-b-pinout.h +++ b/g2core/board/gquintic/gquintic-b-pinout.h @@ -36,7 +36,7 @@ * USAGE NOTES * * Read this first: - * https://github.com/synthetos/g2/wiki/Adding-a-new-G2-board-(or-revision)-to-G2#making-a-new-pin-assignment + * https://github.com/synthetos/g2/wiki/Adding-and-Revising-Boards * * USAGE: * From 4730b562bea7dfce7c4b70ce0119facbb3c929c3 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Tue, 25 Apr 2017 14:41:45 -0500 Subject: [PATCH 079/193] Fixes to GPIO initialization --- g2core/gpio.cpp | 78 ++++++++++++++++++++++++------------------------- 1 file changed, 39 insertions(+), 39 deletions(-) diff --git a/g2core/gpio.cpp b/g2core/gpio.cpp index edcf6a65e..4c93e849f 100644 --- a/g2core/gpio.cpp +++ b/g2core/gpio.cpp @@ -234,69 +234,69 @@ ioDigitalInputExt _din12; // perl -e 'for($i=1;$i<14;$i++) { print "#if OUTPUT${i}_PWM == 1\nstatic PWMOutputPin output_${i}_pin;\n#else\nstatic PWMLikeOutputPin output_${i}_pin;\n#endif\n";}' // BEGIN generated #if OUTPUT1_PWM == 1 -static PWMOutputPin output_1_pin {kNormal, 200000}; +static PWMOutputPin output_1_pin {(DO1_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; #else -static PWMLikeOutputPin output_1_pin; +static PWMLikeOutputPin output_1_pin {(DO1_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; #endif #if OUTPUT2_PWM == 1 -static PWMOutputPin output_2_pin {kNormal, 200000}; +static PWMOutputPin output_2_pin {(DO2_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; #else -static PWMLikeOutputPin output_2_pin; +static PWMLikeOutputPin output_2_pin {(DO2_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; #endif #if OUTPUT3_PWM == 1 -static PWMOutputPin output_3_pin {kNormal, 200000}; +static PWMOutputPin output_3_pin {(DO3_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; #else -static PWMLikeOutputPin output_3_pin; +static PWMLikeOutputPin output_3_pin {(DO3_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; #endif #if OUTPUT4_PWM == 1 -static PWMOutputPin output_4_pin {kNormal, 200000}; +static PWMOutputPin output_4_pin {(DO4_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; #else -static PWMLikeOutputPin output_4_pin; +static PWMLikeOutputPin output_4_pin {(DO4_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; #endif #if OUTPUT5_PWM == 1 -static PWMOutputPin output_5_pin {kNormal, 200000}; +static PWMOutputPin output_5_pin {(DO5_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; #else -static PWMLikeOutputPin output_5_pin; +static PWMLikeOutputPin output_5_pin {(DO5_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; #endif #if OUTPUT6_PWM == 1 -static PWMOutputPin output_6_pin {kNormal, 200000}; +static PWMOutputPin output_6_pin {(DO6_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; #else -static PWMLikeOutputPin output_6_pin; +static PWMLikeOutputPin output_6_pin {(DO6_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; #endif #if OUTPUT7_PWM == 1 -static PWMOutputPin output_7_pin {kNormal, 200000}; +static PWMOutputPin output_7_pin {(DO7_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; #else -static PWMLikeOutputPin output_7_pin; +static PWMLikeOutputPin output_7_pin {(DO7_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; #endif #if OUTPUT8_PWM == 1 -static PWMOutputPin output_8_pin {kNormal, 200000}; +static PWMOutputPin output_8_pin {(DO8_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; #else -static PWMLikeOutputPin output_8_pin; +static PWMLikeOutputPin output_8_pin {(DO8_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow}; #endif #if OUTPUT9_PWM == 1 -static PWMOutputPin output_9_pin {kNormal, 200000}; +static PWMOutputPin output_9_pin {(DO9_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; #else -static PWMLikeOutputPin output_9_pin; +static PWMLikeOutputPin output_9_pin {(DO9_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; #endif #if OUTPUT10_PWM == 1 -static PWMOutputPin output_10_pin {kNormal, 200000}; +static PWMOutputPin output_10_pin {(DO10_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; #else -static PWMLikeOutputPin output_10_pin; +static PWMLikeOutputPin output_10_pin {(DO10_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; #endif #if OUTPUT11_PWM == 1 -static PWMOutputPin output_11_pin {kNormal, 200000}; +static PWMOutputPin output_11_pin {(DO11_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; #else -static PWMLikeOutputPin output_11_pin; +static PWMLikeOutputPin output_11_pin {(DO11_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; #endif #if OUTPUT12_PWM == 1 -static PWMOutputPin output_12_pin {kNormal, 200000}; +static PWMOutputPin output_12_pin {(DO12_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; #else -static PWMLikeOutputPin output_12_pin; +static PWMLikeOutputPin output_12_pin {(DO12_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; #endif #if OUTPUT13_PWM == 1 -static PWMOutputPin output_13_pin {kNormal, 200000}; +static PWMOutputPin output_13_pin {(DO13_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; #else -static PWMLikeOutputPin output_13_pin; +static PWMLikeOutputPin output_13_pin {(DO13_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; #endif // END generated @@ -315,19 +315,19 @@ void gpio_init(void) // Generated with: // perl -e 'for($i=1;$i<14;$i++) { print "output_${i}_pin.setFrequency(200000);\n";}' // BEGIN generated - output_1_pin.setFrequency(200000); - output_2_pin.setFrequency(200000); - output_3_pin.setFrequency(200000); - output_4_pin.setFrequency(200000); - output_5_pin.setFrequency(200000); - output_6_pin.setFrequency(200000); - output_7_pin.setFrequency(200000); - output_8_pin.setFrequency(200000); - output_9_pin.setFrequency(200000); - output_10_pin.setFrequency(200000); - output_11_pin.setFrequency(200000); - output_12_pin.setFrequency(200000); - output_13_pin.setFrequency(200000); +// output_1_pin.setFrequency(200000); +// output_2_pin.setFrequency(200000); +// output_3_pin.setFrequency(200000); +// output_4_pin.setFrequency(200000); +// output_5_pin.setFrequency(200000); +// output_6_pin.setFrequency(200000); +// output_7_pin.setFrequency(200000); +// output_8_pin.setFrequency(200000); +// output_9_pin.setFrequency(200000); +// output_10_pin.setFrequency(200000); +// output_11_pin.setFrequency(200000); +// output_12_pin.setFrequency(200000); +// output_13_pin.setFrequency(200000); // END generated return(gpio_reset()); From e806e37dc9c4b98d3076cf73c42f772fa09a6a3c Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Thu, 27 Apr 2017 15:35:10 -0400 Subject: [PATCH 080/193] =?UTF-8?q?Fix=20where=20gcode=20flavor=20wasn?= =?UTF-8?q?=E2=80=99t=20reset=20on=20disconnect.?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- g2core/controller.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/g2core/controller.cpp b/g2core/controller.cpp index 0cb3fbf94..1925fb2a6 100644 --- a/g2core/controller.cpp +++ b/g2core/controller.cpp @@ -324,6 +324,7 @@ void _reset_comms_mode() { // reset the communications mode cs.comm_mode = COMM_MODE; js.json_mode = (COMM_MODE < AUTO_MODE) ? COMM_MODE : JSON_MODE; + mst.marlin_flavor = false; sr.status_report_verbosity = STATUS_REPORT_VERBOSITY; qr.queue_report_verbosity = QUEUE_REPORT_VERBOSITY; } From 1c9111c0ee1c37316f765357d04579dfbad16b8a Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Thu, 27 Apr 2017 15:35:20 -0400 Subject: [PATCH 081/193] Update motate reference for typos --- Motate | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Motate b/Motate index d12aa8dfe..c026a30ef 160000 --- a/Motate +++ b/Motate @@ -1 +1 @@ -Subproject commit d12aa8dfea220a9d44ef53123958dd384d315c2e +Subproject commit c026a30ef28deb8696d599de4bfa08af0588ee27 From 4f7a6e090a31bf3e4d57f7e6a2bed1065b4a417f Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Thu, 27 Apr 2017 19:59:23 -0400 Subject: [PATCH 082/193] =?UTF-8?q?Tweaks=20to=20stepper:=20don=E2=80=99t?= =?UTF-8?q?=20turn=20of=20dad=20timer,=20and=20use=20std::min=20instead=20?= =?UTF-8?q?of=20min3?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- g2core/stepper.cpp | 9 +++++---- g2core/util.h | 8 ++++---- 2 files changed, 9 insertions(+), 8 deletions(-) diff --git a/g2core/stepper.cpp b/g2core/stepper.cpp index f3340a191..bafd9bd30 100644 --- a/g2core/stepper.cpp +++ b/g2core/stepper.cpp @@ -286,7 +286,7 @@ void dda_timer_type::interrupt() // process last DDA tick after end of segment if (st_run.dda_ticks_downcount == 0) { - dda_timer.stop(); // turn it off or it will keep stepping out the last segment + // we used to turn off the stepper timer here, but we don't anymore return; } @@ -488,7 +488,7 @@ static void _load_move() //**** setup the new segment **** - st_run.dda_ticks_downcount = st_pre.dda_ticks; + // st_run.dda_ticks_downcount is setup right before turning on the interrupt, since we don't turn it off st_run.dda_ticks_X_substeps = st_pre.dda_ticks_X_substeps; // INLINED VERSION: 4.3us @@ -623,6 +623,7 @@ static void _load_move() //**** do this last **** + st_run.dda_ticks_downcount = st_pre.dda_ticks; dda_timer.start(); // start the DDA timer if not already running // handle dwells and commands @@ -732,9 +733,9 @@ stat_t st_prep_line(float travel_steps[], float following_error[], float segment correction_steps = following_error[motor] * STEP_CORRECTION_FACTOR; if (correction_steps > 0) { - correction_steps = min3(correction_steps, fabs(travel_steps[motor]), STEP_CORRECTION_MAX); + correction_steps = std::min(std::min(correction_steps, fabs(travel_steps[motor])), STEP_CORRECTION_MAX); } else { - correction_steps = max3(correction_steps, -fabs(travel_steps[motor]), -STEP_CORRECTION_MAX); + correction_steps = std::max(std::max(correction_steps, -fabs(travel_steps[motor])), -STEP_CORRECTION_MAX); } st_pre.mot[motor].corrected_steps += correction_steps; travel_steps[motor] -= correction_steps; diff --git a/g2core/util.h b/g2core/util.h index b205b6072..a7322beb4 100644 --- a/g2core/util.h +++ b/g2core/util.h @@ -77,10 +77,10 @@ float *set_vector_by_axis(float value, uint8_t axis); //*** math utilities *** -float min3(float x1, float x2, float x3); -float min4(float x1, float x2, float x3, float x4); -float max3(float x1, float x2, float x3); -float max4(float x1, float x2, float x3, float x4); +//float min3(float x1, float x2, float x3); +//float min4(float x1, float x2, float x3, float x4); +//float max3(float x1, float x2, float x3); +//float max4(float x1, float x2, float x3, float x4); //float std_dev(float a[], uint8_t n, float *mean); //*** string utilities *** From 37914e8a91bfca305cc08beda4072f9da122aa94 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Thu, 27 Apr 2017 19:59:50 -0400 Subject: [PATCH 083/193] Adjust quintic-b-pinout.h back to use the servo instead of out10 --- g2core/board/gquintic/gquintic-b-pinout.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/g2core/board/gquintic/gquintic-b-pinout.h b/g2core/board/gquintic/gquintic-b-pinout.h index 5348a2765..ba8989d33 100755 --- a/g2core/board/gquintic/gquintic-b-pinout.h +++ b/g2core/board/gquintic/gquintic-b-pinout.h @@ -144,8 +144,8 @@ _MAKE_MOTATE_PIN(kADC2_PinNumber, 'A', 19); // AFEC0,8 _MAKE_MOTATE_PIN(kADC1_PinNumber, 'A', 20); // AFEC0,9 _MAKE_MOTATE_PIN(kSerial_CTSPinNumber, 'A', 21); // _MAKE_MOTATE_PIN(kSocket1_EnablePinNumber, 'A', 22); // -_MAKE_MOTATE_PIN(kOutput10_PinNumber, 'A', 23); // PWM 1,2 -//_MAKE_MOTATE_PIN(kServo1_PinNumber, 'A', 23); // +//_MAKE_MOTATE_PIN(kOutput10_PinNumber, 'A', 23); // PWM 1,2 +_MAKE_MOTATE_PIN(kServo1_PinNumber, 'A', 23); // _MAKE_MOTATE_PIN(kSocket3_EnablePinNumber, 'A', 24); // _MAKE_MOTATE_PIN(kSocket2_DirPinNumber, 'A', 25); // _MAKE_MOTATE_PIN(kOutput5_PinNumber, 'A', 26); // TC 2,0 From fab536850fb04fe84177ca49597b3b411ebff077 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Thu, 27 Apr 2017 20:00:19 -0400 Subject: [PATCH 084/193] =?UTF-8?q?Cleanup=20some=20comments=20and=20more?= =?UTF-8?q?=20min/max=20=E2=86=92=20std::min/std::max?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- g2core/plan_line.cpp | 25 +++++++++++-------------- 1 file changed, 11 insertions(+), 14 deletions(-) diff --git a/g2core/plan_line.cpp b/g2core/plan_line.cpp index 892330e8a..400ea9eed 100644 --- a/g2core/plan_line.cpp +++ b/g2core/plan_line.cpp @@ -56,13 +56,12 @@ static void _calculate_vmaxes(mpBuf_t* bf, const float axis_length[], const floa static void _calculate_junction_vmax(mpBuf_t* bf); //+++++DIAGNOSTICS -#pragma GCC optimize("O0") // this pragma is required to force the planner to actually set these unused values -//#pragma GCC reset_options +//#pragma GCC optimize("O0") // this pragma is required to force the planner to actually set these unused values static void _set_bf_diagnostics(mpBuf_t* bf) { bf->linenum = bf->gm.linenum; // UPDATE_BF_DIAGNOSTICS(bf); //+++++ } -#pragma GCC reset_options +//#pragma GCC reset_options /* Runtime-specific setters and getters * @@ -286,16 +285,13 @@ static mpBuf_t* _plan_block(mpBuf_t* bf) if (bf->pv->gm.path_control == PATH_EXACT_STOP) { bf->pv->exit_vmax = 0; } else { - bf->pv->exit_vmax = min3(bf->pv->junction_vmax, bf->pv->cruise_vmax, bf->cruise_vmax); + bf->pv->exit_vmax = std::min(std::min(bf->pv->junction_vmax, bf->pv->cruise_vmax), bf->cruise_vmax); } } _calculate_override(bf); // adjust cruise_vmax for feed/traverse override // bf->plannable_time = bf->pv->plannable_time; // set plannable time - excluding current move bf->buffer_state = MP_BUFFER_IN_PROCESS; - // +++++ Why do we have to do this here? - // bf->pv_group = bf->pv; - bf->hint = NO_HINT; // ensure we've cleared the hints // Time: 12us-41us if (bf->nx->plannable) { // read in new buffers until EMPTY @@ -314,7 +310,7 @@ static mpBuf_t* _plan_block(mpBuf_t* bf) if (mp.planner_state == PLANNER_BACK_PLANNING) { // NOTE: We stop when the previous block is no longer plannable. // We will alter the previous block's exit_velocity. - float braking_velocity = 0; // we use this to stre the previous entry velocity, start at 0 + float braking_velocity = 0; // we use this to store the previous entry velocity, start at 0 bool optimal = false; // we use the optimal flag (as the opposite of plannable) to carry plan-ability backward. // We test for (braking_velocity < bf->exit_velocity) in case of an inversion, and plannable is then violated. @@ -386,8 +382,8 @@ static mpBuf_t* _plan_block(mpBuf_t* bf) braking_velocity = mp_get_target_velocity(bf->exit_velocity, bf->length, bf); if (bf->pv->exit_vmax > braking_velocity) { // remember, exit vmax already is min of - // pv_group->cruise_vmax, cruise_vmax, and - // pv_group->junction_vmax + // pv->cruise_vmax, cruise_vmax, and + // pv->junction_vmax bf->cruise_velocity = braking_velocity; // put this here to avoid a race condition with _exec() bf->hint = PERFECT_DECELERATION; // This is advisory, and may be altered by forward planning @@ -637,8 +633,8 @@ static void _calculate_vmaxes(mpBuf_t* bf, const float axis_length[], const floa } } } - block_time = max3(feed_time, max_time, MIN_BLOCK_TIME); - min_time = max(min_time, MIN_BLOCK_TIME); + block_time = std::max(std::max(feed_time, max_time), MIN_BLOCK_TIME); + min_time = std::max(min_time, MIN_BLOCK_TIME); bf->cruise_vset = bf->length / block_time; // target velocity requested bf->cruise_vmax = bf->cruise_vset; // starting value for cruise vmax bf->absolute_vmax = bf->length / min_time; // absolute velocity limit @@ -697,7 +693,7 @@ static void _calculate_vmaxes(mpBuf_t* bf, const float axis_length[], const floa static void _calculate_junction_vmax(mpBuf_t* bf) { // ++++ RG If we change cruise_vmax, we'll need to recompute junction_vmax, if we do this: - float velocity = min(bf->cruise_vmax, bf->nx->cruise_vmax); // start with our maximum possible velocity + float velocity = std::min(bf->cruise_vmax, bf->nx->cruise_vmax); // start with our maximum possible velocity // uint8_t jerk_axis = AXIS_X; // cmAxes jerk_axis = AXIS_X; @@ -712,7 +708,8 @@ static void _calculate_junction_vmax(mpBuf_t* bf) if (delta > EPSILON) { // formula (4): (See Note 1, above) - velocity = min(velocity, (cm.a[axis].max_junction_accel / delta)); + velocity = std::min(velocity, (cm.a[axis].max_junction_accel / delta)); + // if ((cm.a[axis].max_junction_accel / delta) < velocity) { // velocity = (cm.a[axis].max_junction_accel / delta); // // bf->jerk_axis = axis; From 520bd7de4c9fd3f52ba7c7a87d52c98c53b5d3c6 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Thu, 27 Apr 2017 20:00:27 -0400 Subject: [PATCH 085/193] Adjust Ultimaker settings. --- g2core/settings/settings_Ultimaker_2_Plus.h | 19 ++++++++++--------- 1 file changed, 10 insertions(+), 9 deletions(-) diff --git a/g2core/settings/settings_Ultimaker_2_Plus.h b/g2core/settings/settings_Ultimaker_2_Plus.h index 72808b329..666ff8275 100644 --- a/g2core/settings/settings_Ultimaker_2_Plus.h +++ b/g2core/settings/settings_Ultimaker_2_Plus.h @@ -133,7 +133,7 @@ #define M4_MICROSTEPS 64 #define M4_POLARITY 0 #define M4_POWER_MODE MOTOR_POWER_MODE -#define M4_POWER_LEVEL 0.8 +#define M4_POWER_LEVEL 0.6 // 96 steps/mm at 1/16 microstepping = 33.3333 mm/rev #define M5_MOTOR_MAP AXIS_B @@ -151,8 +151,8 @@ #define X_FEEDRATE_MAX X_VELOCITY_MAX // xfr G1 max feed rate in mm/min #define X_TRAVEL_MIN 0 // xtn minimum travel - used by soft limits and homing #define X_TRAVEL_MAX 230 // xtm travel between switches or crashes -#define X_JERK_MAX 7000 // xjm yes, that's "100 billion" mm/(min^3) -#define X_JERK_HIGH_SPEED 7000 // xjh +#define X_JERK_MAX 8000 // xjm yes, that's "100 billion" mm/(min^3) +#define X_JERK_HIGH_SPEED 8000 // xjh #define X_HOMING_INPUT 1 // xhi input used for homing or 0 to disable #define X_HOMING_DIRECTION 0 // xhd 0=search moves negative, 1= search moves positive #define X_SEARCH_VELOCITY 2500 // xsv move in negative direction @@ -165,8 +165,8 @@ #define Y_FEEDRATE_MAX Y_VELOCITY_MAX #define Y_TRAVEL_MIN 0 #define Y_TRAVEL_MAX 224.5 -#define Y_JERK_MAX 7000 -#define Y_JERK_HIGH_SPEED 7000 +#define Y_JERK_MAX 8000 +#define Y_JERK_HIGH_SPEED 8000 #define Y_HOMING_INPUT 3 #define Y_HOMING_DIRECTION 1 #define Y_SEARCH_VELOCITY 3000 @@ -189,7 +189,8 @@ #define Z_LATCH_BACKOFF 5 #define Z_ZERO_BACKOFF 0 -#define G55_Z_OFFSET 0.3 +#define G55_Z_OFFSET 0.25 // higher number is farther away from the bed + // Rotary values are chosen to make the motor react the same as X for testing /*************************************************************************************** @@ -219,9 +220,9 @@ //#define A_FEEDRATE_MAX 36110.8 // ~15 mm/s //#define A_FEEDRATE_MAX 24073.9 // ~10 mm/s //#define A_FEEDRATE_MAX 12036.95 // ~5 mm/s -//#define A_FEEDRATE_MAX 6018.475 // ~2.5 mm/s +//#define A_FEEDRATE_MAX 6018.475 // ~2.5 mm/s Testing: {afr:6018.475} //#define A_FEEDRATE_MAX 1000.0 // ~0.415 mm/s -#define A_FEEDRATE_MAX 800.0 +#define A_FEEDRATE_MAX 800.0 // WORKS WELL //#define A_FEEDRATE_MAX 500.0 // ~0.2075 mm/s #define A_TRAVEL_MIN 0 #define A_TRAVEL_MAX 10 @@ -388,7 +389,7 @@ #define DO2_MODE IO_ACTIVE_HIGH // unavailable, is the extruder output //Fan1A_PWM -#define DO3_MODE IO_ACTIVE_HIGH +#define DO3_MODE IO_ACTIVE_LOW //Fan1B_PWM #define DO4_MODE IO_ACTIVE_HIGH From 52743a37620a3697aa25e708ceab357d51f80eef Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Thu, 27 Apr 2017 20:25:34 -0400 Subject: [PATCH 086/193] Fixed a few issues with the last commit. --- g2core/controller.cpp | 2 ++ g2core/settings/settings_default.h | 9 +++++++++ g2core/temperature.cpp | 2 -- 3 files changed, 11 insertions(+), 2 deletions(-) diff --git a/g2core/controller.cpp b/g2core/controller.cpp index 1925fb2a6..419c8a534 100644 --- a/g2core/controller.cpp +++ b/g2core/controller.cpp @@ -324,7 +324,9 @@ void _reset_comms_mode() { // reset the communications mode cs.comm_mode = COMM_MODE; js.json_mode = (COMM_MODE < AUTO_MODE) ? COMM_MODE : JSON_MODE; +#if MARLIN_COMPAT_ENABLED == true mst.marlin_flavor = false; +#endif sr.status_report_verbosity = STATUS_REPORT_VERBOSITY; qr.queue_report_verbosity = QUEUE_REPORT_VERBOSITY; } diff --git a/g2core/settings/settings_default.h b/g2core/settings/settings_default.h index dead597e7..1316d84af 100644 --- a/g2core/settings/settings_default.h +++ b/g2core/settings/settings_default.h @@ -937,6 +937,9 @@ #ifndef H1_DEFAULT_D #define H1_DEFAULT_D 400.0 #endif +#ifndef H1_DEFAULT_F +#define H1_DEFAULT_F 0.0 +#endif #ifndef H2_DEFAULT_ENABLE #define H2_DEFAULT_ENABLE false @@ -950,6 +953,9 @@ #ifndef H2_DEFAULT_D #define H2_DEFAULT_D 400.0 #endif +#ifndef H2_DEFAULT_F +#define H2_DEFAULT_F 0.0 +#endif #ifndef H3_DEFAULT_ENABLE #define H3_DEFAULT_ENABLE false @@ -963,6 +969,9 @@ #ifndef H3_DEFAULT_D #define H3_DEFAULT_D 400.0 #endif +#ifndef H3_DEFAULT_F +#define H3_DEFAULT_F 0.0 +#endif // *** DEFAULT COORDINATE SYSTEM OFFSETS *** diff --git a/g2core/temperature.cpp b/g2core/temperature.cpp index 6402e0dae..a218ebfa4 100755 --- a/g2core/temperature.cpp +++ b/g2core/temperature.cpp @@ -52,14 +52,12 @@ #define HAS_TEMPERATURE_SENSOR_3 false #endif #ifndef EXTRUDER_1_OUTPUT_PIN -#warning using default extruder 1 output pin #define EXTRUDER_1_OUTPUT_PIN kOutput1_PinNumber #endif #ifndef EXTRUDER_1_FAN_PIN #define EXTRUDER_1_FAN_PIN kOutput3_PinNumber #endif #ifndef EXTRUDER_2_OUTPUT_PIN -#warning using default extruder 2 output pin #define EXTRUDER_2_OUTPUT_PIN kOutput2_PinNumber #endif #ifndef BED_OUTPUT_PIN From c955b5608a709c7d7d0df78152ba8b0b320342be Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Mon, 1 May 2017 09:31:43 -0500 Subject: [PATCH 087/193] Moving MOTORS back to 5, and the heater outputs to have unique names again. --- g2core/board/gquintic/board_stepper.cpp | 23 ++++++++++--------- g2core/board/gquintic/board_stepper.h | 20 ++++++++-------- g2core/board/gquintic/gquintic-b-pinout.h | 6 ++--- g2core/board/gquintic/hardware.h | 2 +- .../board/gquintic/motate_pin_assignments.h | 9 +++++--- 5 files changed, 32 insertions(+), 28 deletions(-) diff --git a/g2core/board/gquintic/board_stepper.cpp b/g2core/board/gquintic/board_stepper.cpp index 87868f534..b588fb42a 100755 --- a/g2core/board/gquintic/board_stepper.cpp +++ b/g2core/board/gquintic/board_stepper.cpp @@ -29,35 +29,36 @@ #include "board_stepper.h" // These are identical to board_stepper.h, except for the word "extern" and the initialization -Trinamic2130 - motor_1{spiBus, spiCSPinMux.getCS(4)}; +//Trinamic2130 +// motor_1{spiBus, spiCSPinMux.getCS(4)}; Trinamic2130 - motor_2{spiBus, spiCSPinMux.getCS(3)}; + motor_1{spiBus, spiCSPinMux.getCS(3)}; Trinamic2130 - motor_3{spiBus, spiCSPinMux.getCS(2)}; + motor_2{spiBus, spiCSPinMux.getCS(2)}; Trinamic2130 - motor_4{spiBus, spiCSPinMux.getCS(1)}; + motor_3{spiBus, spiCSPinMux.getCS(1)}; Trinamic2130 - motor_5{spiBus, spiCSPinMux.getCS(0)}; + motor_4{spiBus, spiCSPinMux.getCS(0)}; -StepDirHobbyServo motor_6; +StepDirHobbyServo motor_5; -Stepper* Motors[MOTORS] = {&motor_1, &motor_2, &motor_3, &motor_4, &motor_5, &motor_6}; +Stepper* Motors[MOTORS] = {&motor_1, &motor_2, &motor_3, &motor_4, &motor_5}; +//Stepper* Motors[MOTORS] = {&motor_1, &motor_2, &motor_3, &motor_4, &motor_5, &motor_6}; void board_stepper_init() { for (uint8_t motor = 0; motor < MOTORS; motor++) { Motors[motor]->init(); } diff --git a/g2core/board/gquintic/board_stepper.h b/g2core/board/gquintic/board_stepper.h index ec68b9dbf..e8eac9d68 100755 --- a/g2core/board/gquintic/board_stepper.h +++ b/g2core/board/gquintic/board_stepper.h @@ -33,32 +33,32 @@ #include "step_dir_hobbyservo.h" // These are identical to board_stepper.h, except for the word "extern" and the initialization -extern Trinamic2130 - motor_1; +//extern Trinamic2130 +// motor_1; extern Trinamic2130 - motor_2; + motor_1; extern Trinamic2130 - motor_3; + motor_2; extern Trinamic2130 - motor_4; + motor_3; extern Trinamic2130 - motor_5; -extern StepDirHobbyServo motor_6; + motor_4; +extern StepDirHobbyServo motor_5; extern Stepper* Motors[MOTORS]; diff --git a/g2core/board/gquintic/gquintic-b-pinout.h b/g2core/board/gquintic/gquintic-b-pinout.h index 5fab755df..ba8989d33 100755 --- a/g2core/board/gquintic/gquintic-b-pinout.h +++ b/g2core/board/gquintic/gquintic-b-pinout.h @@ -121,11 +121,11 @@ namespace Motate { // _MAKE_MOTATE_PIN(kLED_RGBWPixelPinNumber, 'A', 0); // -_MAKE_MOTATE_PIN(kOutput1_PinNumber, 'A', 1); // TC 0,1 -_MAKE_MOTATE_PIN(kOutput2_PinNumber, 'A', 2); // PWM 0,1 +_MAKE_MOTATE_PIN(kHeaterOutput1_PinNumber, 'A', 1); // TC 0,1 +_MAKE_MOTATE_PIN(kHeaterOutput2_PinNumber, 'A', 2); // PWM 0,1 _MAKE_MOTATE_PIN(kI2C1_SDAPinNumber, 'A', 3); // _MAKE_MOTATE_PIN(kI2C1_SCLPinNumber, 'A', 4); // -_MAKE_MOTATE_PIN(kOutput11_PinNumber, 'A', 5); // PWM 1,3 +_MAKE_MOTATE_PIN(kHeaterOutput11_PinNumber, 'A', 5); // PWM 1,3 _MAKE_MOTATE_PIN(kExternalClock1_PinNumber, 'A', 6); // CPU_CLK _MAKE_MOTATE_PIN(kOutput7_PinNumber, 'A', 7); // PWM 0,3 //_MAKE_MOTATE_PIN(kServo1_PinNumber, 'A', 7); // diff --git a/g2core/board/gquintic/hardware.h b/g2core/board/gquintic/hardware.h index 7929eb97a..73e46778d 100644 --- a/g2core/board/gquintic/hardware.h +++ b/g2core/board/gquintic/hardware.h @@ -58,7 +58,7 @@ enum hwPlatform { #define AXES 6 // number of axes supported in this version #define HOMING_AXES 4 // number of axes that can be homed (assumes Zxyabc sequence) -#define MOTORS 6 // number of motors on the board - 5 Trinamics + 1 servo +#define MOTORS 5 // number of motors on the board - 5 Trinamics + 1 servo #define COORDS 6 // number of supported coordinate systems (index starts at 1) #define PWMS 2 // number of supported PWM channels #define TOOLS 32 // number of entries in tool table (index starts at 1) diff --git a/g2core/board/gquintic/motate_pin_assignments.h b/g2core/board/gquintic/motate_pin_assignments.h index 30505ad7e..ab6849e66 100755 --- a/g2core/board/gquintic/motate_pin_assignments.h +++ b/g2core/board/gquintic/motate_pin_assignments.h @@ -179,8 +179,10 @@ pin_number kGRBL_CommonEnablePinNumber = -1; // g2ref extensions // These first 5 may replace the Spindle and Coolant pins, above -pin_number kOutput1_PinNumber = 130; // DO_1: Extruder1_PWM -pin_number kOutput2_PinNumber = 131; // DO_2: Extruder2_PWM +pin_number kHeaterOutput1_PinNumber = 130; // DO_1: Extruder1_PWM +pin_number kHeaterOutput2_PinNumber = 131; // DO_2: Extruder2_PWM +pin_number kOutput1_PinNumber = -1; // DO_1: Extruder1_PWM +pin_number kOutput2_PinNumber = -1; // DO_2: Extruder2_PWM pin_number kOutput3_PinNumber = 132; // DO_3: Fan1A_PWM pin_number kOutput4_PinNumber = 133; // DO_4: Fan1B_PWM pin_number kOutput5_PinNumber = 134; // DO_5: Fan2A_PWM @@ -191,7 +193,8 @@ pin_number kOutput8_PinNumber = 137; // See Coolant Enable pin_number kOutput9_PinNumber = 138; // DO_09: May be resued for Servo1 pin_number kOutput10_PinNumber = 139; // DO_10: May be resued for Servo2 -pin_number kOutput11_PinNumber = 140; // DO_11: Heated Bed FET +pin_number kHeaterOutput11_PinNumber = 140; // DO_11: Heated Bed FET +pin_number kOutput11_PinNumber = -1; // DO_11: Heated Bed FET pin_number kOutput12_PinNumber = 141; // DO_12: Indicator_LED pin_number kOutput13_PinNumber = -1; // 142; pin_number kOutput14_PinNumber = -1; // 143; From 5b820210fd4cc0d95ca350daa2cb79a28127214b Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Mon, 1 May 2017 09:32:41 -0500 Subject: [PATCH 088/193] Added temporary not_maxidraw --- g2core/settings/settings_not_maxidraw.h | 344 ++++++++++++++++++++++++ 1 file changed, 344 insertions(+) create mode 100755 g2core/settings/settings_not_maxidraw.h diff --git a/g2core/settings/settings_not_maxidraw.h b/g2core/settings/settings_not_maxidraw.h new file mode 100755 index 000000000..6a54f9db1 --- /dev/null +++ b/g2core/settings/settings_not_maxidraw.h @@ -0,0 +1,344 @@ +/* + * settings_not_maxidraw_v1.h - settings for the WaterColorBot v2 (http://watercolorbot.com/) + * This file is part of the g2core project + * + * Copyright (c) 2016 Alden S. Hart Jr. + * Copyright (c) 2016 Robert Giseburt + * + * This file ("the software") is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License, version 2 as published by the + * Free Software Foundation. You should have received a copy of the GNU General Public + * License, version 2 along with the software. If not, see . + * + * As a special exception, you may use this file as part of a software library without + * restriction. Specifically, if other files instantiate templates or use macros or + * inline functions from this file, or you compile this file and link it with other + * files to produce an executable, this file does not by itself cause the resulting + * executable to be covered by the GNU General Public License. This exception does not + * however invalidate any other reasons why the executable file might be covered by the + * GNU General Public License. + * + * THE SOFTWARE IS DISTRIBUTED IN THE HOPE THAT IT WILL BE USEFUL, BUT WITHOUT ANY + * WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES + * OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT + * SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF + * OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + */ + +/***********************************************************************/ +/**** Not MaxiDraw v1 Configuration *****************************************/ +/***********************************************************************/ + +#include "hardware.h" + +// ***> NOTE: The init message must be a single line with no CRs or LFs +#define INIT_MESSAGE "Initializing configs to Not MaxiDraw v1 settings" + +#define JUNCTION_INTEGRATION_TIME 2.5 // cornering - usually between 0.5 and 2.0 (higher is faster) +#define CHORDAL_TOLERANCE 0.01 // chordal accuracy for arc drawing (in mm) + +#define SOFT_LIMIT_ENABLE 0 // 0=off, 1=on +#define HARD_LIMIT_ENABLE 1 // 0=off, 1=on +#define SAFETY_INTERLOCK_ENABLE 1 // 0=off, 1=on + +#define SPINDLE_ENABLE_POLARITY 1 // 0=active low, 1=active high +#define SPINDLE_DIR_POLARITY 0 // 0=clockwise is low, 1=clockwise is high +#define SPINDLE_PAUSE_ON_HOLD true +#define SPINDLE_DWELL_TIME 1.0 + +#define COOLANT_MIST_POLARITY 1 // 0=active low, 1=active high +#define COOLANT_FLOOD_POLARITY 1 // 0=active low, 1=active high +#define COOLANT_PAUSE_ON_HOLD false + +// Communications and reporting settings + +#define MARLIN_COMPAT_ENABLED true // enable marlin compatibility mode +#define COMM_MODE JSON_MODE // one of: TEXT_MODE, JSON_MODE +#define XIO_ENABLE_FLOW_CONTROL FLOW_CONTROL_RTS // FLOW_CONTROL_OFF, FLOW_CONTROL_RTS + +#define TEXT_VERBOSITY TV_VERBOSE // one of: TV_SILENT, TV_VERBOSE +#define JSON_VERBOSITY JV_MESSAGES // one of: JV_SILENT, JV_FOOTER, JV_CONFIGS, JV_MESSAGES, JV_LINENUM, JV_VERBOSE +#define QUEUE_REPORT_VERBOSITY QR_OFF // one of: QR_OFF, QR_SINGLE, QR_TRIPLE + +#define STATUS_REPORT_VERBOSITY SR_FILTERED // one of: SR_OFF, SR_FILTERED, SR_VERBOSE +#define STATUS_REPORT_MIN_MS 100 // milliseconds - enforces a viable minimum +#define STATUS_REPORT_INTERVAL_MS 250 // milliseconds - set $SV=0 to disable + +//#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","bcr","feed","vel","unit","coor","dist","admo","frmo","momo","stat" +#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","feed","vel","momo","stat" + +// Alternate SRs +//#define STATUS_REPORT_DEFAULTS "line","vel","mpox","mpoy","mpoz","mpoa","coor","ofsa","ofsx","ofsy","ofsz","dist","unit","stat","homz","homy","homx","momo" +//#define STATUS_REPORT_DEFAULTS "_ts1","_cs1","_es1","_xs1","_fe1","line","posx","posy","posz","vel","stat" +//#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","vel","_cs1","_es1","_xs1","_fe1","_cs2","_es2","_xs2","_fe2" +//#define STATUS_REPORT_DEFAULTS "mpox","mpoy","mpoz","mpoa","ofsx","ofsy","ofsz","ofsa","unit","stat","coor","momo","dist","home","hold","macs","cycs","mots","plan","feed" +//#define STATUS_REPORT_DEFAULTS "line","mpox","mpoy","mpoz","mpoa","ofsx","ofsy","ofsz","ofsa","stat","_cs1","_es1","_fe0","_fe1","_fe2","_fe3" +//#define STATUS_REPORT_DEFAULTS "line","mpox","mpoy","mpoz","stat","_ts2","_ps2","_cs2","_es2","_fe2" +//#define STATUS_REPORT_DEFAULTS "line","mpox","mpoy","mpoz","_cs3","_es3","_fe3","_xs3","_cs2","_es2","_fe2","_xs2","stat" +//#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","feed","vel","unit","coor","dist","frmo","momo","stat","_cs1","_es1","_xs1","_fe1" + +// Gcode startup defaults +#define GCODE_DEFAULT_UNITS MILLIMETERS // MILLIMETERS or INCHES +#define GCODE_DEFAULT_PLANE CANON_PLANE_XY // CANON_PLANE_XY, CANON_PLANE_XZ, or CANON_PLANE_YZ +#define GCODE_DEFAULT_COORD_SYSTEM G54 // G54, G55, G56, G57, G58 or G59 +#define GCODE_DEFAULT_PATH_CONTROL PATH_CONTINUOUS +#define GCODE_DEFAULT_DISTANCE_MODE ABSOLUTE_DISTANCE_MODE + +// *** motor settings ************************************************************************************ + +#define MOTOR_POWER_MODE MOTOR_POWERED_IN_CYCLE // default motor power mode (see cmMotorPowerMode in stepper.h) +#define MOTOR_POWER_TIMEOUT 2.00 // motor power timeout in seconds + +// Not CoreXY like AxiDraw +//#define KINEMATICS KINE_CORE_XY // X and Y MUST use the same settings! + +#if MOTORS == 3 +// gQuadratic +#define X_Y_POWER_LEVEL 0.4 +#define X_Y_MICROSTEPS 32 +#define JERK_MAX 2000 +#endif +#if MOTORS == 6 +// gQuintic +#define X_Y_POWER_LEVEL 0.8 +#define X_Y_MICROSTEPS 64 +#define JERK_MAX 1000 +#endif + +#define M1_MOTOR_MAP AXIS_X // 1ma +#define M1_STEP_ANGLE 1.8 // 1sa +#define M1_TRAVEL_PER_REV 99.9 // 1tr +#define M1_MICROSTEPS X_Y_MICROSTEPS // 1mi 1,2,4,8 +#define M1_POLARITY 0 // 1po 0=normal, 1=reversed +#define M1_POWER_MODE MOTOR_ALWAYS_POWERED // 1pm standard +#define M1_POWER_LEVEL X_Y_POWER_LEVEL // 1pl + +#define M2_MOTOR_MAP AXIS_Y +#define M2_STEP_ANGLE 1.8 +#define M2_TRAVEL_PER_REV 99.9 +#define M2_MICROSTEPS X_Y_MICROSTEPS +#define M2_POLARITY 0 +#define M2_POWER_MODE MOTOR_ALWAYS_POWERED +#define M2_POWER_LEVEL X_Y_POWER_LEVEL + +#define M3_MOTOR_MAP AXIS_Z + // This "stepper" is a hobby servo. Note that all hobby + // servo settings are per full servo range, instead of + // per revolution. +#define M3_STEP_ANGLE 1.8 // hobby servos are simulated with 200 "full steps" +#define M3_TRAVEL_PER_REV 26 // this is actually the full travel of the servo, not + // necessarily covering a revolution +#define M3_MICROSTEPS 32 // the max step resolution for a hobby servo is 1/32 +#define M3_POLARITY 1 +#define M3_POWER_MODE MOTOR_ALWAYS_POWERED +#define M3_POWER_LEVEL 0.50 // this is ignored + +#define M6_MOTOR_MAP AXIS_Z +// This "stepper" is a hobby servo. Note that all hobby +// servo settings are per full servo range, instead of +// per revolution. +#define M6_STEP_ANGLE 1.8 // hobby servos are simulated with 200 "full steps" +#define M6_TRAVEL_PER_REV 26 // this is actually the full travel of the servo, not +// necessarily covering a revolution +#define M6_MICROSTEPS 32 // the max step resolution for a hobby servo is 1/32 +#define M6_POLARITY 1 +#define M6_POWER_MODE MOTOR_ALWAYS_POWERED +#define M6_POWER_LEVEL 0.50 // this is ignored + +// *** axis settings ********************************************************************************** + + +#define X_AXIS_MODE AXIS_STANDARD // xam see canonical_machine.h cmAxisMode for valid values +#define X_VELOCITY_MAX 15000 // xvm G0 max velocity in mm/min +#define X_FEEDRATE_MAX 15000 // xfr G1 max feed rate in mm/min +#define X_TRAVEL_MIN 0 // xtn minimum travel - used by soft limits and homing +#define X_TRAVEL_MAX 400 // xtm maximum travel - used by soft limits and homing +#define X_JERK_MAX JERK_MAX // xjm +#define X_JERK_HIGH_SPEED X_JERK_MAX // xjh +#define X_HOMING_INPUT 1 // xhi input used for homing or 0 to disable +#define X_HOMING_DIRECTION 0 // xhd 0=search moves negative, 1= search moves positive +#define X_SEARCH_VELOCITY 1000 // xsv move in negative direction +#define X_LATCH_VELOCITY 100 // xlv mm/min +#define X_LATCH_BACKOFF 10 // xlb mm +#define X_ZERO_BACKOFF 2 // xzb mm + +#define Y_AXIS_MODE AXIS_STANDARD +#define Y_VELOCITY_MAX 15000 +#define Y_FEEDRATE_MAX 15000 +#define Y_TRAVEL_MIN 0 +#define Y_TRAVEL_MAX 175 +#define Y_JERK_MAX JERK_MAX +#define Y_JERK_HIGH_SPEED Y_JERK_MAX +#define Y_HOMING_INPUT 3 +#define Y_HOMING_DIRECTION 0 +#define Y_SEARCH_VELOCITY 1000 +#define Y_LATCH_VELOCITY 100 +#define Y_LATCH_BACKOFF 10 +#define Y_ZERO_BACKOFF 2 + +#define Z_AXIS_MODE AXIS_STANDARD +#define Z_VELOCITY_MAX 10000 +#define Z_FEEDRATE_MAX Z_VELOCITY_MAX +#define Z_TRAVEL_MIN 0 +#define Z_TRAVEL_MAX 75 +#define Z_JERK_MAX 1000 +#define Z_JERK_HIGH_SPEED Z_JERK_MAX +#define Z_HOMING_INPUT 6 +#define Z_HOMING_DIRECTION 1 +#define Z_SEARCH_VELOCITY 600 +#define Z_LATCH_VELOCITY 100 +#define Z_LATCH_BACKOFF 10 +#define Z_ZERO_BACKOFF 2 + +//*** Input / output settings *** +/* + IO_MODE_DISABLED + IO_ACTIVE_LOW aka NORMALLY_OPEN + IO_ACTIVE_HIGH aka NORMALLY_CLOSED + + INPUT_ACTION_NONE + INPUT_ACTION_STOP + INPUT_ACTION_FAST_STOP + INPUT_ACTION_HALT + INPUT_ACTION_RESET + + INPUT_FUNCTION_NONE + INPUT_FUNCTION_LIMIT + INPUT_FUNCTION_INTERLOCK + INPUT_FUNCTION_SHUTDOWN + INPUT_FUNCTION_PANIC +*/ +// Inputs are defined for the g2ref(a) board +// Xmn (board label) +#define DI1_MODE IO_ACTIVE_HIGH +#define DI1_ACTION INPUT_ACTION_NONE +#define DI1_FUNCTION INPUT_FUNCTION_NONE + +// Xmax +#define DI2_MODE IO_MODE_DISABLED +#define DI2_ACTION INPUT_ACTION_NONE +#define DI2_FUNCTION INPUT_FUNCTION_NONE + +// Ymin +#define DI3_MODE IO_MODE_DISABLED +#define DI3_ACTION INPUT_ACTION_NONE +#define DI3_FUNCTION INPUT_FUNCTION_NONE + +// Ymax +#define DI4_MODE IO_ACTIVE_HIGH +#define DI4_ACTION INPUT_ACTION_NONE +#define DI4_FUNCTION INPUT_FUNCTION_NONE + +// Zmin +#define DI5_MODE IO_ACTIVE_LOW // Z probe +#define DI5_ACTION INPUT_ACTION_NONE +#define DI5_FUNCTION INPUT_FUNCTION_NONE + +// Zmax +#define DI6_MODE IO_MODE_DISABLED +#define DI6_ACTION INPUT_ACTION_STOP +#define DI6_FUNCTION INPUT_FUNCTION_NONE + +// Shutdown (Amin on v9 board) +#define DI7_MODE IO_MODE_DISABLED +#define DI7_ACTION INPUT_ACTION_NONE +#define DI7_FUNCTION INPUT_FUNCTION_NONE + +// High Voltage Z Probe In (Amax on v9 board) +#define DI8_MODE IO_ACTIVE_LOW +#define DI8_ACTION INPUT_ACTION_NONE +#define DI8_FUNCTION INPUT_FUNCTION_NONE + +// Hardware interlock input +#define DI9_MODE IO_MODE_DISABLED +#define DI9_ACTION INPUT_ACTION_NONE +#define DI9_FUNCTION INPUT_FUNCTION_NONE + +//Extruder1_PWM +#define DO1_MODE IO_ACTIVE_HIGH + +//Extruder2_PWM +#define DO2_MODE IO_ACTIVE_HIGH + +//Fan1A_PWM +#define DO3_MODE IO_ACTIVE_HIGH + +//Fan1B_PWM +#define DO4_MODE IO_ACTIVE_HIGH + +#define DO5_MODE IO_ACTIVE_HIGH +#define DO6_MODE IO_ACTIVE_HIGH +#define DO7_MODE IO_ACTIVE_HIGH +#define DO8_MODE IO_ACTIVE_HIGH + +//SAFEin (Output) signal +#define DO9_MODE IO_ACTIVE_HIGH + +#define DO10_MODE IO_ACTIVE_HIGH + +//Header Bed FET +#define DO11_MODE IO_ACTIVE_HIGH + +//Indicator_LED +#define DO12_MODE IO_ACTIVE_HIGH + +#define DO13_MODE IO_ACTIVE_HIGH + + +// *** PWM SPINDLE CONTROL *** + +#define P1_PWM_FREQUENCY 100 // in Hz +#define P1_CW_SPEED_LO 1000 // in RPM (arbitrary units) +#define P1_CW_SPEED_HI 2000 +#define P1_CW_PHASE_LO 0.125 // phase [0..1] +#define P1_CW_PHASE_HI 0.2 +#define P1_CCW_SPEED_LO 1000 +#define P1_CCW_SPEED_HI 2000 +#define P1_CCW_PHASE_LO 0.125 +#define P1_CCW_PHASE_HI 0.2 +#define P1_PWM_PHASE_OFF 0.1 + +// *** DEFAULT COORDINATE SYSTEM OFFSETS *** + +#define G54_X_OFFSET 0 // G54 is traditionally set to all zeros +#define G54_Y_OFFSET 0 +#define G54_Z_OFFSET 0 +#define G54_A_OFFSET 0 +#define G54_B_OFFSET 0 +#define G54_C_OFFSET 0 + +#define G55_X_OFFSET (X_TRAVEL_MAX/2) // set to middle of table +#define G55_Y_OFFSET (Y_TRAVEL_MAX/2) +#define G55_Z_OFFSET 0 +#define G55_A_OFFSET 0 +#define G55_B_OFFSET 0 +#define G55_C_OFFSET 0 + +#define G56_X_OFFSET 0 +#define G56_Y_OFFSET 0 +#define G56_Z_OFFSET 0 +#define G56_A_OFFSET 0 +#define G56_B_OFFSET 0 +#define G56_C_OFFSET 0 + +#define G57_X_OFFSET 0 +#define G57_Y_OFFSET 0 +#define G57_Z_OFFSET 0 +#define G57_A_OFFSET 0 +#define G57_B_OFFSET 0 +#define G57_C_OFFSET 0 + +#define G58_X_OFFSET 0 +#define G58_Y_OFFSET 0 +#define G58_Z_OFFSET 0 +#define G58_A_OFFSET 0 +#define G58_B_OFFSET 0 +#define G58_C_OFFSET 0 + +#define G59_X_OFFSET 0 +#define G59_Y_OFFSET 0 +#define G59_Z_OFFSET 0 +#define G59_A_OFFSET 0 +#define G59_B_OFFSET 0 +#define G59_C_OFFSET 0 From ef72a8449ebe3b5bd79eb90c5d12bcdd85425b81 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Mon, 1 May 2017 20:14:52 -0500 Subject: [PATCH 089/193] Fix missing frequency in GPIO settings. --- g2core/gpio.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/g2core/gpio.cpp b/g2core/gpio.cpp index 4c93e849f..14fb7cdbb 100644 --- a/g2core/gpio.cpp +++ b/g2core/gpio.cpp @@ -271,7 +271,7 @@ static PWMLikeOutputPin output_7_pin {(DO7_MODE == IO_ACTIV #if OUTPUT8_PWM == 1 static PWMOutputPin output_8_pin {(DO8_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; #else -static PWMLikeOutputPin output_8_pin {(DO8_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow}; +static PWMLikeOutputPin output_8_pin {(DO8_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; #endif #if OUTPUT9_PWM == 1 static PWMOutputPin output_9_pin {(DO9_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; From 3e26890813c36e3c0c235256fd32c3db1e111892 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Mon, 1 May 2017 20:21:59 -0500 Subject: [PATCH 090/193] Rebuilding DDA dubstep accumulator to not incorporate time. Other load time improvements. --- g2core/stepper.cpp | 54 ++++++++++++++++++++++++++++++---------------- g2core/stepper.h | 47 +++++++++++++++++++++++++++++++--------- 2 files changed, 72 insertions(+), 29 deletions(-) diff --git a/g2core/stepper.cpp b/g2core/stepper.cpp index bafd9bd30..cd6b607db 100644 --- a/g2core/stepper.cpp +++ b/g2core/stepper.cpp @@ -56,13 +56,13 @@ void stepper_debug(const char (&str)[len]) { ; }; /**** Allocate structures ****/ -stConfig_t st_cfg; -stPrepSingleton_t st_pre; +stConfig_t st_cfg HOT_DATA; +stPrepSingleton_t st_pre HOT_DATA; static stRunSingleton_t st_run HOT_DATA; /**** Static functions ****/ -static void _load_move(void); +static void _load_move(void) HOT_FUNC; // handy macro //#define _f_to_period(f) (uint16_t)((float)F_CPU / (float)f) @@ -138,6 +138,8 @@ void stepper_init() } board_stepper_init(); stepper_reset(); // reset steppers to known state + + dda_timer.start(); // start the DDA timer if not already running } /* @@ -302,39 +304,39 @@ void dda_timer_type::interrupt() // process DDAs for each motor if ((st_run.mot[MOTOR_1].substep_accumulator += st_run.mot[MOTOR_1].substep_increment) > 0) { motor_1.stepStart(); // turn step bit on - st_run.mot[MOTOR_1].substep_accumulator -= st_run.dda_ticks_X_substeps; + st_run.mot[MOTOR_1].substep_accumulator -= DDA_SUBSTEPS; //st_run.dda_ticks_X_substeps; INCREMENT_ENCODER(MOTOR_1); } if ((st_run.mot[MOTOR_2].substep_accumulator += st_run.mot[MOTOR_2].substep_increment) > 0) { motor_2.stepStart(); // turn step bit on - st_run.mot[MOTOR_2].substep_accumulator -= st_run.dda_ticks_X_substeps; + st_run.mot[MOTOR_2].substep_accumulator -= DDA_SUBSTEPS; //st_run.dda_ticks_X_substeps; INCREMENT_ENCODER(MOTOR_2); } #if MOTORS > 2 if ((st_run.mot[MOTOR_3].substep_accumulator += st_run.mot[MOTOR_3].substep_increment) > 0) { motor_3.stepStart(); // turn step bit on - st_run.mot[MOTOR_3].substep_accumulator -= st_run.dda_ticks_X_substeps; + st_run.mot[MOTOR_3].substep_accumulator -= DDA_SUBSTEPS; //st_run.dda_ticks_X_substeps; INCREMENT_ENCODER(MOTOR_3); } #endif #if MOTORS > 3 if ((st_run.mot[MOTOR_4].substep_accumulator += st_run.mot[MOTOR_4].substep_increment) > 0) { motor_4.stepStart(); // turn step bit on - st_run.mot[MOTOR_4].substep_accumulator -= st_run.dda_ticks_X_substeps; + st_run.mot[MOTOR_4].substep_accumulator -= DDA_SUBSTEPS; //st_run.dda_ticks_X_substeps; INCREMENT_ENCODER(MOTOR_4); } #endif #if MOTORS > 4 if ((st_run.mot[MOTOR_5].substep_accumulator += st_run.mot[MOTOR_5].substep_increment) > 0) { motor_5.stepStart(); // turn step bit on - st_run.mot[MOTOR_5].substep_accumulator -= st_run.dda_ticks_X_substeps; + st_run.mot[MOTOR_5].substep_accumulator -= DDA_SUBSTEPS; //st_run.dda_ticks_X_substeps; INCREMENT_ENCODER(MOTOR_5); } #endif #if MOTORS > 5 if ((st_run.mot[MOTOR_6].substep_accumulator += st_run.mot[MOTOR_6].substep_increment) > 0) { motor_6.stepStart(); // turn step bit on - st_run.mot[MOTOR_6].substep_accumulator -= st_run.dda_ticks_X_substeps; + st_run.mot[MOTOR_6].substep_accumulator -= DDA_SUBSTEPS; //st_run.dda_ticks_X_substeps; INCREMENT_ENCODER(MOTOR_6); } #endif @@ -489,7 +491,7 @@ static void _load_move() //**** setup the new segment **** // st_run.dda_ticks_downcount is setup right before turning on the interrupt, since we don't turn it off - st_run.dda_ticks_X_substeps = st_pre.dda_ticks_X_substeps; +// st_run.dda_ticks_X_substeps = st_pre.dda_ticks_X_substeps; // INLINED VERSION: 4.3us //**** MOTOR_1 LOAD **** @@ -505,10 +507,12 @@ static void _load_move() // segments it may have been inactive in between. // Apply accumulator correction if the time base has changed since previous segment +#if 0 if (st_pre.mot[MOTOR_1].accumulator_correction_flag == true) { st_pre.mot[MOTOR_1].accumulator_correction_flag = false; st_run.mot[MOTOR_1].substep_accumulator *= st_pre.mot[MOTOR_1].accumulator_correction; } +#endif // Detect direction change and if so: // Set the direction bit in hardware. @@ -516,7 +520,8 @@ static void _load_move() if (st_pre.mot[MOTOR_1].direction != st_pre.mot[MOTOR_1].prev_direction) { st_pre.mot[MOTOR_1].prev_direction = st_pre.mot[MOTOR_1].direction; - st_run.mot[MOTOR_1].substep_accumulator = -(st_run.dda_ticks_X_substeps + st_run.mot[MOTOR_1].substep_accumulator); +// st_run.mot[MOTOR_1].substep_accumulator = -(st_run.dda_ticks_X_substeps + st_run.mot[MOTOR_1].substep_accumulator); + st_run.mot[MOTOR_1].substep_accumulator = -(DDA_SUBSTEPS + st_run.mot[MOTOR_1].substep_accumulator); // invert the accumulator for the direction change motor_1.setDirection(st_pre.mot[MOTOR_1].direction); } @@ -532,13 +537,15 @@ static void _load_move() #if (MOTORS >= 2) if ((st_run.mot[MOTOR_2].substep_increment = st_pre.mot[MOTOR_2].substep_increment) != 0) { +#if 0 if (st_pre.mot[MOTOR_2].accumulator_correction_flag == true) { st_pre.mot[MOTOR_2].accumulator_correction_flag = false; st_run.mot[MOTOR_2].substep_accumulator *= st_pre.mot[MOTOR_2].accumulator_correction; } +#endif if (st_pre.mot[MOTOR_2].direction != st_pre.mot[MOTOR_2].prev_direction) { st_pre.mot[MOTOR_2].prev_direction = st_pre.mot[MOTOR_2].direction; - st_run.mot[MOTOR_2].substep_accumulator = -(st_run.dda_ticks_X_substeps + st_run.mot[MOTOR_2].substep_accumulator); + st_run.mot[MOTOR_2].substep_accumulator = -(DDA_SUBSTEPS + st_run.mot[MOTOR_2].substep_accumulator); motor_2.setDirection(st_pre.mot[MOTOR_2].direction); } motor_2.enable(); @@ -550,13 +557,15 @@ static void _load_move() #endif #if (MOTORS >= 3) if ((st_run.mot[MOTOR_3].substep_increment = st_pre.mot[MOTOR_3].substep_increment) != 0) { +#if 0 if (st_pre.mot[MOTOR_3].accumulator_correction_flag == true) { st_pre.mot[MOTOR_3].accumulator_correction_flag = false; st_run.mot[MOTOR_3].substep_accumulator *= st_pre.mot[MOTOR_3].accumulator_correction; } +#endif if (st_pre.mot[MOTOR_3].direction != st_pre.mot[MOTOR_3].prev_direction) { st_pre.mot[MOTOR_3].prev_direction = st_pre.mot[MOTOR_3].direction; - st_run.mot[MOTOR_3].substep_accumulator = -(st_run.dda_ticks_X_substeps + st_run.mot[MOTOR_3].substep_accumulator); + st_run.mot[MOTOR_3].substep_accumulator = -(DDA_SUBSTEPS + st_run.mot[MOTOR_3].substep_accumulator); motor_3.setDirection(st_pre.mot[MOTOR_3].direction); } motor_3.enable(); @@ -568,13 +577,15 @@ static void _load_move() #endif #if (MOTORS >= 4) if ((st_run.mot[MOTOR_4].substep_increment = st_pre.mot[MOTOR_4].substep_increment) != 0) { +#if 0 if (st_pre.mot[MOTOR_4].accumulator_correction_flag == true) { st_pre.mot[MOTOR_4].accumulator_correction_flag = false; st_run.mot[MOTOR_4].substep_accumulator *= st_pre.mot[MOTOR_4].accumulator_correction; } +#endif if (st_pre.mot[MOTOR_4].direction != st_pre.mot[MOTOR_4].prev_direction) { st_pre.mot[MOTOR_4].prev_direction = st_pre.mot[MOTOR_4].direction; - st_run.mot[MOTOR_4].substep_accumulator = -(st_run.dda_ticks_X_substeps + st_run.mot[MOTOR_4].substep_accumulator); + st_run.mot[MOTOR_4].substep_accumulator = -(DDA_SUBSTEPS + st_run.mot[MOTOR_4].substep_accumulator); motor_4.setDirection(st_pre.mot[MOTOR_4].direction); } motor_4.enable(); @@ -586,13 +597,15 @@ static void _load_move() #endif #if (MOTORS >= 5) if ((st_run.mot[MOTOR_5].substep_increment = st_pre.mot[MOTOR_5].substep_increment) != 0) { +#if 0 if (st_pre.mot[MOTOR_5].accumulator_correction_flag == true) { st_pre.mot[MOTOR_5].accumulator_correction_flag = false; st_run.mot[MOTOR_5].substep_accumulator *= st_pre.mot[MOTOR_5].accumulator_correction; } +#endif if (st_pre.mot[MOTOR_5].direction != st_pre.mot[MOTOR_5].prev_direction) { st_pre.mot[MOTOR_5].prev_direction = st_pre.mot[MOTOR_5].direction; - st_run.mot[MOTOR_5].substep_accumulator = -(st_run.dda_ticks_X_substeps + st_run.mot[MOTOR_5].substep_accumulator); + st_run.mot[MOTOR_5].substep_accumulator = -(DDA_SUBSTEPS + st_run.mot[MOTOR_5].substep_accumulator); motor_5.setDirection(st_pre.mot[MOTOR_5].direction); } motor_5.enable(); @@ -604,13 +617,15 @@ static void _load_move() #endif #if (MOTORS >= 6) if ((st_run.mot[MOTOR_6].substep_increment = st_pre.mot[MOTOR_6].substep_increment) != 0) { +#if 0 if (st_pre.mot[MOTOR_6].accumulator_correction_flag == true) { st_pre.mot[MOTOR_6].accumulator_correction_flag = false; st_run.mot[MOTOR_6].substep_accumulator *= st_pre.mot[MOTOR_6].accumulator_correction; } +#endif if (st_pre.mot[MOTOR_6].direction != st_pre.mot[MOTOR_6].prev_direction) { st_pre.mot[MOTOR_6].prev_direction = st_pre.mot[MOTOR_6].direction; - st_run.mot[MOTOR_6].substep_accumulator = -(st_run.dda_ticks_X_substeps + st_run.mot[MOTOR_6].substep_accumulator); + st_run.mot[MOTOR_6].substep_accumulator = -(DDA_SUBSTEPS + st_run.mot[MOTOR_6].substep_accumulator); motor_6.setDirection(st_pre.mot[MOTOR_6].direction); } motor_6.enable(); @@ -624,7 +639,6 @@ static void _load_move() //**** do this last **** st_run.dda_ticks_downcount = st_pre.dda_ticks; - dda_timer.start(); // start the DDA timer if not already running // handle dwells and commands } else if (st_pre.block_type == BLOCK_TYPE_DWELL) { @@ -688,7 +702,7 @@ stat_t st_prep_line(float travel_steps[], float following_error[], float segment //st_pre.dda_period = _f_to_period(FREQUENCY_DDA); // FYI: this is a constant st_pre.dda_ticks = (int32_t)(segment_time * 60 * FREQUENCY_DDA);// NB: converts minutes to seconds - st_pre.dda_ticks_X_substeps = st_pre.dda_ticks * DDA_SUBSTEPS; + //st_pre.dda_ticks_X_substeps = st_pre.dda_ticks * DDA_SUBSTEPS; // setup motor parameters @@ -712,6 +726,7 @@ stat_t st_prep_line(float travel_steps[], float following_error[], float segment st_pre.mot[motor].step_sign = -1; } +#if 0 // Detect segment time changes and setup the accumulator correction factor and flag. // Putting this here computes the correct factor even if the motor was dormant for some // number of previous moves. Correction is computed based on the last segment time actually used. @@ -723,6 +738,7 @@ stat_t st_prep_line(float travel_steps[], float following_error[], float segment } st_pre.mot[motor].prev_segment_time = segment_time; } +#endif // 'Nudge' correction strategy. Inject a single, scaled correction value then hold off // NOTE: This clause can be commented out to test for numerical accuracy and accumulating errors @@ -746,7 +762,7 @@ stat_t st_prep_line(float travel_steps[], float following_error[], float segment // Rounding is performed to eliminate a negative bias in the uint32 conversion // that results in long-term negative drift. (fabs/round order doesn't matter) - st_pre.mot[motor].substep_increment = round(fabs(travel_steps[motor] * DDA_SUBSTEPS)); + st_pre.mot[motor].substep_increment = round(fabs(travel_steps[motor] * DDA_SUBSTEPS) / st_pre.dda_ticks); } st_pre.block_type = BLOCK_TYPE_ALINE; st_pre.buffer_state = PREP_BUFFER_OWNED_BY_LOADER; // signal that prep buffer is ready diff --git a/g2core/stepper.h b/g2core/stepper.h index 28ae10ad7..0109568d6 100644 --- a/g2core/stepper.h +++ b/g2core/stepper.h @@ -254,6 +254,8 @@ #ifndef STEPPER_H_ONCE #define STEPPER_H_ONCE +#include "MotateUtilities.h" // for HOT_DATA and HOT_FUNC + #include "planner.h" // planner.h must precede stepper.h for moveType typedef /********************************* @@ -309,7 +311,9 @@ typedef enum { * The ARM is roughly the same as the DDA clock rate is 4x higher but the segment time is ~1/5 * Decreasing the nominal segment time increases the number precision. */ -#define DDA_SUBSTEPS ((MAX_LONG * 0.90) / (FREQUENCY_DDA * (NOM_SEGMENT_TIME * 60))) +//#define DDA_SUBSTEPS ((MAX_LONG * 0.90) / (FREQUENCY_DDA * (NOM_SEGMENT_TIME * 60))) +//#define DDA_SUBSTEPS (MAX_LONG * 0.90) +#define DDA_SUBSTEPS (1932735283L) /* Step correction settings * @@ -375,7 +379,7 @@ typedef struct stRunSingleton { // Stepper static values and axis pa magic_t magic_start; // magic number to test memory integrity uint32_t dda_ticks_downcount; // dda tick down-counter (unscaled) uint32_t dwell_ticks_downcount; // dwell tick down-counter (unscaled) - uint32_t dda_ticks_X_substeps; // ticks multiplied by scaling factor + uint32_t dda_steps_tick_X_substeps; // DDA substps per tick scaled by substep factor stRunMotor_t mot[MOTORS]; // runtime motor structures magic_t magic_end; } stRunSingleton_t; @@ -410,7 +414,7 @@ typedef struct stPrepSingleton { uint32_t dda_ticks; // DDA ticks for the move uint32_t dwell_ticks; // dwell ticks remaining - uint32_t dda_ticks_X_substeps; // DDA ticks scaled by substep factor +// uint32_t dda_ticks_X_substeps; // DDA ticks scaled by substep factor stPrepMotor_t mot[MOTORS]; // prep time motor structs magic_t magic_end; } stPrepSingleton_t; @@ -426,6 +430,7 @@ struct Stepper { uint32_t _motor_disable_timeout_ms; // the number of ms that the timeout is reset to stPowerState _power_state; // state machine for managing motor power stPowerMode _power_mode; // See stPowerMode for values + bool _was_enabled; // store if we enabled a motor to handle timout setup outside of load /* stepper default values */ @@ -473,23 +478,40 @@ struct Stepper { // }; // turn on motor in all cases unless it's disabled - // NOTE: in the future the default assigned timeout will be the motor's default value - void enable(float timeout = st_cfg.motor_power_timeout) + // this version is called from the loader, and explicitly does NOT have floating point computations + // HOT - called from the DDA interrupt + void enable() HOT_FUNC + { + if (_power_mode == MOTOR_DISABLED) { + return; + } + this->_enableImpl(); + _power_state = MOTOR_RUNNING; + + _was_enabled = true; // flag to handle it in the periodic call + }; + + // turn on motor in all cases unless it's disabled + // this version has the timeout computed here, as provided + void enable(float timeout) HOT_FUNC { if (_power_mode == MOTOR_DISABLED) { return; } this->_enableImpl(); _power_state = MOTOR_RUNNING; + _was_enabled = false; // we're doing it here, so don't do it elsewhere if ((uint8_t)timeout == 0) { timeout = st_cfg.motor_power_timeout; } _motor_disable_timeout_ms = timeout * 1000.0; + }; // turn off motor in all cases unless it's permanently enabled - void disable() + // HOT - called from the DDA interrupt + void disable() HOT_FUNC { if (this->getPowerMode() == MOTOR_ALWAYS_POWERED) { return; @@ -500,7 +522,8 @@ struct Stepper { }; // turn off motor is only powered when moving - void motionStopped() { + // HOT - called from the DDA interrupt + void motionStopped() HOT_FUNC { if (_power_mode == MOTOR_POWERED_IN_CYCLE) { this->enable(); _power_state = MOTOR_POWER_TIMEOUT_START; @@ -513,6 +536,10 @@ struct Stepper { virtual void periodicCheck(bool have_actually_stopped) // can be overridden { + if (_was_enabled) { + _motor_disable_timeout_ms = st_cfg.motor_power_timeout * 1000.0; + } + if (have_actually_stopped && _power_state == MOTOR_RUNNING) { _power_state = MOTOR_POWER_TIMEOUT_START; // ...start motor power timeouts } @@ -541,9 +568,9 @@ struct Stepper { virtual bool canStep() { return true; }; virtual void _enableImpl() { /* must override */ }; virtual void _disableImpl() { /* must override */ }; - virtual void stepStart() { /* must override */ }; - virtual void stepEnd() { /* must override */ }; - virtual void setDirection(uint8_t new_direction) { /* must override */ }; + virtual void stepStart() HOT_FUNC { /* must override */ }; // HOT - called from the DDA interrupt + virtual void stepEnd() HOT_FUNC { /* must override */ }; // HOT - called from the DDA interrupt + virtual void setDirection(uint8_t new_direction) HOT_FUNC { /* must override */ }; // HOT - called from the DDA interrupt virtual void setMicrosteps(const uint8_t microsteps) { /* must override */ }; virtual void setPowerLevel(float new_pl) { /* must override */ }; }; From 08facb800c9e86cd835271735d547210f70573bb Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Mon, 1 May 2017 20:22:42 -0500 Subject: [PATCH 091/193] Adjusting Ultimaker2+ settings (TESTING) --- g2core/settings/settings_Ultimaker_2_Plus.h | 15 +++++++-------- 1 file changed, 7 insertions(+), 8 deletions(-) diff --git a/g2core/settings/settings_Ultimaker_2_Plus.h b/g2core/settings/settings_Ultimaker_2_Plus.h index 666ff8275..a66861f18 100644 --- a/g2core/settings/settings_Ultimaker_2_Plus.h +++ b/g2core/settings/settings_Ultimaker_2_Plus.h @@ -39,7 +39,7 @@ //**** GLOBAL / GENERAL SETTINGS ****************************************************** -#define JUNCTION_INTEGRATION_TIME 0.8 // cornering - between 0.10 and 2.00 (higher is faster) +#define JUNCTION_INTEGRATION_TIME 1.0 // cornering - between 0.10 and 2.00 (higher is faster) #define CHORDAL_TOLERANCE 0.01 // chordal accuracy for arc drawing (in mm) #define SOFT_LIMIT_ENABLE 0 // 0=off, 1=on @@ -83,7 +83,7 @@ //#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","he1t","he1st","he1at","he1op","pid1p","pid1i","pid1d","feed","vel","unit","path","stat" // Defaults for thermistor tuning -#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","he1t","he1st","he1at","he1tr","he1tv","he1op","he2t","he2st","he2at","he2tr","he2tv","he2op","he3t","he3st","he3at","he3tr","he3tv","he3op","feed","vel","unit","path","stat" +#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","he1t","he1st","he1at","he1tr","he1tv","he1op","he2t","he2st","he2at","he2tr","he2tv","he2op","he3t","he3st","he3at","he3tr","he3tv","he3op","feed","vel","unit","path","stat","_fe1","_fe2","_fe3","_fe4","_xs1","_xs2","_xs3","_xs4" //{sr:{"line":t,"posx":t,"posy":t,"posz":t,"posa":t,"he1t":t,"he1st":t,"he1at":t,"he1tr":t,"he1tv":t,"he1op":t,"he3t":t,"he3st":t,"he3at":t,"he3tr":t,"he3tv":t,"he3op":t,"feed":t,"vel":t,"unit":t,"path":t,"stat":t}} // Gcode startup defaults #define GCODE_DEFAULT_UNITS MILLIMETERS // MILLIMETERS or INCHES @@ -103,7 +103,7 @@ #define M1_STEP_ANGLE 1.8 // 1sa // Marlin says 80 steps/unit, and 16 microsteps, with a 200-step/rev motor #define M1_TRAVEL_PER_REV 40 // 1tr -#define M1_MICROSTEPS 128 // 1mi 1,2,4,8,16,32 +#define M1_MICROSTEPS 64 // 1mi 1,2,4,8,16,32 #define M1_POLARITY 0 // 1po 0=normal, 1=reversed #define M1_POWER_MODE MOTOR_POWERED_IN_CYCLE // 1pm standard #define M1_POWER_LEVEL 0.5 // 1pl @@ -113,7 +113,7 @@ #define M2_STEP_ANGLE 1.8 // Marlin says 80 steps/unit, and 16 microsteps, with a 200-step/rev motor #define M2_TRAVEL_PER_REV 40 -#define M2_MICROSTEPS 128 +#define M2_MICROSTEPS 64 #define M2_POLARITY 1 #define M2_POWER_MODE MOTOR_POWERED_IN_CYCLE #define M2_POWER_LEVEL 0.5 @@ -135,11 +135,10 @@ #define M4_POWER_MODE MOTOR_POWER_MODE #define M4_POWER_LEVEL 0.6 -// 96 steps/mm at 1/16 microstepping = 33.3333 mm/rev #define M5_MOTOR_MAP AXIS_B #define M5_STEP_ANGLE 1.8 #define M5_TRAVEL_PER_REV 360 // degrees moved per motor rev -#define M5_MICROSTEPS 128 +#define M5_MICROSTEPS 64 #define M5_POLARITY 0 #define M5_POWER_MODE MOTOR_POWER_MODE #define M5_POWER_LEVEL 0.8 @@ -220,9 +219,9 @@ //#define A_FEEDRATE_MAX 36110.8 // ~15 mm/s //#define A_FEEDRATE_MAX 24073.9 // ~10 mm/s //#define A_FEEDRATE_MAX 12036.95 // ~5 mm/s -//#define A_FEEDRATE_MAX 6018.475 // ~2.5 mm/s Testing: {afr:6018.475} +#define A_FEEDRATE_MAX 6018.475 // ~2.5 mm/s Testing: {afr:6018.475} //#define A_FEEDRATE_MAX 1000.0 // ~0.415 mm/s -#define A_FEEDRATE_MAX 800.0 // WORKS WELL +//#define A_FEEDRATE_MAX 800.0 // WORKS WELL //#define A_FEEDRATE_MAX 500.0 // ~0.2075 mm/s #define A_TRAVEL_MIN 0 #define A_TRAVEL_MAX 10 From 8e06da58b02e53d61a87da9ce441e112923da01c Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Mon, 1 May 2017 20:23:05 -0500 Subject: [PATCH 092/193] EXPERIMENT: Adding tiny junction compensation --- g2core/plan_line.cpp | 20 ++++++++++++++++++++ g2core/planner.h | 5 +++++ 2 files changed, 25 insertions(+) diff --git a/g2core/plan_line.cpp b/g2core/plan_line.cpp index 400ea9eed..0d6f0b844 100644 --- a/g2core/plan_line.cpp +++ b/g2core/plan_line.cpp @@ -697,11 +697,31 @@ static void _calculate_junction_vmax(mpBuf_t* bf) // uint8_t jerk_axis = AXIS_X; // cmAxes jerk_axis = AXIS_X; + bool using_junction_unit = false; + float junction_length_since = bf->junction_length_since + bf->length; + if (junction_length_since < 5.0) { + // push the length_since forward, and copy the junction_unit + bf->nx->junction_length_since = junction_length_since; + using_junction_unit = true; + } else { + bf->nx->junction_length_since = bf->length; + } for (uint8_t axis = 0; axis < AXES; axis++) { if (bf->axis_flags[axis] || bf->nx->axis_flags[axis]) { // skip axes with no movement float delta = fabs(bf->unit[axis] - bf->nx->unit[axis]); // formula (1) + if (using_junction_unit) { + // use the highest delta of the two + delta = std::max(delta, fabs(bf->junction_unit[axis] - bf->nx->unit[axis])); + + // push the junction_unit for this axis into the next block + bf->nx->junction_unit[axis] = bf->junction_unit[axis]; + } else { + // push this unit to the next junction_unit + bf->nx->junction_unit[axis] = bf->unit[axis]; + } + // Corner case: If an axis has zero delta, we might have a straight line. // Corner case: An axis doesn't change (and it's not a straight line). // In either case, division-by-zero is bad, m'kay? diff --git a/g2core/planner.h b/g2core/planner.h index cf352e9f3..3c184ad4d 100644 --- a/g2core/planner.h +++ b/g2core/planner.h @@ -328,6 +328,9 @@ struct mpBuffer_to_clear { float unit[AXES]; // unit vector for axis scaling & planning bool axis_flags[AXES]; // set true for axes participating in the move & for command parameters + float junction_unit[AXES]; // unit vector delta at the junction for cornering. Needed for groups of small moves. + float junction_length_since; // length total of the moves since the junction_unit was captured. See _calculate_junction_vmax() comments. + bool plannable; // set true when this block can be used for planning float length; // total length of line or helix in mm @@ -379,6 +382,8 @@ struct mpBuffer_to_clear { for (uint8_t i = 0; i< AXES; i++) { unit[i] = 0; + junction_unit[i] = 0; + junction_length_since = 0; axis_flags[i] = 0; } From 5e54658a80ce0cdafc966dc26d0cf2d36fd5d4ad Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Mon, 1 May 2017 20:14:52 -0500 Subject: [PATCH 093/193] Fix missing frequency in GPIO settings. --- g2core/gpio.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/g2core/gpio.cpp b/g2core/gpio.cpp index 4c93e849f..14fb7cdbb 100644 --- a/g2core/gpio.cpp +++ b/g2core/gpio.cpp @@ -271,7 +271,7 @@ static PWMLikeOutputPin output_7_pin {(DO7_MODE == IO_ACTIV #if OUTPUT8_PWM == 1 static PWMOutputPin output_8_pin {(DO8_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; #else -static PWMLikeOutputPin output_8_pin {(DO8_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow}; +static PWMLikeOutputPin output_8_pin {(DO8_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; #endif #if OUTPUT9_PWM == 1 static PWMOutputPin output_9_pin {(DO9_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; From fd95d734332a4ee1d0997c23954f162d472a1a17 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Mon, 1 May 2017 20:26:32 -0500 Subject: [PATCH 094/193] Uncommenting code commented for debugging --- g2core/temperature.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/g2core/temperature.cpp b/g2core/temperature.cpp index a218ebfa4..b983606bf 100755 --- a/g2core/temperature.cpp +++ b/g2core/temperature.cpp @@ -471,7 +471,7 @@ const int32_t fet_pin1_freq = 2000; #if TEMPERATURE_OUTPUT_ON == 1 PWMOutputPin fet_pin1 {kNormal, fet_pin1_freq};// {kPWMPinInverted, fet_pin1_freq}; #else -//PWMOutputPin<-1> fet_pin1;// {kPWMPinInverted}; +PWMOutputPin<-1> fet_pin1;// {kPWMPinInverted}; #endif // DO_2: Extruder2_PWM @@ -479,7 +479,7 @@ const int32_t fet_pin2_freq = 2000; #if TEMPERATURE_OUTPUT_ON == 1 PWMOutputPin fet_pin2 {kNormal, fet_pin2_freq};// {kPWMPinInverted, fet_pin1_freq}; #else -//PWMOutputPin<-1> fet_pin2;// {kPWMPinInverted}; +PWMOutputPin<-1> fet_pin2;// {kPWMPinInverted}; #endif // DO_11: Heated Bed FET @@ -488,7 +488,7 @@ const int32_t fet_pin3_freq = 100; #if TEMPERATURE_OUTPUT_ON == 1 PWMOutputPin fet_pin3 BED_OUTPUT_INIT; #else -//PWMOutputPin<-1> fet_pin3;// {kPWMPinInverted}; +PWMOutputPin<-1> fet_pin3;// {kPWMPinInverted}; #endif From dbaec2df24ad4cdd76ad99fa5945a73d618346f0 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Mon, 1 May 2017 20:41:50 -0500 Subject: [PATCH 095/193] Motate update to fix PWM on pin A23 inversion --- Motate | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Motate b/Motate index c026a30ef..faa0f4b50 160000 --- a/Motate +++ b/Motate @@ -1 +1 @@ -Subproject commit c026a30ef28deb8696d599de4bfa08af0588ee27 +Subproject commit faa0f4b509c710e276c1ae435f952daa0439f576 From 591a5f2ba19cfba58228588d0699872f1a5fa81f Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Mon, 1 May 2017 20:46:55 -0500 Subject: [PATCH 096/193] Correct not Maxidraw settings. --- g2core/settings/settings_not_maxidraw.h | 19 ++++++++++++++++++- 1 file changed, 18 insertions(+), 1 deletion(-) diff --git a/g2core/settings/settings_not_maxidraw.h b/g2core/settings/settings_not_maxidraw.h index 6a54f9db1..4d6bdd551 100755 --- a/g2core/settings/settings_not_maxidraw.h +++ b/g2core/settings/settings_not_maxidraw.h @@ -118,10 +118,27 @@ #define M2_STEP_ANGLE 1.8 #define M2_TRAVEL_PER_REV 99.9 #define M2_MICROSTEPS X_Y_MICROSTEPS -#define M2_POLARITY 0 +#define M2_POLARITY 1 #define M2_POWER_MODE MOTOR_ALWAYS_POWERED #define M2_POWER_LEVEL X_Y_POWER_LEVEL +// Duplicate M1 on M4 +#define M4_MOTOR_MAP AXIS_X +#define M4_STEP_ANGLE 1.8 +#define M4_TRAVEL_PER_REV 99.9 +#define M4_MICROSTEPS X_Y_MICROSTEPS +#define M4_POLARITY 1 +#define M4_POWER_MODE MOTOR_ALWAYS_POWERED +#define M4_POWER_LEVEL X_Y_POWER_LEVEL + +#define M5_MOTOR_MAP AXIS_Y // 1ma +#define M5_STEP_ANGLE 1.8 // 1sa +#define M5_TRAVEL_PER_REV 99.9 // 1tr +#define M5_MICROSTEPS X_Y_MICROSTEPS // 1mi 1,2,4,8 +#define M5_POLARITY 0 // 1po 0=normal, 1=reversed +#define M5_POWER_MODE MOTOR_ALWAYS_POWERED // 1pm standard +#define M5_POWER_LEVEL X_Y_POWER_LEVEL // 1pl + #define M3_MOTOR_MAP AXIS_Z // This "stepper" is a hobby servo. Note that all hobby // servo settings are per full servo range, instead of From ceb446207df58e769c8113536e4007618341137a Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Mon, 1 May 2017 20:50:00 -0500 Subject: [PATCH 097/193] Renamed Not Maxidraw to DROSMM --- .../{settings_not_maxidraw.h => settings_drosmm_v1.h} | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) rename g2core/settings/{settings_not_maxidraw.h => settings_drosmm_v1.h} (98%) diff --git a/g2core/settings/settings_not_maxidraw.h b/g2core/settings/settings_drosmm_v1.h similarity index 98% rename from g2core/settings/settings_not_maxidraw.h rename to g2core/settings/settings_drosmm_v1.h index 4d6bdd551..a9445831f 100755 --- a/g2core/settings/settings_not_maxidraw.h +++ b/g2core/settings/settings_drosmm_v1.h @@ -1,5 +1,5 @@ /* - * settings_not_maxidraw_v1.h - settings for the WaterColorBot v2 (http://watercolorbot.com/) + * settings_drosmm_v1.h - settings for the DROSMM * This file is part of the g2core project * * Copyright (c) 2016 Alden S. Hart Jr. @@ -27,13 +27,13 @@ */ /***********************************************************************/ -/**** Not MaxiDraw v1 Configuration *****************************************/ +/**** DROSMM v1 Configuration *****************************************/ /***********************************************************************/ #include "hardware.h" // ***> NOTE: The init message must be a single line with no CRs or LFs -#define INIT_MESSAGE "Initializing configs to Not MaxiDraw v1 settings" +#define INIT_MESSAGE "Initializing configs to DROSMM v1 settings (rev2)" #define JUNCTION_INTEGRATION_TIME 2.5 // cornering - usually between 0.5 and 2.0 (higher is faster) #define CHORDAL_TOLERANCE 0.01 // chordal accuracy for arc drawing (in mm) @@ -131,6 +131,7 @@ #define M4_POWER_MODE MOTOR_ALWAYS_POWERED #define M4_POWER_LEVEL X_Y_POWER_LEVEL +// Duplicate M2 on M5 #define M5_MOTOR_MAP AXIS_Y // 1ma #define M5_STEP_ANGLE 1.8 // 1sa #define M5_TRAVEL_PER_REV 99.9 // 1tr @@ -139,6 +140,7 @@ #define M5_POWER_MODE MOTOR_ALWAYS_POWERED // 1pm standard #define M5_POWER_LEVEL X_Y_POWER_LEVEL // 1pl + #define M3_MOTOR_MAP AXIS_Z // This "stepper" is a hobby servo. Note that all hobby // servo settings are per full servo range, instead of From d183160d026925aa22aafb98bcb77f07de07a75b Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Wed, 3 May 2017 08:54:10 -0500 Subject: [PATCH 098/193] Update to UM2+ --- g2core/settings/settings_Ultimaker_2_Plus.h | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/g2core/settings/settings_Ultimaker_2_Plus.h b/g2core/settings/settings_Ultimaker_2_Plus.h index a66861f18..6f92354f3 100644 --- a/g2core/settings/settings_Ultimaker_2_Plus.h +++ b/g2core/settings/settings_Ultimaker_2_Plus.h @@ -103,7 +103,7 @@ #define M1_STEP_ANGLE 1.8 // 1sa // Marlin says 80 steps/unit, and 16 microsteps, with a 200-step/rev motor #define M1_TRAVEL_PER_REV 40 // 1tr -#define M1_MICROSTEPS 64 // 1mi 1,2,4,8,16,32 +#define M1_MICROSTEPS 128 // 1mi 1,2,4,8,16,32 #define M1_POLARITY 0 // 1po 0=normal, 1=reversed #define M1_POWER_MODE MOTOR_POWERED_IN_CYCLE // 1pm standard #define M1_POWER_LEVEL 0.5 // 1pl @@ -113,7 +113,7 @@ #define M2_STEP_ANGLE 1.8 // Marlin says 80 steps/unit, and 16 microsteps, with a 200-step/rev motor #define M2_TRAVEL_PER_REV 40 -#define M2_MICROSTEPS 64 +#define M2_MICROSTEPS 128 #define M2_POLARITY 1 #define M2_POWER_MODE MOTOR_POWERED_IN_CYCLE #define M2_POWER_LEVEL 0.5 @@ -122,7 +122,7 @@ #define M3_STEP_ANGLE 1.8 // Marlin says 200 steps/unit, and 8 microsteps, with a 200-step/rev motor #define M3_TRAVEL_PER_REV 8 -#define M3_MICROSTEPS 64 +#define M3_MICROSTEPS 128 #define M3_POLARITY 0 #define M3_POWER_MODE MOTOR_POWERED_IN_CYCLE #define M3_POWER_LEVEL 0.5 @@ -130,7 +130,7 @@ #define M4_MOTOR_MAP AXIS_A #define M4_STEP_ANGLE 1.8 #define M4_TRAVEL_PER_REV 360 // degrees moved per motor rev -#define M4_MICROSTEPS 64 +#define M4_MICROSTEPS 128 #define M4_POLARITY 0 #define M4_POWER_MODE MOTOR_POWER_MODE #define M4_POWER_LEVEL 0.6 @@ -146,7 +146,7 @@ // *** axis settings ********************************************************************************** #define X_AXIS_MODE AXIS_STANDARD // xam see canonical_machine.h cmAxisMode for valid values -#define X_VELOCITY_MAX 18000 // xvm G0 max velocity in mm/min +#define X_VELOCITY_MAX 12000 // xvm G0 max velocity in mm/min #define X_FEEDRATE_MAX X_VELOCITY_MAX // xfr G1 max feed rate in mm/min #define X_TRAVEL_MIN 0 // xtn minimum travel - used by soft limits and homing #define X_TRAVEL_MAX 230 // xtm travel between switches or crashes @@ -160,7 +160,7 @@ #define X_ZERO_BACKOFF 0.5 // xzb mm #define Y_AXIS_MODE AXIS_STANDARD -#define Y_VELOCITY_MAX 18000 +#define Y_VELOCITY_MAX 12000 #define Y_FEEDRATE_MAX Y_VELOCITY_MAX #define Y_TRAVEL_MIN 0 #define Y_TRAVEL_MAX 224.5 @@ -188,7 +188,7 @@ #define Z_LATCH_BACKOFF 5 #define Z_ZERO_BACKOFF 0 -#define G55_Z_OFFSET 0.25 // higher number is farther away from the bed +#define G55_Z_OFFSET 0.3 // higher number is farther away from the bed // Rotary values are chosen to make the motor react the same as X for testing From 64a289000026441f4b58416d0b550f0babd9ffd4 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Tue, 16 May 2017 15:48:04 -0500 Subject: [PATCH 099/193] More complete control over TMC2130 via JSON and in general. Other quintic cleanup. --- g2core/board/gquintic/0_hardware.cpp | 4 +- g2core/board/gquintic/board_stepper.cpp | 10 +- g2core/board/gquintic/board_xio.cpp | 6 +- g2core/board/gquintic/board_xio.h | 2 +- g2core/board/gquintic/hardware.h | 13 +- .../{hardware.cpp => 0_hardware.cpp} | 0 g2core/config_app.cpp | 297 ++++++++++++- .../device/step_dir_driver/step_dir_driver.h | 2 +- .../step_dir_hobbyservo/step_dir_hobbyservo.h | 2 +- g2core/device/trinamic/tmc2130.cpp | 27 -- g2core/device/trinamic/tmc2130.h | 392 +++++++++++++++++- g2core/settings/settings_Ultimaker_2_Plus.h | 57 ++- g2core/stepper.h | 2 +- 13 files changed, 726 insertions(+), 88 deletions(-) rename g2core/board/printrboardg2/{hardware.cpp => 0_hardware.cpp} (100%) delete mode 100644 g2core/device/trinamic/tmc2130.cpp diff --git a/g2core/board/gquintic/0_hardware.cpp b/g2core/board/gquintic/0_hardware.cpp index 9a2879bc0..1ab8ffc7a 100755 --- a/g2core/board/gquintic/0_hardware.cpp +++ b/g2core/board/gquintic/0_hardware.cpp @@ -39,8 +39,8 @@ //Motate::ClockOutputPin external_clk_pin {16000000}; // 16MHz optimally Motate::OutputPin external_clk_pin {Motate::kStartLow}; -SPI_CS_PinMux_used_t spiCSPinMux; -SPIBus_used_t spiBus; +HOT_DATA SPI_CS_PinMux_used_t spiCSPinMux; +HOT_DATA SPIBus_used_t spiBus; /* * hardware_init() - lowest level hardware init diff --git a/g2core/board/gquintic/board_stepper.cpp b/g2core/board/gquintic/board_stepper.cpp index b588fb42a..e8a202fce 100755 --- a/g2core/board/gquintic/board_stepper.cpp +++ b/g2core/board/gquintic/board_stepper.cpp @@ -34,28 +34,28 @@ // Motate::kSocket1_DirPinNumber, // Motate::kSocket1_EnablePinNumber> // motor_1{spiBus, spiCSPinMux.getCS(4)}; -Trinamic2130 motor_1{spiBus, spiCSPinMux.getCS(3)}; -Trinamic2130 motor_2{spiBus, spiCSPinMux.getCS(2)}; -Trinamic2130 motor_3{spiBus, spiCSPinMux.getCS(1)}; -Trinamic2130 motor_4{spiBus, spiCSPinMux.getCS(0)}; -StepDirHobbyServo motor_5; +HOT_DATA StepDirHobbyServo motor_5; Stepper* Motors[MOTORS] = {&motor_1, &motor_2, &motor_3, &motor_4, &motor_5}; //Stepper* Motors[MOTORS] = {&motor_1, &motor_2, &motor_3, &motor_4, &motor_5, &motor_6}; diff --git a/g2core/board/gquintic/board_xio.cpp b/g2core/board/gquintic/board_xio.cpp index 8c8817654..551e7a10d 100755 --- a/g2core/board/gquintic/board_xio.cpp +++ b/g2core/board/gquintic/board_xio.cpp @@ -42,7 +42,7 @@ const Motate::USBSettings_t Motate::USBSettings = { }; /*gProductVersion = */ //0.1, -XIOUSBDevice_t usb; +HOT_DATA XIOUSBDevice_t usb; decltype(usb.mixin<0>::Serial) &SerialUSB = usb.mixin<0>::Serial; #if USB_SERIAL_PORTS_EXPOSED == 2 @@ -57,13 +57,13 @@ MOTATE_SET_USB_SERIAL_NUMBER_STRING_FROM_CHIPID() //******** SPI ******** #if XIO_HAS_SPI -Motate::SPI spi; +HOT_DATA Motate::SPI spi; #endif //******** UART ******** #if XIO_HAS_UART -Motate::UART Serial {115200, Motate::UARTMode::RTSCTSFlowControl}; +HOT_DATA Motate::UART Serial {115200, Motate::UARTMode::RTSCTSFlowControl}; #endif void board_hardware_init(void) // called 1st diff --git a/g2core/board/gquintic/board_xio.h b/g2core/board/gquintic/board_xio.h index df866818a..09f20fef8 100755 --- a/g2core/board/gquintic/board_xio.h +++ b/g2core/board/gquintic/board_xio.h @@ -43,7 +43,7 @@ typedef Motate::USBDevice< Motate::USBCDC > XIOUSBDevice_t; typedef Motate::USBDevice XIOUSBDevice_t; #endif -extern XIOUSBDevice_t usb HOT_DATA; +extern XIOUSBDevice_t usb; extern decltype(usb.mixin<0>::Serial)& SerialUSB; #if USB_SERIAL_PORTS_EXPOSED == 2 extern decltype(usb.mixin<1>::Serial)& SerialUSB1; diff --git a/g2core/board/gquintic/hardware.h b/g2core/board/gquintic/hardware.h index 73e46778d..d01953cb2 100644 --- a/g2core/board/gquintic/hardware.h +++ b/g2core/board/gquintic/hardware.h @@ -63,6 +63,11 @@ enum hwPlatform { #define PWMS 2 // number of supported PWM channels #define TOOLS 32 // number of entries in tool table (index starts at 1) +#define MOTOR_1_IS_TRINAMIC +#define MOTOR_2_IS_TRINAMIC +#define MOTOR_3_IS_TRINAMIC +#define MOTOR_4_IS_TRINAMIC +//#define MOTOR_5_IS_TRINAMIC //////////////////////////// /////// ARM VERSION //////// @@ -121,12 +126,12 @@ using Motate::OutputPin; /**** Stepper DDA and dwell timer settings ****/ //#define FREQUENCY_DDA 200000UL // Hz step frequency. Interrupts actually fire at 2x (400 KHz) -#define FREQUENCY_DDA 400000UL // Hz step frequency. Interrupts actually fire at 2x (300 KHz) -#define FREQUENCY_DWELL 1000UL +#define FREQUENCY_DDA 400000UL // Hz step frequency. Interrupts actually fire at 2x (300 KHz) +#define FREQUENCY_DWELL 1000UL -#define MIN_SEGMENT_MS ((float)0.125) // S70 can handle much much smaller segements +#define MIN_SEGMENT_MS ((float)0.25) // S70 can handle much much smaller segements -#define PLANNER_BUFFER_POOL_SIZE (96) +#define PLANNER_BUFFER_POOL_SIZE (60) /**** Motate Definitions ****/ diff --git a/g2core/board/printrboardg2/hardware.cpp b/g2core/board/printrboardg2/0_hardware.cpp similarity index 100% rename from g2core/board/printrboardg2/hardware.cpp rename to g2core/board/printrboardg2/0_hardware.cpp diff --git a/g2core/config_app.cpp b/g2core/config_app.cpp index f39f4218f..27cbaf515 100644 --- a/g2core/config_app.cpp +++ b/g2core/config_app.cpp @@ -95,7 +95,7 @@ static stat_t get_tick(nvObj_t *nv); // get system tick count * cannot exceed TOKEN_LEN. String functions working on the table assume these * rules are followed and do not check lengths or perform other validation. * - * - If the count of lines in cfgArray exceeds 255 (which it does) you need to + * - If the count of lines in cfgArray exceeds 255 (which it does) you need to * ensure index_t is uint16_t in the config.h file (and not uint8_t). * * - The precision value 'p' only affects JSON responses. You need to also set @@ -201,66 +201,338 @@ const cfgItem_t cfgArray[] = { { "1","1ma",_fip, 0, st_print_ma, get_ui8, st_set_ma, (float *)&st_cfg.mot[MOTOR_1].motor_map, M1_MOTOR_MAP }, { "1","1sa",_fip, 3, st_print_sa, get_flt, st_set_sa, (float *)&st_cfg.mot[MOTOR_1].step_angle, M1_STEP_ANGLE }, { "1","1tr",_fipc,4, st_print_tr, get_flt, st_set_tr, (float *)&st_cfg.mot[MOTOR_1].travel_rev, M1_TRAVEL_PER_REV }, - { "1","1mi",_fip, 0, st_print_mi, get_ui8, st_set_mi, (float *)&st_cfg.mot[MOTOR_1].microsteps, M1_MICROSTEPS }, + { "1","1mi",_fip, 0, st_print_mi, get_int, st_set_mi, (float *)&st_cfg.mot[MOTOR_1].microsteps, M1_MICROSTEPS }, { "1","1su",_fipi,5, st_print_su, st_get_su,st_set_su, (float *)&st_cfg.mot[MOTOR_1].steps_per_unit, M1_STEPS_PER_UNIT }, { "1","1po",_fip, 0, st_print_po, get_ui8, set_01, (float *)&st_cfg.mot[MOTOR_1].polarity, M1_POLARITY }, { "1","1pm",_fip, 0, st_print_pm, st_get_pm,st_set_pm, (float *)&cs.null, M1_POWER_MODE }, { "1","1pl",_fip, 3, st_print_pl, get_flt, st_set_pl, (float *)&st_cfg.mot[MOTOR_1].power_level, M1_POWER_LEVEL }, // { "1","1pi",_fip, 3, st_print_pi, get_flt, st_set_pi, (float *)&st_cfg.mot[MOTOR_1].power_idle, M1_POWER_IDLE }, // { "1","1mt",_fip, 2, st_print_mt, get_flt, st_set_mt, (float *)&st_cfg.mot[MOTOR_1].motor_timeout, M1_MOTOR_TIMEOUT }, +#ifdef MOTOR_1_IS_TRINAMIC + { "1","1ts",_f0, 0, tx_print_nul, + [](nvObj_t *nv){return motor_1.get_ts(nv); }, + set_ro, (float *)&cs.null, 0 }, + { "1","1pth",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_1.get_pth(nv);}, + [](nvObj_t *nv){return motor_1.set_pth(nv);}, (float *)&cs.null, M1_TMC2130_TPWMTHRS }, + { "1","1cth",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_1.get_cth(nv);}, + [](nvObj_t *nv){return motor_1.set_cth(nv);}, (float *)&cs.null, M1_TMC2130_TCOOLTHRS }, + { "1","1hth",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_1.get_hth(nv);}, + [](nvObj_t *nv){return motor_1.set_hth(nv);}, (float *)&cs.null, M1_TMC2130_THIGH }, + { "1","1sgt",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_1.get_sgt(nv);}, + [](nvObj_t *nv){return motor_1.set_sgt(nv);}, (float *)&cs.null, M1_TMC2130_SGT }, + { "1","1sgr",_f0, 0, tx_print_nul, + [](nvObj_t *nv){return motor_1.get_sgr(nv);}, + set_ro, (float *)&cs.null, 0 }, + { "1","1csa",_f0, 0, tx_print_nul, + [](nvObj_t *nv){return motor_1.get_csa(nv);}, + set_ro, (float *)&cs.null, 0 }, + { "1","1sgs",_f0, 0, tx_print_nul, + [](nvObj_t *nv){return motor_1.get_sgs(nv);}, + set_ro, (float *)&cs.null, 0 }, + { "1","1tbl",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_1.get_tbl(nv);}, + [](nvObj_t *nv){return motor_1.set_tbl(nv);}, (float *)&cs.null, M1_TMC2130_TBL }, + { "1","1pgrd",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_1.get_pgrd(nv);}, + [](nvObj_t *nv){return motor_1.set_pgrd(nv);}, (float *)&cs.null, M1_TMC2130_PWM_GRAD }, + { "1","1pamp",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_1.get_pamp(nv);}, + [](nvObj_t *nv){return motor_1.set_pamp(nv);}, (float *)&cs.null, M1_TMC2130_PWM_AMPL }, + { "1","1hend",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_1.get_hend(nv);}, + [](nvObj_t *nv){return motor_1.set_hend(nv);}, (float *)&cs.null, M1_TMC2130_HEND }, + { "1","1hsrt",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_1.get_hsrt(nv);}, + [](nvObj_t *nv){return motor_1.set_hsrt(nv);}, (float *)&cs.null, M1_TMC2130_HSTRT }, + { "1","1smin",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_1.get_smin(nv);}, + [](nvObj_t *nv){return motor_1.set_smin(nv);}, (float *)&cs.null, M1_TMC2130_SMIN }, + { "1","1smax",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_1.get_smax(nv);}, + [](nvObj_t *nv){return motor_1.set_smax(nv);}, (float *)&cs.null, M1_TMC2130_SMAX }, + { "1","1sup",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_1.get_sup(nv);}, + [](nvObj_t *nv){return motor_1.set_sup(nv);}, (float *)&cs.null, M1_TMC2130_SUP }, + { "1","1sdn",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_1.get_sdn(nv);}, + [](nvObj_t *nv){return motor_1.set_sdn(nv);}, (float *)&cs.null, M1_TMC2130_SDN }, +#endif + #if (MOTORS >= 2) { "2","2ma",_fip, 0, st_print_ma, get_ui8, st_set_ma, (float *)&st_cfg.mot[MOTOR_2].motor_map, M2_MOTOR_MAP }, { "2","2sa",_fip, 3, st_print_sa, get_flt, st_set_sa, (float *)&st_cfg.mot[MOTOR_2].step_angle, M2_STEP_ANGLE }, { "2","2tr",_fipc,4, st_print_tr, get_flt, st_set_tr, (float *)&st_cfg.mot[MOTOR_2].travel_rev, M2_TRAVEL_PER_REV }, - { "2","2mi",_fip, 0, st_print_mi, get_ui8, st_set_mi, (float *)&st_cfg.mot[MOTOR_2].microsteps, M2_MICROSTEPS }, + { "2","2mi",_fip, 0, st_print_mi, get_int, st_set_mi, (float *)&st_cfg.mot[MOTOR_2].microsteps, M2_MICROSTEPS }, { "2","2su",_fipi,5, st_print_su, st_get_su,st_set_su, (float *)&st_cfg.mot[MOTOR_2].steps_per_unit, M2_STEPS_PER_UNIT }, { "2","2po",_fip, 0, st_print_po, get_ui8, set_01, (float *)&st_cfg.mot[MOTOR_2].polarity, M2_POLARITY }, { "2","2pm",_fip, 0, st_print_pm, st_get_pm,st_set_pm, (float *)&cs.null, M2_POWER_MODE }, { "2","2pl",_fip, 3, st_print_pl, get_flt, st_set_pl, (float *)&st_cfg.mot[MOTOR_2].power_level, M2_POWER_LEVEL}, // { "2","2pi",_fip, 3, st_print_pi, get_flt, st_set_pi, (float *)&st_cfg.mot[MOTOR_2].power_idle, M2_POWER_IDLE }, // { "2","2mt",_fip, 2, st_print_mt, get_flt, st_set_mt, (float *)&st_cfg.mot[MOTOR_2].motor_timeout, M2_MOTOR_TIMEOUT }, +#ifdef MOTOR_2_IS_TRINAMIC + { "2","2ts",_f0, 0, tx_print_nul, + [](nvObj_t *nv){return motor_2.get_ts(nv); }, + set_ro, (float *)&cs.null, 0 }, + { "2","2pth",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_2.get_pth(nv);}, + [](nvObj_t *nv){return motor_2.set_pth(nv);}, (float *)&cs.null, M2_TMC2130_TPWMTHRS }, + { "2","2cth",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_2.get_cth(nv);}, + [](nvObj_t *nv){return motor_2.set_cth(nv);}, (float *)&cs.null, M2_TMC2130_TCOOLTHRS }, + { "2","2hth",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_2.get_hth(nv);}, + [](nvObj_t *nv){return motor_2.set_hth(nv);}, (float *)&cs.null, M2_TMC2130_THIGH }, + { "2","2sgt",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_2.get_sgt(nv);}, + [](nvObj_t *nv){return motor_2.set_sgt(nv);}, (float *)&cs.null, M2_TMC2130_SGT }, + { "2","2sgr",_f0, 0, tx_print_nul, + [](nvObj_t *nv){return motor_2.get_sgr(nv);}, + set_ro, (float *)&cs.null, 0 }, + { "2","2csa",_f0, 0, tx_print_nul, + [](nvObj_t *nv){return motor_2.get_csa(nv);}, + set_ro, (float *)&cs.null, 0 }, + { "2","2sgs",_f0, 0, tx_print_nul, + [](nvObj_t *nv){return motor_2.get_sgs(nv);}, + set_ro, (float *)&cs.null, 0 }, + { "2","2tbl",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_2.get_tbl(nv);}, + [](nvObj_t *nv){return motor_2.set_tbl(nv);}, (float *)&cs.null, M2_TMC2130_TBL }, + { "2","2pgrd",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_2.get_pgrd(nv);}, + [](nvObj_t *nv){return motor_2.set_pgrd(nv);}, (float *)&cs.null, M2_TMC2130_PWM_GRAD }, + { "1","2pamp",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_2.get_pamp(nv);}, + [](nvObj_t *nv){return motor_2.set_pamp(nv);}, (float *)&cs.null, M2_TMC2130_PWM_AMPL }, + { "2","2hend",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_2.get_hend(nv);}, + [](nvObj_t *nv){return motor_2.set_hend(nv);}, (float *)&cs.null, M2_TMC2130_HEND }, + { "2","2hsrt",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_2.get_hsrt(nv);}, + [](nvObj_t *nv){return motor_2.set_hsrt(nv);}, (float *)&cs.null, M2_TMC2130_HSTRT }, + { "2","2smin",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_2.get_smin(nv);}, + [](nvObj_t *nv){return motor_2.set_smin(nv);}, (float *)&cs.null, M2_TMC2130_SMIN }, + { "2","2smax",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_2.get_smax(nv);}, + [](nvObj_t *nv){return motor_2.set_smax(nv);}, (float *)&cs.null, M2_TMC2130_SMAX }, + { "2","2sup",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_2.get_sup(nv);}, + [](nvObj_t *nv){return motor_2.set_sup(nv);}, (float *)&cs.null, M2_TMC2130_SUP }, + { "2","2sdn",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_2.get_sdn(nv);}, + [](nvObj_t *nv){return motor_2.set_sdn(nv);}, (float *)&cs.null, M2_TMC2130_SDN }, +#endif #endif #if (MOTORS >= 3) { "3","3ma",_fip, 0, st_print_ma, get_ui8, st_set_ma, (float *)&st_cfg.mot[MOTOR_3].motor_map, M3_MOTOR_MAP }, { "3","3sa",_fip, 3, st_print_sa, get_flt, st_set_sa, (float *)&st_cfg.mot[MOTOR_3].step_angle, M3_STEP_ANGLE }, { "3","3tr",_fipc,4, st_print_tr, get_flt, st_set_tr, (float *)&st_cfg.mot[MOTOR_3].travel_rev, M3_TRAVEL_PER_REV }, - { "3","3mi",_fip, 0, st_print_mi, get_ui8, st_set_mi, (float *)&st_cfg.mot[MOTOR_3].microsteps, M3_MICROSTEPS }, + { "3","3mi",_fip, 0, st_print_mi, get_int, st_set_mi, (float *)&st_cfg.mot[MOTOR_3].microsteps, M3_MICROSTEPS }, { "3","3su",_fipi,5, st_print_su, st_get_su,st_set_su, (float *)&st_cfg.mot[MOTOR_3].steps_per_unit, M3_STEPS_PER_UNIT }, { "3","3po",_fip, 0, st_print_po, get_ui8, set_01, (float *)&st_cfg.mot[MOTOR_3].polarity, M3_POLARITY }, { "3","3pm",_fip, 0, st_print_pm, st_get_pm,st_set_pm, (float *)&cs.null, M3_POWER_MODE }, { "3","3pl",_fip, 3, st_print_pl, get_flt, st_set_pl, (float *)&st_cfg.mot[MOTOR_3].power_level, M3_POWER_LEVEL }, // { "3","3pi",_fip, 3, st_print_pi, get_flt, st_set_pi, (float *)&st_cfg.mot[MOTOR_3].power_idle, M3_POWER_IDLE }, // { "3","3mt",_fip, 2, st_print_mt, get_flt, st_set_mt, (float *)&st_cfg.mot[MOTOR_3].motor_timeout, M3_MOTOR_TIMEOUT }, +#ifdef MOTOR_3_IS_TRINAMIC + { "3","3ts",_f0, 0, tx_print_nul, + [](nvObj_t *nv){return motor_3.get_ts(nv); }, + set_ro, (float *)&cs.null, 0 }, + { "3","3pth",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_3.get_pth(nv);}, + [](nvObj_t *nv){return motor_3.set_pth(nv);}, (float *)&cs.null, M3_TMC2130_TPWMTHRS }, + { "3","3cth",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_3.get_cth(nv);}, + [](nvObj_t *nv){return motor_3.set_cth(nv);}, (float *)&cs.null, M3_TMC2130_TCOOLTHRS }, + { "3","3hth",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_3.get_hth(nv);}, + [](nvObj_t *nv){return motor_3.set_hth(nv);}, (float *)&cs.null, M3_TMC2130_THIGH }, + { "3","3sgt",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_3.get_sgt(nv);}, + [](nvObj_t *nv){return motor_3.set_sgt(nv);}, (float *)&cs.null, M3_TMC2130_SGT }, + { "3","3sgr",_f0, 0, tx_print_nul, + [](nvObj_t *nv){return motor_3.get_sgr(nv);}, + set_ro, (float *)&cs.null, 0 }, + { "3","3csa",_f0, 0, tx_print_nul, + [](nvObj_t *nv){return motor_3.get_csa(nv);}, + set_ro, (float *)&cs.null, 0 }, + { "3","3sgs",_f0, 0, tx_print_nul, + [](nvObj_t *nv){return motor_3.get_sgs(nv);}, + set_ro, (float *)&cs.null, 0 }, + { "3","3tbl",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_3.get_tbl(nv);}, + [](nvObj_t *nv){return motor_3.set_tbl(nv);}, (float *)&cs.null, M3_TMC2130_TBL }, + { "3","3pgrd",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_3.get_pgrd(nv);}, + [](nvObj_t *nv){return motor_3.set_pgrd(nv);}, (float *)&cs.null, M3_TMC2130_PWM_GRAD }, + { "1","3pamp",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_3.get_pamp(nv);}, + [](nvObj_t *nv){return motor_3.set_pamp(nv);}, (float *)&cs.null, M3_TMC2130_PWM_AMPL }, + { "3","3hend",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_3.get_hend(nv);}, + [](nvObj_t *nv){return motor_3.set_hend(nv);}, (float *)&cs.null, M3_TMC2130_HEND }, + { "3","3hsrt",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_3.get_hsrt(nv);}, + [](nvObj_t *nv){return motor_3.set_hsrt(nv);}, (float *)&cs.null, M3_TMC2130_HSTRT }, + { "3","3smin",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_3.get_smin(nv);}, + [](nvObj_t *nv){return motor_3.set_smin(nv);}, (float *)&cs.null, M3_TMC2130_SMIN }, + { "3","3smax",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_3.get_smax(nv);}, + [](nvObj_t *nv){return motor_3.set_smax(nv);}, (float *)&cs.null, M3_TMC2130_SMAX }, + { "3","3sup",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_3.get_sup(nv);}, + [](nvObj_t *nv){return motor_3.set_sup(nv);}, (float *)&cs.null, M3_TMC2130_SUP }, + { "3","3sdn",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_3.get_sdn(nv);}, + [](nvObj_t *nv){return motor_3.set_sdn(nv);}, (float *)&cs.null, M3_TMC2130_SDN }, +#endif #endif #if (MOTORS >= 4) { "4","4ma",_fip, 0, st_print_ma, get_ui8, st_set_ma, (float *)&st_cfg.mot[MOTOR_4].motor_map, M4_MOTOR_MAP }, { "4","4sa",_fip, 3, st_print_sa, get_flt, st_set_sa, (float *)&st_cfg.mot[MOTOR_4].step_angle, M4_STEP_ANGLE }, { "4","4tr",_fipc,4, st_print_tr, get_flt, st_set_tr, (float *)&st_cfg.mot[MOTOR_4].travel_rev, M4_TRAVEL_PER_REV }, - { "4","4mi",_fip, 0, st_print_mi, get_ui8, st_set_mi, (float *)&st_cfg.mot[MOTOR_4].microsteps, M4_MICROSTEPS }, + { "4","4mi",_fip, 0, st_print_mi, get_int, st_set_mi, (float *)&st_cfg.mot[MOTOR_4].microsteps, M4_MICROSTEPS }, { "4","4su",_fipi,5, st_print_su, st_get_su,st_set_su, (float *)&st_cfg.mot[MOTOR_4].steps_per_unit, M4_STEPS_PER_UNIT }, { "4","4po",_fip, 0, st_print_po, get_ui8, set_01, (float *)&st_cfg.mot[MOTOR_4].polarity, M4_POLARITY }, { "4","4pm",_fip, 0, st_print_pm, st_get_pm,st_set_pm, (float *)&cs.null, M4_POWER_MODE }, { "4","4pl",_fip, 3, st_print_pl, get_flt, st_set_pl, (float *)&st_cfg.mot[MOTOR_4].power_level, M4_POWER_LEVEL }, // { "4","4pi",_fip, 3, st_print_pi, get_flt, st_set_pi, (float *)&st_cfg.mot[MOTOR_4].power_idle, M4_POWER_IDLE }, // { "4","4mt",_fip, 2, st_print_mt, get_flt, st_set_mt, (float *)&st_cfg.mot[MOTOR_4].motor_timeout, M4_MOTOR_TIMEOUT }, +#ifdef MOTOR_4_IS_TRINAMIC + { "4","4ts",_f0, 0, tx_print_nul, + [](nvObj_t *nv){return motor_4.get_ts(nv); }, + set_ro, (float *)&cs.null, 0 }, + { "4","4pth",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_4.get_pth(nv);}, + [](nvObj_t *nv){return motor_4.set_pth(nv);}, (float *)&cs.null, M4_TMC2130_TPWMTHRS }, + { "4","4cth",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_4.get_cth(nv);}, + [](nvObj_t *nv){return motor_4.set_cth(nv);}, (float *)&cs.null, M4_TMC2130_TCOOLTHRS }, + { "4","4hth",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_4.get_hth(nv);}, + [](nvObj_t *nv){return motor_4.set_hth(nv);}, (float *)&cs.null, M4_TMC2130_THIGH }, + { "4","4sgt",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_4.get_sgt(nv);}, + [](nvObj_t *nv){return motor_4.set_sgt(nv);}, (float *)&cs.null, M4_TMC2130_SGT }, + { "4","4sgr",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_4.get_sgr(nv);}, + set_ro, (float *)&cs.null, 0 }, + { "4","4csa",_f0, 0, tx_print_nul, + [](nvObj_t *nv){return motor_4.get_csa(nv);}, + set_ro, (float *)&cs.null, 0 }, + { "4","4sgs",_f0, 0, tx_print_nul, + [](nvObj_t *nv){return motor_4.get_sgs(nv);}, + set_ro, (float *)&cs.null, 0 }, + { "4","4tbl",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_4.get_tbl(nv);}, + [](nvObj_t *nv){return motor_4.set_tbl(nv);}, (float *)&cs.null, M4_TMC2130_TBL }, + { "4","4pgrd",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_4.get_pgrd(nv);}, + [](nvObj_t *nv){return motor_4.set_pgrd(nv);}, (float *)&cs.null, M4_TMC2130_PWM_GRAD }, + { "1","4pamp",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_4.get_pamp(nv);}, + [](nvObj_t *nv){return motor_4.set_pamp(nv);}, (float *)&cs.null, M4_TMC2130_PWM_AMPL }, + { "4","4hend",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_4.get_hend(nv);}, + [](nvObj_t *nv){return motor_4.set_hend(nv);}, (float *)&cs.null, M4_TMC2130_HEND }, + { "4","4hsrt",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_4.get_hsrt(nv);}, + [](nvObj_t *nv){return motor_4.set_hsrt(nv);}, (float *)&cs.null, M4_TMC2130_HSTRT }, + { "4","4hend",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_4.get_hend(nv);}, + [](nvObj_t *nv){return motor_4.set_hend(nv);}, (float *)&cs.null, M4_TMC2130_HEND }, + { "4","4hsrt",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_4.get_hsrt(nv);}, + [](nvObj_t *nv){return motor_4.set_hsrt(nv);}, (float *)&cs.null, M4_TMC2130_HSTRT }, + { "4","4smin",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_4.get_smin(nv);}, + [](nvObj_t *nv){return motor_4.set_smin(nv);}, (float *)&cs.null, M4_TMC2130_SMIN }, + { "4","4smax",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_4.get_smax(nv);}, + [](nvObj_t *nv){return motor_4.set_smax(nv);}, (float *)&cs.null, M4_TMC2130_SMAX }, + { "4","4sup",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_4.get_sup(nv);}, + [](nvObj_t *nv){return motor_4.set_sup(nv);}, (float *)&cs.null, M4_TMC2130_SUP }, + { "4","4sdn",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_4.get_sdn(nv);}, + [](nvObj_t *nv){return motor_4.set_sdn(nv);}, (float *)&cs.null, M4_TMC2130_SDN }, +#endif #endif #if (MOTORS >= 5) { "5","5ma",_fip, 0, st_print_ma, get_ui8, st_set_ma, (float *)&st_cfg.mot[MOTOR_5].motor_map, M5_MOTOR_MAP }, { "5","5sa",_fip, 3, st_print_sa, get_flt, st_set_sa, (float *)&st_cfg.mot[MOTOR_5].step_angle, M5_STEP_ANGLE }, { "5","5tr",_fipc,4, st_print_tr, get_flt, st_set_tr, (float *)&st_cfg.mot[MOTOR_5].travel_rev, M5_TRAVEL_PER_REV }, - { "5","5mi",_fip, 0, st_print_mi, get_ui8, st_set_mi, (float *)&st_cfg.mot[MOTOR_5].microsteps, M5_MICROSTEPS }, + { "5","5mi",_fip, 0, st_print_mi, get_int, st_set_mi, (float *)&st_cfg.mot[MOTOR_5].microsteps, M5_MICROSTEPS }, { "5","5su",_fipi,5, st_print_su, st_get_su,st_set_su, (float *)&st_cfg.mot[MOTOR_5].steps_per_unit, M5_STEPS_PER_UNIT }, { "5","5po",_fip, 0, st_print_po, get_ui8, set_01, (float *)&st_cfg.mot[MOTOR_5].polarity, M5_POLARITY }, { "5","5pm",_fip, 0, st_print_pm, st_get_pm,st_set_pm, (float *)&cs.null, M5_POWER_MODE }, { "5","5pl",_fip, 3, st_print_pl, get_flt, st_set_pl, (float *)&st_cfg.mot[MOTOR_5].power_level, M5_POWER_LEVEL }, // { "5","5pi",_fip, 3, st_print_pi, get_flt, st_set_pi, (float *)&st_cfg.mot[MOTOR_5].power_idle, M5_POWER_IDLE }, // { "5","5mt",_fip, 2, st_print_mt, get_flt, st_set_mt, (float *)&st_cfg.mot[MOTOR_5].motor_timeout, M5_MOTOR_TIMEOUT }, +#ifdef MOTOR_5_IS_TRINAMIC + { "5","5ts",_f0, 0, tx_print_nul, + [](nvObj_t *nv){return motor_5.get_ts(nv); }, + set_ro, (float *)&cs.null, 0 }, + { "5","5pth",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_5.get_pth(nv);}, + [](nvObj_t *nv){return motor_5.set_pth(nv);}, (float *)&cs.null, M5_TMC2130_TPWMTHRS }, + { "5","5cth",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_5.get_cth(nv);}, + [](nvObj_t *nv){return motor_5.set_cth(nv);}, (float *)&cs.null, M5_TMC2130_TCOOLTHRS }, + { "5","5hth",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_5.get_hth(nv);}, + [](nvObj_t *nv){return motor_5.set_hth(nv);}, (float *)&cs.null, M5_TMC2130_THIGH }, + { "5","5sgt",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_5.get_sgt(nv);}, + [](nvObj_t *nv){return motor_5.set_sgt(nv);}, (float *)&cs.null, M5_TMC2130_SGT }, + { "5","5sgr",_f0, 0, tx_print_nul, + [](nvObj_t *nv){return motor_5.get_sgr(nv);}, + set_ro, (float *)&cs.null, 0 }, + { "5","5csa",_f0, 0, tx_print_nul, + [](nvObj_t *nv){return motor_5.get_csa(nv);}, + set_ro, (float *)&cs.null, 0 }, + { "5","5sgs",_f0, 0, tx_print_nul, + [](nvObj_t *nv){return motor_5.get_sgs(nv);}, + set_ro, (float *)&cs.null, 0 }, + { "5","5tbl",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_5.get_tbl(nv);}, + [](nvObj_t *nv){return motor_5.set_tbl(nv);}, (float *)&cs.null, M5_TMC2130_TBL }, + { "5","5pgrd",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_5.get_pgrd(nv);}, + [](nvObj_t *nv){return motor_5.set_pgrd(nv);}, (float *)&cs.null, M5_TMC2130_PWM_GRAD }, + { "5","5pamp",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_5.get_pamp(nv);}, + [](nvObj_t *nv){return motor_5.set_pamp(nv);}, (float *)&cs.null, M5_TMC2130_PWM_AMPL }, + { "5","5hend",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_5.get_hend(nv);}, + [](nvObj_t *nv){return motor_5.set_hend(nv);}, (float *)&cs.null, M5_TMC2130_HEND }, + { "5","5hsrt",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_5.get_hsrt(nv);}, + [](nvObj_t *nv){return motor_5.set_hsrt(nv);}, (float *)&cs.null, M5_TMC2130_HSTRT }, + { "5","5smin",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_5.get_smin(nv);}, + [](nvObj_t *nv){return motor_5.set_smin(nv);}, (float *)&cs.null, M5_TMC2130_SMIN }, + { "5","5smax",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_5.get_smax(nv);}, + [](nvObj_t *nv){return motor_5.set_smax(nv);}, (float *)&cs.null, M5_TMC2130_SMAX }, + { "5","5sup",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_5.get_sup(nv);}, + [](nvObj_t *nv){return motor_5.set_sup(nv);}, (float *)&cs.null, M5_TMC2130_SUP }, + { "5","5sdn",_fip, 0, tx_print_nul, + [](nvObj_t *nv){return motor_5.get_sdn(nv);}, + [](nvObj_t *nv){return motor_5.set_sdn(nv);}, (float *)&cs.null, M5_TMC2130_SDN }, +#endif #endif #if (MOTORS >= 6) { "6","6ma",_fip, 0, st_print_ma, get_ui8, st_set_ma, (float *)&st_cfg.mot[MOTOR_6].motor_map, M6_MOTOR_MAP }, { "6","6sa",_fip, 3, st_print_sa, get_flt, st_set_sa, (float *)&st_cfg.mot[MOTOR_6].step_angle, M6_STEP_ANGLE }, { "6","6tr",_fipc,4, st_print_tr, get_flt, st_set_tr, (float *)&st_cfg.mot[MOTOR_6].travel_rev, M6_TRAVEL_PER_REV }, - { "6","6mi",_fip, 0, st_print_mi, get_ui8, st_set_mi, (float *)&st_cfg.mot[MOTOR_6].microsteps, M6_MICROSTEPS }, + { "6","6mi",_fip, 0, st_print_mi, get_int, st_set_mi, (float *)&st_cfg.mot[MOTOR_6].microsteps, M6_MICROSTEPS }, { "6","6su",_fipi,5, st_print_su, st_get_su,st_set_su, (float *)&st_cfg.mot[MOTOR_6].steps_per_unit, M6_STEPS_PER_UNIT }, { "6","6po",_fip, 0, st_print_po, get_ui8, set_01, (float *)&st_cfg.mot[MOTOR_6].polarity, M6_POLARITY }, { "6","6pm",_fip, 0, st_print_pm, st_get_pm,st_set_pm, (float *)&cs.null, M6_POWER_MODE }, @@ -268,6 +540,7 @@ const cfgItem_t cfgArray[] = { // { "6","6pi",_fip, 3, st_print_pi, get_flt, st_set_pi, (float *)&st_cfg.mot[MOTOR_6].power_idle, M6_POWER_IDLE }, // { "6","6mt",_fip, 2, st_print_mt, get_flt, st_set_mt, (float *)&st_cfg.mot[MOTOR_6].motor_timeout, M6_MOTOR_TIMEOUT }, #endif + // Axis parameters { "x","xam",_fip, 0, cm_print_am, cm_get_am, cm_set_am, (float *)&cm.a[AXIS_X].axis_mode, X_AXIS_MODE }, { "x","xvm",_fipc, 0, cm_print_vm, get_flt, cm_set_vm, (float *)&cm.a[AXIS_X].velocity_max, X_VELOCITY_MAX }, @@ -1278,14 +1551,14 @@ stat_t set_fltp(nvObj_t *nv) /* * preprocess_float() - pre-process floating point number for units display * - * Apologies in advance for this twisty little function. This function is used to + * Apologies in advance for this twisty little function. This function is used to * convert the native, canonical form of a parameter (mm, or whatever), into a display * format appropriate to the units mode in effect. It uses the flags in the config table - * to determine what type of conversion to perform. It's complicated by the fact that - * only linear axes actually convert - rotaries do not. Plus, determining the axis for - * a motor requires unraveling the motor mapping (handled in cm_get_axis_type()). + * to determine what type of conversion to perform. It's complicated by the fact that + * only linear axes actually convert - rotaries do not. Plus, determining the axis for + * a motor requires unraveling the motor mapping (handled in cm_get_axis_type()). * Also, there are global SYS group values that are not associated with any axis. - * Lastly, the steps-per-unit value (1su) is actually kept in inverse conversion form, + * Lastly, the steps-per-unit value (1su) is actually kept in inverse conversion form, * as its native form would be units-per-step. */ diff --git a/g2core/device/step_dir_driver/step_dir_driver.h b/g2core/device/step_dir_driver/step_dir_driver.h index d64ddded6..3d4ba3b3d 100644 --- a/g2core/device/step_dir_driver/step_dir_driver.h +++ b/g2core/device/step_dir_driver/step_dir_driver.h @@ -75,7 +75,7 @@ struct StepDirStepper final : Stepper { bool canStep() override { return !_step.isNull(); }; - void setMicrosteps(const uint8_t microsteps) override { + void setMicrosteps(const uint16_t microsteps) override { if (!_enable.isNull()) { switch (microsteps) { case (1): { diff --git a/g2core/device/step_dir_hobbyservo/step_dir_hobbyservo.h b/g2core/device/step_dir_hobbyservo/step_dir_hobbyservo.h index e0a46c6a7..0a7fb6ef8 100644 --- a/g2core/device/step_dir_hobbyservo/step_dir_hobbyservo.h +++ b/g2core/device/step_dir_hobbyservo/step_dir_hobbyservo.h @@ -75,7 +75,7 @@ struct StepDirHobbyServo final : Stepper { bool canStep() override { return true; }; - void setMicrosteps(const uint8_t microsteps) override { + void setMicrosteps(const uint16_t microsteps) override { switch (microsteps) { case (1): { _microsteps_per_step = 32; diff --git a/g2core/device/trinamic/tmc2130.cpp b/g2core/device/trinamic/tmc2130.cpp deleted file mode 100644 index 32dd3104c..000000000 --- a/g2core/device/trinamic/tmc2130.cpp +++ /dev/null @@ -1,27 +0,0 @@ -/* - * trinamic/tmc2130.cpp - control over a Trinamic TMC2130 stepper motor driver - * This file is part of the G2 project - * - * Copyright (c) 2016 Alden S. Hart, Jr. - * Copyright (c) 2016 Robert Giseburt - * - * This file ("the software") is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License, version 2 as published by the - * Free Software Foundation. You should have received a copy of the GNU General Public - * License, version 2 along with the software. If not, see . - * - * As a special exception, you may use this file as part of a software library without - * restriction. Specifically, if other files instantiate templates or use macros or - * inline functions from this file, or you compile this file and link it with other - * files to produce an executable, this file does not by itself cause the resulting - * executable to be covered by the GNU General Public License. This exception does not - * however invalidate any other reasons why the executable file might be covered by the - * GNU General Public License. - * - * THE SOFTWARE IS DISTRIBUTED IN THE HOPE THAT IT WILL BE USEFUL, BUT WITHOUT ANY - * WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES - * OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT - * SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF - * OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - */ diff --git a/g2core/device/trinamic/tmc2130.h b/g2core/device/trinamic/tmc2130.h index 1c189470f..0b78bbadc 100644 --- a/g2core/device/trinamic/tmc2130.h +++ b/g2core/device/trinamic/tmc2130.h @@ -110,7 +110,7 @@ struct Trinamic2130 final : Stepper { // We can leave this as is: // bool canStep() override { return true; }; - void setMicrosteps(const uint8_t microsteps) override + void setMicrosteps(const uint16_t microsteps) override { switch (microsteps) { case ( 0): { CHOPCONF.MRES = 0; break; } // 256 @@ -122,6 +122,7 @@ struct Trinamic2130 final : Stepper { case ( 32): { CHOPCONF.MRES = 3; break; } case ( 64): { CHOPCONF.MRES = 2; break; } case (128): { CHOPCONF.MRES = 1; break; } + case (256): { CHOPCONF.MRES = 0; break; } default: return; } CHOPCONF_needs_written = true; @@ -400,17 +401,30 @@ struct Trinamic2130 final : Stepper { volatile bool CHOPCONF_needs_read; volatile bool CHOPCONF_needs_written; - struct { + union { volatile uint32_t value; - // uint8_t bytes[4]; - } COOLCONF; // 0x6D - READ ONLY - void _postReadCoolConf() { - COOLCONF.value = fromBigEndian(in_buffer.value); - }; + volatile struct { + uint32_t semin : 4; // 0 - 3 + uint32_t : 1; // 4 + uint32_t seup : 2; // 5 - 6 + uint32_t : 1; // 7 + uint32_t semax : 4; // 8 - 11 + uint32_t : 1; // 12 + uint32_t sedn : 2; // 13 - 14 + uint32_t seimin : 1; // 15 + + uint32_t sgt : 7; // 16-22 + uint32_t : 1; // 23 + uint32_t sfilt : 1; // 24 + } __attribute__ ((packed)); + } COOLCONF; // 0x6D - WRITE ONLY +// void _postReadCoolConf() { +// COOLCONF.value = fromBigEndian(in_buffer.value); +// }; void _prepWriteCoolConf() { out_buffer.value = toBigEndian(COOLCONF.value); }; - volatile bool COOLCONF_needs_read; +// volatile bool COOLCONF_needs_read; volatile bool COOLCONF_needs_written; union { @@ -485,7 +499,7 @@ struct Trinamic2130 final : Stepper { if (XDIRECT_needs_read) { next_reg = XDIRECT_reg; XDIRECT_needs_read = false; } else if (MSCNT_needs_read) { next_reg = MSCNT_reg; MSCNT_needs_read = false; } else if (CHOPCONF_needs_read) { next_reg = CHOPCONF_reg; CHOPCONF_needs_read = false; } else - if (COOLCONF_needs_read) { next_reg = COOLCONF_reg; COOLCONF_needs_read = false; } else +// if (COOLCONF_needs_read) { next_reg = COOLCONF_reg; COOLCONF_needs_read = false; } else if (DRV_STATUS_needs_read) { next_reg = DRV_STATUS_reg; DRV_STATUS_needs_read = false; } else // otherwise, check to see if we need to finish a read @@ -518,7 +532,7 @@ struct Trinamic2130 final : Stepper { case XDIRECT_reg: _postReadXDirect(); break; case MSCNT_reg: _postReadMSCount(); break; case CHOPCONF_reg: _postReadChopConf(); break; - case COOLCONF_reg: _postReadCoolConf(); break; +// case COOLCONF_reg: _postReadCoolConf(); break; case DRV_STATUS_reg: _postReadDriverStatus(); break; default: @@ -559,29 +573,59 @@ struct Trinamic2130 final : Stepper { TPOWERDOWN.value = 256; TPOWERDOWN_needs_written = true; + // With a nominal 12mhz clock, 1 "tick" is 1/12000000 + // TSTEP ≥ TPWMTHRS -> go into stealthChop + // TSTEP is ticks-per-step, so higher TSTEP means slower motion + // So, to convert 50mm/s to TSTEP, with 40mm/rev (M) and 200fs/rev (f), we get: + // - convert mm to revolutions: r=(S/M) + // - then revolutions to steps + // - then steps to 1/256th microsteps: s=(r*f*256) + // - then convert microsteps/sec to ticks/microstep: T=s/(1/12000000) == T=12000000/s + // T = 12000000/((S/M)*f*256); f=200; M=40; S=20 -> T=187.5 + TPWMTHRS.value = 24; // 400mm/s + TPWMTHRS_needs_written = true; + TCOOLTHRS.value = 10; // 300mm/s + TCOOLTHRS_needs_written = true; + THIGH.value = 10; // 300mm/s + THIGH_needs_written = true; + XDIRECT.value = 0; XDIRECT_needs_written = true; VDCMIN.value = 0; VDCMIN_needs_written = true; - GCONF.en_pwm_mode = 1; - GCONF_needs_written = true; - - CHOPCONF.TOFF = 0x5; + GCONF.i_scale_analog = 0; + GCONF.internal_Rsense = 0; + GCONF.en_pwm_mode = 1; // enable stealthChop™ + GCONF.enc_commutation = 0; + GCONF.shaft = 0; + GCONF.diag0_error = 0; + GCONF.diag0_otpw = 0; + GCONF.diag0_stall = 0; + GCONF.diag1_stall = 0; + GCONF.diag1_index = 0; + GCONF.diag1_onstate = 0; + GCONF.diag1_steps_skipped = 0; + GCONF.diag0_int_pushpull = 0; + GCONF.diag1_pushpull = 0; + GCONF.small_hysteresis = 0; + GCONF_needs_written = true; + + CHOPCONF.TOFF = 0x4; // was 5 "For operation with stealthChop, this parameter is not used, but it is required to enable the motor." CHOPCONF.HSTRT_TFD012 = 0x4; - CHOPCONF.HEND_OFFSET = 0x1; + CHOPCONF.HEND_OFFSET = 0x0; // value is 0 for -3, 1 for -2, etc. CHOPCONF.TFD3 = 0x0; CHOPCONF.disfdcc = 0x0; - CHOPCONF.rndtf = 0x0; + CHOPCONF.rndtf = 0x0; // enable spreadCycle™ CHOPCONF.chm = 0x0; - CHOPCONF.TBL = 0x2; - CHOPCONF.vsense = 0x1; + CHOPCONF.TBL = 0x1; // was 2 + CHOPCONF.vsense = 0x1; // was 1 CHOPCONF.vhighfs = 0x0; CHOPCONF.vhighchm = 0x0; - CHOPCONF.SYNC = 0x0; + CHOPCONF.SYNC = 5; CHOPCONF.MRES = 0x3; - CHOPCONF.intpol = 0x0; + CHOPCONF.intpol = 0; CHOPCONF.dedge = 0x0; CHOPCONF.diss2g = 0x0; // CHOPCONF.TOFF = 8; @@ -603,8 +647,8 @@ struct Trinamic2130 final : Stepper { CHOPCONF_needs_written = true; PWMCONF.PWM_AMPL = 200; - PWMCONF.PWM_GRAD = 1; - PWMCONF.pwm_freq = 0; + PWMCONF.PWM_GRAD = 5; // 0 - 15 + PWMCONF.pwm_freq = 3; // approx 19MHz with the internal clock PWMCONF.pwm_autoscale = 1; PWMCONF.pwm_symmetric = 0; PWMCONF.freewheel = 0; @@ -616,6 +660,16 @@ struct Trinamic2130 final : Stepper { // PWMCONF.freewheel = 0; PWMCONF_needs_written = true; + COOLCONF.semin = 1; // enable coolstep and set min sg (1-15) + COOLCONF.semax = 15; // set coolstep max sg(0-15) + COOLCONF.seup = 3; // set coolstep up rate (0-3) + COOLCONF.sedn = 3; // set coolstep down rate (0-3) +// COOLCONF.sgt = 64+(64-60); // set stallGuard threshold (-64 to 63) (-60) + COOLCONF.sgt = 0; // set stallGuard threshold (-64 to 63) (63) + COOLCONF.seimin= 1; // minimum current setting (0 for 1/2 IRUN, or 1 for 1/4 IRUN) + COOLCONF.sfilt= 1; // enable stallGuard filtering (0 or 1) + COOLCONF_needs_written = true; + IOIN_needs_read = true; MSCNT_needs_read = true; @@ -634,7 +688,301 @@ struct Trinamic2130 final : Stepper { IOIN_needs_read = true; CHOPCONF_needs_read = true; DRV_STATUS_needs_read = true; + TSTEP_needs_read = true; _startNextReadWrite(); } }; + + + // NV interface helpers + stat_t get_ts(nvObj_t *nv) { + nv->value = TSTEP.value; + nv->valuetype = TYPE_INT; + return STAT_OK; + }; + // no set + + stat_t get_pth(nvObj_t *nv) { + nv->value = TPWMTHRS.value; + nv->valuetype = TYPE_INT; + return STAT_OK; + }; + stat_t set_pth(nvObj_t *nv) { + int32_t v = nv->value; + if (v < 0) { + nv->valuetype = TYPE_NULL; + return (STAT_INPUT_LESS_THAN_MIN_VALUE); + } + if (v > 1048575) { + nv->valuetype = TYPE_NULL; + return (STAT_INPUT_EXCEEDS_MAX_VALUE); + } + TPWMTHRS.value = v; + TPWMTHRS_needs_written = true; + return STAT_OK; + }; + + stat_t get_cth(nvObj_t *nv) { + nv->value = TCOOLTHRS.value; + nv->valuetype = TYPE_INT; + return STAT_OK; + }; + stat_t set_cth(nvObj_t *nv) { + int32_t v = nv->value; + if (v < 0) { + nv->valuetype = TYPE_NULL; + return (STAT_INPUT_LESS_THAN_MIN_VALUE); + } + if (v > 1048575) { + nv->valuetype = TYPE_NULL; + return (STAT_INPUT_EXCEEDS_MAX_VALUE); + } + TCOOLTHRS.value = v; + TCOOLTHRS_needs_written = true; + return STAT_OK; + }; + + stat_t get_hth(nvObj_t *nv) { + nv->value = THIGH.value; + nv->valuetype = TYPE_INT; + return STAT_OK; + }; + stat_t set_hth(nvObj_t *nv) { + int32_t v = nv->value; + if (v < 0) { + nv->valuetype = TYPE_NULL; + return (STAT_INPUT_LESS_THAN_MIN_VALUE); + } + if (v > 1048575) { + nv->valuetype = TYPE_NULL; + return (STAT_INPUT_EXCEEDS_MAX_VALUE); + } + THIGH.value = v; + THIGH_needs_written = true; + return STAT_OK; + }; + + stat_t get_sgt(nvObj_t *nv) { + int32_t v = COOLCONF.sgt; + nv->value = (int32_t)(63&v)-(v&64); + nv->valuetype = TYPE_INT; + return STAT_OK; + }; + stat_t set_sgt(nvObj_t *nv) { + int32_t v = nv->value; + if (v < -64) { + nv->valuetype = TYPE_NULL; + return (STAT_INPUT_LESS_THAN_MIN_VALUE); + } + if (v > 63) { + nv->valuetype = TYPE_NULL; + return (STAT_INPUT_EXCEEDS_MAX_VALUE); + } + COOLCONF.sgt = (v<0)?127&(64|((~(-v))+1)):v; + COOLCONF_needs_written = true; + return STAT_OK; + }; + + stat_t get_csa(nvObj_t *nv) { + nv->value = DRV_STATUS.CS_ACTUAL; + nv->valuetype = TYPE_INT; + return STAT_OK; + }; + // no set + + stat_t get_sgr(nvObj_t *nv) { + nv->value = DRV_STATUS.SG_RESULT; + nv->valuetype = TYPE_INT; + return STAT_OK; + }; + // no set + + stat_t get_sgs(nvObj_t *nv) { + nv->value = DRV_STATUS.stallGuard; + nv->valuetype = TYPE_BOOL; + return STAT_OK; + }; + // no set + + + stat_t get_tbl(nvObj_t *nv) { + nv->value = CHOPCONF.TBL; + nv->valuetype = TYPE_INT; + return STAT_OK; + }; + stat_t set_tbl(nvObj_t *nv) { + int32_t v = nv->value; + if (v < 0) { + nv->valuetype = TYPE_NULL; + return (STAT_INPUT_LESS_THAN_MIN_VALUE); + } + if (v > 3) { + nv->valuetype = TYPE_NULL; + return (STAT_INPUT_EXCEEDS_MAX_VALUE); + } + CHOPCONF.TBL = v; + CHOPCONF_needs_written = true; + return STAT_OK; + }; + + stat_t get_pgrd(nvObj_t *nv) { + nv->value = PWMCONF.PWM_GRAD; + nv->valuetype = TYPE_INT; + return STAT_OK; + }; + stat_t set_pgrd(nvObj_t *nv) { + int32_t v = nv->value; + if (v < 0) { + nv->valuetype = TYPE_NULL; + return (STAT_INPUT_LESS_THAN_MIN_VALUE); + } + if (v > 15) { + nv->valuetype = TYPE_NULL; + return (STAT_INPUT_EXCEEDS_MAX_VALUE); + } + PWMCONF.PWM_GRAD = v; + PWMCONF_needs_written = true; + return STAT_OK; + }; + + stat_t get_pamp(nvObj_t *nv) { + nv->value = PWMCONF.PWM_AMPL; + nv->valuetype = TYPE_INT; + return STAT_OK; + }; + stat_t set_pamp(nvObj_t *nv) { + int32_t v = nv->value; + if (v < 0) { + nv->valuetype = TYPE_NULL; + return (STAT_INPUT_LESS_THAN_MIN_VALUE); + } + if (v > 255) { + nv->valuetype = TYPE_NULL; + return (STAT_INPUT_EXCEEDS_MAX_VALUE); + } + PWMCONF.PWM_AMPL = v; + PWMCONF_needs_written = true; + return STAT_OK; + }; + + stat_t get_hend(nvObj_t *nv) { + nv->value = CHOPCONF.HEND_OFFSET; + nv->valuetype = TYPE_INT; + return STAT_OK; + }; + stat_t set_hend(nvObj_t *nv) { + int32_t v = nv->value; + if (v < 0) { + nv->valuetype = TYPE_NULL; + return (STAT_INPUT_LESS_THAN_MIN_VALUE); + } + if (v > 15) { + nv->valuetype = TYPE_NULL; + return (STAT_INPUT_EXCEEDS_MAX_VALUE); + } + CHOPCONF.HEND_OFFSET = v; + CHOPCONF_needs_written = true; + return STAT_OK; + }; + + stat_t get_hsrt(nvObj_t *nv) { + nv->value = CHOPCONF.HSTRT_TFD012; + nv->valuetype = TYPE_INT; + return STAT_OK; + }; + stat_t set_hsrt(nvObj_t *nv) { + int32_t v = nv->value; + if (v < 0) { + nv->valuetype = TYPE_NULL; + return (STAT_INPUT_LESS_THAN_MIN_VALUE); + } + if (v > 15) { + nv->valuetype = TYPE_NULL; + return (STAT_INPUT_EXCEEDS_MAX_VALUE); + } + CHOPCONF.HSTRT_TFD012 = v; + CHOPCONF_needs_written = true; + return STAT_OK; + }; + + stat_t get_smin(nvObj_t *nv) { + nv->value = COOLCONF.semin; + nv->valuetype = TYPE_INT; + return STAT_OK; + }; + stat_t set_smin(nvObj_t *nv) { + int32_t v = nv->value; + if (v < 0) { + nv->valuetype = TYPE_NULL; + return (STAT_INPUT_LESS_THAN_MIN_VALUE); + } + if (v > 15) { + nv->valuetype = TYPE_NULL; + return (STAT_INPUT_EXCEEDS_MAX_VALUE); + } + COOLCONF.semin = v; + COOLCONF_needs_written = true; + return STAT_OK; + }; + + stat_t get_smax(nvObj_t *nv) { + nv->value = COOLCONF.semax; + nv->valuetype = TYPE_INT; + return STAT_OK; + }; + stat_t set_smax(nvObj_t *nv) { + int32_t v = nv->value; + if (v < 0) { + nv->valuetype = TYPE_NULL; + return (STAT_INPUT_LESS_THAN_MIN_VALUE); + } + if (v > 15) { + nv->valuetype = TYPE_NULL; + return (STAT_INPUT_EXCEEDS_MAX_VALUE); + } + COOLCONF.semax = v; + COOLCONF_needs_written = true; + return STAT_OK; + }; + + stat_t get_sup(nvObj_t *nv) { + nv->value = COOLCONF.seup; + nv->valuetype = TYPE_INT; + return STAT_OK; + }; + stat_t set_sup(nvObj_t *nv) { + int32_t v = nv->value; + if (v < 0) { + nv->valuetype = TYPE_NULL; + return (STAT_INPUT_LESS_THAN_MIN_VALUE); + } + if (v > 15) { + nv->valuetype = TYPE_NULL; + return (STAT_INPUT_EXCEEDS_MAX_VALUE); + } + COOLCONF.seup = v; + COOLCONF_needs_written = true; + return STAT_OK; + }; + + stat_t get_sdn(nvObj_t *nv) { + nv->value = COOLCONF.sedn; + nv->valuetype = TYPE_INT; + return STAT_OK; + }; + stat_t set_sdn(nvObj_t *nv) { + int32_t v = nv->value; + if (v < 0) { + nv->valuetype = TYPE_NULL; + return (STAT_INPUT_LESS_THAN_MIN_VALUE); + } + if (v > 15) { + nv->valuetype = TYPE_NULL; + return (STAT_INPUT_EXCEEDS_MAX_VALUE); + } + COOLCONF.sedn = v; + COOLCONF_needs_written = true; + return STAT_OK; + }; + }; diff --git a/g2core/settings/settings_Ultimaker_2_Plus.h b/g2core/settings/settings_Ultimaker_2_Plus.h index 6f92354f3..3c6ccde0a 100644 --- a/g2core/settings/settings_Ultimaker_2_Plus.h +++ b/g2core/settings/settings_Ultimaker_2_Plus.h @@ -40,6 +40,8 @@ //**** GLOBAL / GENERAL SETTINGS ****************************************************** #define JUNCTION_INTEGRATION_TIME 1.0 // cornering - between 0.10 and 2.00 (higher is faster) +//{jt:1.0} +//{jt:0.75} #define CHORDAL_TOLERANCE 0.01 // chordal accuracy for arc drawing (in mm) #define SOFT_LIMIT_ENABLE 0 // 0=off, 1=on @@ -83,7 +85,7 @@ //#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","he1t","he1st","he1at","he1op","pid1p","pid1i","pid1d","feed","vel","unit","path","stat" // Defaults for thermistor tuning -#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","he1t","he1st","he1at","he1tr","he1tv","he1op","he2t","he2st","he2at","he2tr","he2tv","he2op","he3t","he3st","he3at","he3tr","he3tv","he3op","feed","vel","unit","path","stat","_fe1","_fe2","_fe3","_fe4","_xs1","_xs2","_xs3","_xs4" +#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","he1t","he1st","he1at","he1tr","he1tv","he1op","he2t","he2st","he2at","he2tr","he2tv","he2op","he3t","he3st","he3at","he3tr","he3tv","he3op","feed","vel","unit","path","stat","1ts","2ts","1sgr","1sgs","2sgr","2sgs","_xs1","_xs2","_xs3","_xs4" //{sr:{"line":t,"posx":t,"posy":t,"posz":t,"posa":t,"he1t":t,"he1st":t,"he1at":t,"he1tr":t,"he1tv":t,"he1op":t,"he3t":t,"he3st":t,"he3at":t,"he3tr":t,"he3tv":t,"he3op":t,"feed":t,"vel":t,"unit":t,"path":t,"stat":t}} // Gcode startup defaults #define GCODE_DEFAULT_UNITS MILLIMETERS // MILLIMETERS or INCHES @@ -103,10 +105,14 @@ #define M1_STEP_ANGLE 1.8 // 1sa // Marlin says 80 steps/unit, and 16 microsteps, with a 200-step/rev motor #define M1_TRAVEL_PER_REV 40 // 1tr -#define M1_MICROSTEPS 128 // 1mi 1,2,4,8,16,32 +#define M1_MICROSTEPS 128 // 1mi 1,2,4,8,16,32 #define M1_POLARITY 0 // 1po 0=normal, 1=reversed #define M1_POWER_MODE MOTOR_POWERED_IN_CYCLE // 1pm standard #define M1_POWER_LEVEL 0.5 // 1pl +#define M1_TMC2130_TPWMTHRS 500 // 1pth +#define M1_TMC2130_TCOOLTHRS 200 // 1cth +#define M1_TMC2130_THIGH 100 // 1hth +#define M1_TMC2130_SGT 4 // 1sgt // 80 steps/mm at 1/16 microstepping = 40 mm/rev #define M2_MOTOR_MAP AXIS_Y @@ -117,6 +123,10 @@ #define M2_POLARITY 1 #define M2_POWER_MODE MOTOR_POWERED_IN_CYCLE #define M2_POWER_LEVEL 0.5 +#define M2_TMC2130_TPWMTHRS 500 +#define M2_TMC2130_TCOOLTHRS 200 +#define M2_TMC2130_THIGH 100 +#define M2_TMC2130_SGT 4 #define M3_MOTOR_MAP AXIS_Z #define M3_STEP_ANGLE 1.8 @@ -126,6 +136,10 @@ #define M3_POLARITY 0 #define M3_POWER_MODE MOTOR_POWERED_IN_CYCLE #define M3_POWER_LEVEL 0.5 +#define M3_TMC2130_TPWMTHRS 500 +#define M3_TMC2130_TCOOLTHRS 200 +#define M3_TMC2130_THIGH 100 +#define M3_TMC2130_SGT 4 #define M4_MOTOR_MAP AXIS_A #define M4_STEP_ANGLE 1.8 @@ -134,6 +148,10 @@ #define M4_POLARITY 0 #define M4_POWER_MODE MOTOR_POWER_MODE #define M4_POWER_LEVEL 0.6 +#define M4_TMC2130_TPWMTHRS 500 +#define M4_TMC2130_TCOOLTHRS 200 +#define M4_TMC2130_THIGH 100 +#define M4_TMC2130_SGT 4 #define M5_MOTOR_MAP AXIS_B #define M5_STEP_ANGLE 1.8 @@ -142,11 +160,15 @@ #define M5_POLARITY 0 #define M5_POWER_MODE MOTOR_POWER_MODE #define M5_POWER_LEVEL 0.8 +#define M5_TMC2130_TPWMTHRS 500 +#define M5_TMC2130_TCOOLTHRS 200 +#define M5_TMC2130_THIGH 100 +#define M5_TMC2130_SGT 4 // *** axis settings ********************************************************************************** #define X_AXIS_MODE AXIS_STANDARD // xam see canonical_machine.h cmAxisMode for valid values -#define X_VELOCITY_MAX 12000 // xvm G0 max velocity in mm/min +#define X_VELOCITY_MAX 9000 // xvm G0 max velocity in mm/min #define X_FEEDRATE_MAX X_VELOCITY_MAX // xfr G1 max feed rate in mm/min #define X_TRAVEL_MIN 0 // xtn minimum travel - used by soft limits and homing #define X_TRAVEL_MAX 230 // xtm travel between switches or crashes @@ -158,9 +180,11 @@ #define X_LATCH_VELOCITY 200 // xlv mm/min #define X_LATCH_BACKOFF 10 // xlb mm #define X_ZERO_BACKOFF 0.5 // xzb mm +//{xjm:5000} +//{yjm:5000} #define Y_AXIS_MODE AXIS_STANDARD -#define Y_VELOCITY_MAX 12000 +#define Y_VELOCITY_MAX 9000 #define Y_FEEDRATE_MAX Y_VELOCITY_MAX #define Y_TRAVEL_MIN 0 #define Y_TRAVEL_MAX 224.5 @@ -188,8 +212,10 @@ #define Z_LATCH_BACKOFF 5 #define Z_ZERO_BACKOFF 0 -#define G55_Z_OFFSET 0.3 // higher number is farther away from the bed - +//#define G55_Z_OFFSET 0.3 // higher number is farther away from the bed +// {g55z:0.3} +#define G55_Z_OFFSET 0.25 // higher number is farther away from the bed +// {g55z:0.25} // Rotary values are chosen to make the motor react the same as X for testing /*************************************************************************************** @@ -219,7 +245,7 @@ //#define A_FEEDRATE_MAX 36110.8 // ~15 mm/s //#define A_FEEDRATE_MAX 24073.9 // ~10 mm/s //#define A_FEEDRATE_MAX 12036.95 // ~5 mm/s -#define A_FEEDRATE_MAX 6018.475 // ~2.5 mm/s Testing: {afr:6018.475} +#define A_FEEDRATE_MAX 6018.475 // ~2.5 mm/s Testing: {afr:800} //#define A_FEEDRATE_MAX 1000.0 // ~0.415 mm/s //#define A_FEEDRATE_MAX 800.0 // WORKS WELL //#define A_FEEDRATE_MAX 500.0 // ~0.2075 mm/s @@ -227,7 +253,7 @@ #define A_TRAVEL_MAX 10 //#define A_JERK_MAX 288886.4 // ~120 million mm/min^3 //#define A_JERK_MAX 144443.2 // ~60 million mm/min^3 -#define A_JERK_MAX 48147.7 // ~20 million mm/min^3 +#define A_JERK_MAX 48147.7 // ~20 million mm/min^3 {ajm:48147.7} #define A_HOMING_INPUT 0 #define A_HOMING_DIRECTION 0 #define A_SEARCH_VELOCITY 2000 @@ -252,7 +278,20 @@ #define B_LATCH_BACKOFF 5 #define B_ZERO_BACKOFF 2 #define B_JERK_HIGH_SPEED 361108.0 // ~150 million mm/min^3 - +// +//{afr:6018.475} +//{ajm:48147.7} +//{xjm:8000} +//{yjm:8000} +//{xfr:3000} +//{yfr:3000} +//{1pl:0.25} +//{2pl:0.25} +//{4pl:0.35} + +//{1pl:0.6} +//{2pl:0.6} +//{4pl:0.6} //*** Input / output settings *** diff --git a/g2core/stepper.h b/g2core/stepper.h index 0109568d6..6d148ad35 100644 --- a/g2core/stepper.h +++ b/g2core/stepper.h @@ -571,7 +571,7 @@ struct Stepper { virtual void stepStart() HOT_FUNC { /* must override */ }; // HOT - called from the DDA interrupt virtual void stepEnd() HOT_FUNC { /* must override */ }; // HOT - called from the DDA interrupt virtual void setDirection(uint8_t new_direction) HOT_FUNC { /* must override */ }; // HOT - called from the DDA interrupt - virtual void setMicrosteps(const uint8_t microsteps) { /* must override */ }; + virtual void setMicrosteps(const uint16_t microsteps) { /* must override */ }; virtual void setPowerLevel(float new_pl) { /* must override */ }; }; From 72f80f9b9e28286e3801e440424b6d151fa5c4ab Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Tue, 16 May 2017 15:52:00 -0500 Subject: [PATCH 100/193] Added NEW_DDA to test a new optimized DDA --- g2core/stepper.cpp | 105 ++++++++++++++++++++++++++++++++++++--------- g2core/stepper.h | 26 ++++++++--- 2 files changed, 103 insertions(+), 28 deletions(-) diff --git a/g2core/stepper.cpp b/g2core/stepper.cpp index cd6b607db..0d1983228 100644 --- a/g2core/stepper.cpp +++ b/g2core/stepper.cpp @@ -304,39 +304,63 @@ void dda_timer_type::interrupt() // process DDAs for each motor if ((st_run.mot[MOTOR_1].substep_accumulator += st_run.mot[MOTOR_1].substep_increment) > 0) { motor_1.stepStart(); // turn step bit on +#if NEW_DDA == 1 st_run.mot[MOTOR_1].substep_accumulator -= DDA_SUBSTEPS; //st_run.dda_ticks_X_substeps; +#else + st_run.mot[MOTOR_1].substep_accumulator -= st_run.dda_ticks_X_substeps; +#endif INCREMENT_ENCODER(MOTOR_1); } if ((st_run.mot[MOTOR_2].substep_accumulator += st_run.mot[MOTOR_2].substep_increment) > 0) { motor_2.stepStart(); // turn step bit on +#if NEW_DDA == 1 st_run.mot[MOTOR_2].substep_accumulator -= DDA_SUBSTEPS; //st_run.dda_ticks_X_substeps; +#else + st_run.mot[MOTOR_2].substep_accumulator -= st_run.dda_ticks_X_substeps; +#endif INCREMENT_ENCODER(MOTOR_2); } #if MOTORS > 2 if ((st_run.mot[MOTOR_3].substep_accumulator += st_run.mot[MOTOR_3].substep_increment) > 0) { motor_3.stepStart(); // turn step bit on +#if NEW_DDA == 1 st_run.mot[MOTOR_3].substep_accumulator -= DDA_SUBSTEPS; //st_run.dda_ticks_X_substeps; +#else + st_run.mot[MOTOR_3].substep_accumulator -= st_run.dda_ticks_X_substeps; +#endif INCREMENT_ENCODER(MOTOR_3); } #endif #if MOTORS > 3 if ((st_run.mot[MOTOR_4].substep_accumulator += st_run.mot[MOTOR_4].substep_increment) > 0) { motor_4.stepStart(); // turn step bit on +#if NEW_DDA == 1 st_run.mot[MOTOR_4].substep_accumulator -= DDA_SUBSTEPS; //st_run.dda_ticks_X_substeps; +#else + st_run.mot[MOTOR_4].substep_accumulator -= st_run.dda_ticks_X_substeps; +#endif INCREMENT_ENCODER(MOTOR_4); } #endif #if MOTORS > 4 if ((st_run.mot[MOTOR_5].substep_accumulator += st_run.mot[MOTOR_5].substep_increment) > 0) { motor_5.stepStart(); // turn step bit on +#if NEW_DDA == 1 st_run.mot[MOTOR_5].substep_accumulator -= DDA_SUBSTEPS; //st_run.dda_ticks_X_substeps; +#else + st_run.mot[MOTOR_5].substep_accumulator -= st_run.dda_ticks_X_substeps; +#endif INCREMENT_ENCODER(MOTOR_5); } #endif #if MOTORS > 5 if ((st_run.mot[MOTOR_6].substep_accumulator += st_run.mot[MOTOR_6].substep_increment) > 0) { motor_6.stepStart(); // turn step bit on +#if NEW_DDA == 1 st_run.mot[MOTOR_6].substep_accumulator -= DDA_SUBSTEPS; //st_run.dda_ticks_X_substeps; +#else + st_run.mot[MOTOR_6].substep_accumulator -= st_run.dda_ticks_X_substeps; +#endif INCREMENT_ENCODER(MOTOR_6); } #endif @@ -491,8 +515,10 @@ static void _load_move() //**** setup the new segment **** // st_run.dda_ticks_downcount is setup right before turning on the interrupt, since we don't turn it off -// st_run.dda_ticks_X_substeps = st_pre.dda_ticks_X_substeps; - +#if NEW_DDA == 1 +#else + st_run.dda_ticks_X_substeps = st_pre.dda_ticks_X_substeps; +#endif // INLINED VERSION: 4.3us //**** MOTOR_1 LOAD **** @@ -507,7 +533,8 @@ static void _load_move() // segments it may have been inactive in between. // Apply accumulator correction if the time base has changed since previous segment -#if 0 +#if NEW_DDA == 1 +#else if (st_pre.mot[MOTOR_1].accumulator_correction_flag == true) { st_pre.mot[MOTOR_1].accumulator_correction_flag = false; st_run.mot[MOTOR_1].substep_accumulator *= st_pre.mot[MOTOR_1].accumulator_correction; @@ -520,8 +547,11 @@ static void _load_move() if (st_pre.mot[MOTOR_1].direction != st_pre.mot[MOTOR_1].prev_direction) { st_pre.mot[MOTOR_1].prev_direction = st_pre.mot[MOTOR_1].direction; -// st_run.mot[MOTOR_1].substep_accumulator = -(st_run.dda_ticks_X_substeps + st_run.mot[MOTOR_1].substep_accumulator); +#if NEW_DDA == 1 st_run.mot[MOTOR_1].substep_accumulator = -(DDA_SUBSTEPS + st_run.mot[MOTOR_1].substep_accumulator); // invert the accumulator for the direction change +#else + st_run.mot[MOTOR_1].substep_accumulator = -(st_run.dda_ticks_X_substeps + st_run.mot[MOTOR_1].substep_accumulator); +#endif motor_1.setDirection(st_pre.mot[MOTOR_1].direction); } @@ -537,7 +567,8 @@ static void _load_move() #if (MOTORS >= 2) if ((st_run.mot[MOTOR_2].substep_increment = st_pre.mot[MOTOR_2].substep_increment) != 0) { -#if 0 +#if NEW_DDA == 1 +#else if (st_pre.mot[MOTOR_2].accumulator_correction_flag == true) { st_pre.mot[MOTOR_2].accumulator_correction_flag = false; st_run.mot[MOTOR_2].substep_accumulator *= st_pre.mot[MOTOR_2].accumulator_correction; @@ -545,7 +576,11 @@ static void _load_move() #endif if (st_pre.mot[MOTOR_2].direction != st_pre.mot[MOTOR_2].prev_direction) { st_pre.mot[MOTOR_2].prev_direction = st_pre.mot[MOTOR_2].direction; - st_run.mot[MOTOR_2].substep_accumulator = -(DDA_SUBSTEPS + st_run.mot[MOTOR_2].substep_accumulator); +#if NEW_DDA == 1 + st_run.mot[MOTOR_2].substep_accumulator = -(DDA_SUBSTEPS + st_run.mot[MOTOR_2].substep_accumulator); // invert the accumulator for the direction change +#else + st_run.mot[MOTOR_2].substep_accumulator = -(st_run.dda_ticks_X_substeps + st_run.mot[MOTOR_2].substep_accumulator); +#endif motor_2.setDirection(st_pre.mot[MOTOR_2].direction); } motor_2.enable(); @@ -557,7 +592,8 @@ static void _load_move() #endif #if (MOTORS >= 3) if ((st_run.mot[MOTOR_3].substep_increment = st_pre.mot[MOTOR_3].substep_increment) != 0) { -#if 0 +#if NEW_DDA == 1 +#else if (st_pre.mot[MOTOR_3].accumulator_correction_flag == true) { st_pre.mot[MOTOR_3].accumulator_correction_flag = false; st_run.mot[MOTOR_3].substep_accumulator *= st_pre.mot[MOTOR_3].accumulator_correction; @@ -565,7 +601,11 @@ static void _load_move() #endif if (st_pre.mot[MOTOR_3].direction != st_pre.mot[MOTOR_3].prev_direction) { st_pre.mot[MOTOR_3].prev_direction = st_pre.mot[MOTOR_3].direction; - st_run.mot[MOTOR_3].substep_accumulator = -(DDA_SUBSTEPS + st_run.mot[MOTOR_3].substep_accumulator); +#if NEW_DDA == 1 + st_run.mot[MOTOR_3].substep_accumulator = -(DDA_SUBSTEPS + st_run.mot[MOTOR_3].substep_accumulator); // invert the accumulator for the direction change +#else + st_run.mot[MOTOR_3].substep_accumulator = -(st_run.dda_ticks_X_substeps + st_run.mot[MOTOR_3].substep_accumulator); +#endif motor_3.setDirection(st_pre.mot[MOTOR_3].direction); } motor_3.enable(); @@ -577,7 +617,8 @@ static void _load_move() #endif #if (MOTORS >= 4) if ((st_run.mot[MOTOR_4].substep_increment = st_pre.mot[MOTOR_4].substep_increment) != 0) { -#if 0 +#if NEW_DDA == 1 +#else if (st_pre.mot[MOTOR_4].accumulator_correction_flag == true) { st_pre.mot[MOTOR_4].accumulator_correction_flag = false; st_run.mot[MOTOR_4].substep_accumulator *= st_pre.mot[MOTOR_4].accumulator_correction; @@ -585,7 +626,11 @@ static void _load_move() #endif if (st_pre.mot[MOTOR_4].direction != st_pre.mot[MOTOR_4].prev_direction) { st_pre.mot[MOTOR_4].prev_direction = st_pre.mot[MOTOR_4].direction; - st_run.mot[MOTOR_4].substep_accumulator = -(DDA_SUBSTEPS + st_run.mot[MOTOR_4].substep_accumulator); +#if NEW_DDA == 1 + st_run.mot[MOTOR_4].substep_accumulator = -(DDA_SUBSTEPS + st_run.mot[MOTOR_4].substep_accumulator); // invert the accumulator for the direction change +#else + st_run.mot[MOTOR_4].substep_accumulator = -(st_run.dda_ticks_X_substeps + st_run.mot[MOTOR_4].substep_accumulator); +#endif motor_4.setDirection(st_pre.mot[MOTOR_4].direction); } motor_4.enable(); @@ -597,7 +642,8 @@ static void _load_move() #endif #if (MOTORS >= 5) if ((st_run.mot[MOTOR_5].substep_increment = st_pre.mot[MOTOR_5].substep_increment) != 0) { -#if 0 +#if NEW_DDA == 1 +#else if (st_pre.mot[MOTOR_5].accumulator_correction_flag == true) { st_pre.mot[MOTOR_5].accumulator_correction_flag = false; st_run.mot[MOTOR_5].substep_accumulator *= st_pre.mot[MOTOR_5].accumulator_correction; @@ -605,7 +651,11 @@ static void _load_move() #endif if (st_pre.mot[MOTOR_5].direction != st_pre.mot[MOTOR_5].prev_direction) { st_pre.mot[MOTOR_5].prev_direction = st_pre.mot[MOTOR_5].direction; - st_run.mot[MOTOR_5].substep_accumulator = -(DDA_SUBSTEPS + st_run.mot[MOTOR_5].substep_accumulator); +#if NEW_DDA == 1 + st_run.mot[MOTOR_5].substep_accumulator = -(DDA_SUBSTEPS + st_run.mot[MOTOR_5].substep_accumulator); // invert the accumulator for the direction change +#else + st_run.mot[MOTOR_5].substep_accumulator = -(st_run.dda_ticks_X_substeps + st_run.mot[MOTOR_5].substep_accumulator); +#endif motor_5.setDirection(st_pre.mot[MOTOR_5].direction); } motor_5.enable(); @@ -617,7 +667,8 @@ static void _load_move() #endif #if (MOTORS >= 6) if ((st_run.mot[MOTOR_6].substep_increment = st_pre.mot[MOTOR_6].substep_increment) != 0) { -#if 0 +#if NEW_DDA == 1 +#else if (st_pre.mot[MOTOR_6].accumulator_correction_flag == true) { st_pre.mot[MOTOR_6].accumulator_correction_flag = false; st_run.mot[MOTOR_6].substep_accumulator *= st_pre.mot[MOTOR_6].accumulator_correction; @@ -625,7 +676,11 @@ static void _load_move() #endif if (st_pre.mot[MOTOR_6].direction != st_pre.mot[MOTOR_6].prev_direction) { st_pre.mot[MOTOR_6].prev_direction = st_pre.mot[MOTOR_6].direction; - st_run.mot[MOTOR_6].substep_accumulator = -(DDA_SUBSTEPS + st_run.mot[MOTOR_6].substep_accumulator); +#if NEW_DDA == 1 + st_run.mot[MOTOR_6].substep_accumulator = -(DDA_SUBSTEPS + st_run.mot[MOTOR_6].substep_accumulator); // invert the accumulator for the direction change +#else + st_run.mot[MOTOR_6].substep_accumulator = -(st_run.dda_ticks_X_substeps + st_run.mot[MOTOR_6].substep_accumulator); +#endif motor_6.setDirection(st_pre.mot[MOTOR_6].direction); } motor_6.enable(); @@ -702,7 +757,10 @@ stat_t st_prep_line(float travel_steps[], float following_error[], float segment //st_pre.dda_period = _f_to_period(FREQUENCY_DDA); // FYI: this is a constant st_pre.dda_ticks = (int32_t)(segment_time * 60 * FREQUENCY_DDA);// NB: converts minutes to seconds - //st_pre.dda_ticks_X_substeps = st_pre.dda_ticks * DDA_SUBSTEPS; +#if NEW_DDA == 1 +#else + st_pre.dda_ticks_X_substeps = st_pre.dda_ticks * DDA_SUBSTEPS; +#endif // setup motor parameters @@ -726,7 +784,8 @@ stat_t st_prep_line(float travel_steps[], float following_error[], float segment st_pre.mot[motor].step_sign = -1; } -#if 0 +#if NEW_DDA == 1 +#else // Detect segment time changes and setup the accumulator correction factor and flag. // Putting this here computes the correct factor even if the motor was dormant for some // number of previous moves. Correction is computed based on the last segment time actually used. @@ -762,7 +821,11 @@ stat_t st_prep_line(float travel_steps[], float following_error[], float segment // Rounding is performed to eliminate a negative bias in the uint32 conversion // that results in long-term negative drift. (fabs/round order doesn't matter) - st_pre.mot[motor].substep_increment = round(fabs(travel_steps[motor] * DDA_SUBSTEPS) / st_pre.dda_ticks); +#if NEW_DDA == 1 + st_pre.mot[motor].substep_increment = round(fabs(travel_steps[motor] / (float)st_pre.dda_ticks) * (float)DDA_SUBSTEPS); +#else + st_pre.mot[motor].substep_increment = round(fabs(travel_steps[motor] * DDA_SUBSTEPS)); +#endif } st_pre.block_type = BLOCK_TYPE_ALINE; st_pre.buffer_state = PREP_BUFFER_OWNED_BY_LOADER; // signal that prep buffer is ready @@ -818,7 +881,7 @@ void st_request_out_of_band_dwell(float milliseconds) /* * _set_hw_microsteps() - set microsteps in hardware */ -static void _set_hw_microsteps(const uint8_t motor, const uint8_t microsteps) +static void _set_hw_microsteps(const uint8_t motor, const uint16_t microsteps) { if (motor >= MOTORS) {return;} @@ -917,13 +980,13 @@ stat_t st_set_mi(nvObj_t *nv) // motor microsteps return (STAT_INPUT_LESS_THAN_MIN_VALUE); } - uint8_t mi = (uint8_t)nv->value; + uint16_t mi = nv->value; if ((mi != 1) && (mi != 2) && (mi != 4) && (mi != 8) && (mi != 16) && (mi != 32)) { nv_add_conditional_message((const char *)"*** WARNING *** Setting non-standard microstep value"); } - set_ui8(nv); // set it anyway, even if it's unsupported + set_int(nv); // set it anyway, even if it's unsupported _set_motor_steps_per_unit(nv); - _set_hw_microsteps(_get_motor(nv->index), (uint8_t)nv->value); + _set_hw_microsteps(_get_motor(nv->index), nv->value); return (STAT_OK); } diff --git a/g2core/stepper.h b/g2core/stepper.h index 6d148ad35..c9f277872 100644 --- a/g2core/stepper.h +++ b/g2core/stepper.h @@ -254,6 +254,8 @@ #ifndef STEPPER_H_ONCE #define STEPPER_H_ONCE +#define NEW_DDA 1 + #include "MotateUtilities.h" // for HOT_DATA and HOT_FUNC #include "planner.h" // planner.h must precede stepper.h for moveType typedef @@ -311,9 +313,11 @@ typedef enum { * The ARM is roughly the same as the DDA clock rate is 4x higher but the segment time is ~1/5 * Decreasing the nominal segment time increases the number precision. */ -//#define DDA_SUBSTEPS ((MAX_LONG * 0.90) / (FREQUENCY_DDA * (NOM_SEGMENT_TIME * 60))) -//#define DDA_SUBSTEPS (MAX_LONG * 0.90) -#define DDA_SUBSTEPS (1932735283L) +#if NEW_DDA == 1 +#define DDA_SUBSTEPS (2147483600L) +#else +#define DDA_SUBSTEPS ((MAX_LONG * 0.90) / (FREQUENCY_DDA * (NOM_SEGMENT_TIME * 60))) +#endif /* Step correction settings * @@ -350,9 +354,9 @@ typedef enum { typedef struct cfgMotor { // per-motor configs // public - uint8_t motor_map; // map motor to axis - uint8_t microsteps; // microsteps to apply for each axis (ex: 8) - uint8_t polarity; // 0=normal polarity, 1=reverse motor direction + uint8_t motor_map; // map motor to axis + uint32_t microsteps; // microsteps to apply for each axis (ex: 8) + uint8_t polarity; // 0=normal polarity, 1=reverse motor direction float power_level; // set 0.000 to 1.000 for PMW vref setting float step_angle; // degrees per whole step (ex: 1.8) float travel_rev; // mm or deg of travel per motor revolution @@ -379,7 +383,11 @@ typedef struct stRunSingleton { // Stepper static values and axis pa magic_t magic_start; // magic number to test memory integrity uint32_t dda_ticks_downcount; // dda tick down-counter (unscaled) uint32_t dwell_ticks_downcount; // dwell tick down-counter (unscaled) +#if NEW_DDA == 1 uint32_t dda_steps_tick_X_substeps; // DDA substps per tick scaled by substep factor +#else + uint32_t dda_ticks_X_substeps; // ticks multiplied by scaling factor +#endif stRunMotor_t mot[MOTORS]; // runtime motor structures magic_t magic_end; } stRunSingleton_t; @@ -413,8 +421,12 @@ typedef struct stPrepSingleton { blockType block_type; // move type (requires planner.h) uint32_t dda_ticks; // DDA ticks for the move + float dda_ticks_holdover; // partial DDA ticks from previous segment uint32_t dwell_ticks; // dwell ticks remaining -// uint32_t dda_ticks_X_substeps; // DDA ticks scaled by substep factor +#if NEW_DDA == 1 +#else + uint32_t dda_ticks_X_substeps; // DDA ticks scaled by substep factor +#endif stPrepMotor_t mot[MOTORS]; // prep time motor structs magic_t magic_end; } stPrepSingleton_t; From 02e3aaf3113fce528fc523122129a9bd6ec8c2fd Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Tue, 16 May 2017 15:53:05 -0500 Subject: [PATCH 101/193] Computed last-in move exit junction_velocity to non-zero. MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Uses a unit vector of all zeroes for the “next move”. --- g2core/plan_line.cpp | 35 ++++++++++++++++++++++++++++++++++- 1 file changed, 34 insertions(+), 1 deletion(-) diff --git a/g2core/plan_line.cpp b/g2core/plan_line.cpp index 0d6f0b844..a36ea4f46 100644 --- a/g2core/plan_line.cpp +++ b/g2core/plan_line.cpp @@ -280,7 +280,9 @@ static mpBuf_t* _plan_block(mpBuf_t* bf) if (mp.planner_state == PLANNER_PRIMING) { // Timings from *here* + if (bf->pv->plannable) { + // calculate junction with previous move _calculate_junction_vmax(bf->pv); // compute maximum junction velocity constraint if (bf->pv->gm.path_control == PATH_EXACT_STOP) { bf->pv->exit_vmax = 0; @@ -288,6 +290,15 @@ static mpBuf_t* _plan_block(mpBuf_t* bf) bf->pv->exit_vmax = std::min(std::min(bf->pv->junction_vmax, bf->pv->cruise_vmax), bf->cruise_vmax); } } + + // calculate junction to stop + _calculate_junction_vmax(bf); // compute maximum junction velocity constraint + if (bf->gm.path_control == PATH_EXACT_STOP) { + bf->exit_vmax = 0; + } else { + bf->exit_vmax = std::min(bf->junction_vmax, bf->cruise_vmax); + } + _calculate_override(bf); // adjust cruise_vmax for feed/traverse override // bf->plannable_time = bf->pv->plannable_time; // set plannable time - excluding current move bf->buffer_state = MP_BUFFER_IN_PROCESS; @@ -692,6 +703,28 @@ static void _calculate_vmaxes(mpBuf_t* bf, const float axis_length[], const floa static void _calculate_junction_vmax(mpBuf_t* bf) { + // special case for planning the last block + if (bf->nx->buffer_state == MP_BUFFER_EMPTY) { + // Compute a junction velocity to full stop + float velocity = bf->cruise_vmax; // start with our maximum possible velocity + + for (uint8_t axis = 0; axis < AXES; axis++) { + if (bf->axis_flags[axis]) { // skip axes with no movement + float delta = bf->unit[axis]; + + // Corner case: If an axis has zero delta, we might have a straight line. + // Corner case: An axis doesn't change (and it's not a straight line). + // In either case, division-by-zero is bad, m'kay? + if (delta > EPSILON) { + velocity = std::min(velocity, (cm.a[axis].max_junction_accel / delta)); + } + } + } + + bf->junction_vmax = velocity; + return; + } + // ++++ RG If we change cruise_vmax, we'll need to recompute junction_vmax, if we do this: float velocity = std::min(bf->cruise_vmax, bf->nx->cruise_vmax); // start with our maximum possible velocity @@ -699,7 +732,7 @@ static void _calculate_junction_vmax(mpBuf_t* bf) // cmAxes jerk_axis = AXIS_X; bool using_junction_unit = false; float junction_length_since = bf->junction_length_since + bf->length; - if (junction_length_since < 5.0) { + if (junction_length_since < 0.5) { // push the length_since forward, and copy the junction_unit bf->nx->junction_length_since = junction_length_since; using_junction_unit = true; From f95c1c14e914cd9fc12be4c262fc23a32d528903 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Tue, 16 May 2017 15:57:35 -0500 Subject: [PATCH 102/193] Update Motate reference for various ADC/Pin/compile fixes --- Motate | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Motate b/Motate index faa0f4b50..c24acaba9 160000 --- a/Motate +++ b/Motate @@ -1 +1 @@ -Subproject commit faa0f4b509c710e276c1ae435f952daa0439f576 +Subproject commit c24acaba902ec2ac09d0917e87f664624b70ae19 From b25a2a0b0cfceac13a98522e371c38b26c5416ef Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Tue, 16 May 2017 15:58:21 -0500 Subject: [PATCH 103/193] Adding gquintic-c target --- g2core/board/gquintic.mk | 7 +- g2core/board/gquintic/gquintic-b-pinout.h | 189 ++++++++++--------- g2core/board/gquintic/gquintic-c-pinout.h | 215 ++++++++++++++++++++++ g2core/boards.mk | 11 +- 4 files changed, 324 insertions(+), 98 deletions(-) create mode 100755 g2core/board/gquintic/gquintic-c-pinout.h diff --git a/g2core/board/gquintic.mk b/g2core/board/gquintic.mk index 8ccba539f..c5dfd5ec5 100755 --- a/g2core/board/gquintic.mk +++ b/g2core/board/gquintic.mk @@ -16,7 +16,12 @@ ifeq ("$(BOARD)","gquintic-b") BASE_BOARD=gquintic DEVICE_DEFINES += MOTATE_BOARD="gquintic-b" DEVICE_DEFINES += SETTINGS_FILE=${SETTINGS_FILE} - DEVICE_DEFINES += SERVO_MOTOR=6 +endif + +ifeq ("$(BOARD)","gquintic-c") + BASE_BOARD=gquintic + DEVICE_DEFINES += MOTATE_BOARD="gquintic-c" + DEVICE_DEFINES += SETTINGS_FILE=${SETTINGS_FILE} endif diff --git a/g2core/board/gquintic/gquintic-b-pinout.h b/g2core/board/gquintic/gquintic-b-pinout.h index ba8989d33..0f9c35f3b 100755 --- a/g2core/board/gquintic/gquintic-b-pinout.h +++ b/g2core/board/gquintic/gquintic-b-pinout.h @@ -1,9 +1,9 @@ /* - * gquintic-a-pinout.h - board pinout specification + * gquintic-b-pinout.h - board pinout specification * This file is part of the g2core project * - * Copyright (c) 2016 Robert Giseburt - * Copyright (c) 2016 Alden S. Hart Jr. + * Copyright (c) 2016-2017 Robert Giseburt + * Copyright (c) 2016-2017 Alden S. Hart Jr. * * This file is part of the Motate Library. * @@ -113,98 +113,97 @@ namespace Motate { -// Unused: -// -// -// -// -// - -_MAKE_MOTATE_PIN(kLED_RGBWPixelPinNumber, 'A', 0); // -_MAKE_MOTATE_PIN(kHeaterOutput1_PinNumber, 'A', 1); // TC 0,1 -_MAKE_MOTATE_PIN(kHeaterOutput2_PinNumber, 'A', 2); // PWM 0,1 -_MAKE_MOTATE_PIN(kI2C1_SDAPinNumber, 'A', 3); // -_MAKE_MOTATE_PIN(kI2C1_SCLPinNumber, 'A', 4); // -_MAKE_MOTATE_PIN(kHeaterOutput11_PinNumber, 'A', 5); // PWM 1,3 -_MAKE_MOTATE_PIN(kExternalClock1_PinNumber, 'A', 6); // CPU_CLK -_MAKE_MOTATE_PIN(kOutput7_PinNumber, 'A', 7); // PWM 0,3 -//_MAKE_MOTATE_PIN(kServo1_PinNumber, 'A', 7); // -_MAKE_MOTATE_PIN(kSerial_RTSPinNumber, 'A', 8); // -_MAKE_MOTATE_PIN(kSerial_RXPinNumber, 'A', 9); // -_MAKE_MOTATE_PIN(kSerial_TXPinNumber, 'A', 10); // -_MAKE_MOTATE_PIN(kSocket2_EnablePinNumber, 'A', 11); // -_MAKE_MOTATE_PIN(kOutput6_PinNumber, 'A', 12); // PWM 1,0 -_MAKE_MOTATE_PIN(kOutput8_PinNumber, 'A', 13); // PWM 0,2 -_MAKE_MOTATE_PIN(kSocket1_StepPinNumber, 'A', 14); // -_MAKE_MOTATE_PIN(kOutput3_PinNumber, 'A', 15); // TC 1,0 -_MAKE_MOTATE_PIN(kOutput4_PinNumber, 'A', 16); // TC 1,1 -_MAKE_MOTATE_PIN(kADC4_PinNumber, 'A', 17); // AFEC0,6 -_MAKE_MOTATE_PIN(kADC3_PinNumber, 'A', 18); // AFEC0,7 -_MAKE_MOTATE_PIN(kADC2_PinNumber, 'A', 19); // AFEC0,8 -_MAKE_MOTATE_PIN(kADC1_PinNumber, 'A', 20); // AFEC0,9 -_MAKE_MOTATE_PIN(kSerial_CTSPinNumber, 'A', 21); // -_MAKE_MOTATE_PIN(kSocket1_EnablePinNumber, 'A', 22); // -//_MAKE_MOTATE_PIN(kOutput10_PinNumber, 'A', 23); // PWM 1,2 -_MAKE_MOTATE_PIN(kServo1_PinNumber, 'A', 23); // -_MAKE_MOTATE_PIN(kSocket3_EnablePinNumber, 'A', 24); // -_MAKE_MOTATE_PIN(kSocket2_DirPinNumber, 'A', 25); // -_MAKE_MOTATE_PIN(kOutput5_PinNumber, 'A', 26); // TC 2,0 -_MAKE_MOTATE_PIN(kSocket3_DirPinNumber, 'A', 27); // On Timer 2! -_MAKE_MOTATE_PIN(kUnassigned1, 'A', 28); // DIAG1 -_MAKE_MOTATE_PIN(kUnassigned2, 'A', 29); // NO PHYSICAL PIN -_MAKE_MOTATE_PIN(kInput1_PinNumber, 'A', 30); // -_MAKE_MOTATE_PIN(kInput4_PinNumber, 'A', 31); // - -_MAKE_MOTATE_PIN(kInput12_PinNumber, 'B', 0); // -_MAKE_MOTATE_PIN(kInput11_PinNumber, 'B', 1); // -_MAKE_MOTATE_PIN(kSocket1_SPISlaveSelectPinNumber, 'B', 2); // -_MAKE_MOTATE_PIN(kOutputSAFE_PinNumber, 'B', 3); // -//_MAKE_MOTATE_PIN( , 'B', 4); // TDI -//_MAKE_MOTATE_PIN( , 'B', 5); // TRACESDO -//_MAKE_MOTATE_PIN( , 'B', 6); // SWDIO -//_MAKE_MOTATE_PIN( , 'B', 7); // SWDCLK -//_MAKE_MOTATE_PIN( , 'B', 8); // XOUT -//_MAKE_MOTATE_PIN( , 'B', 9); // XIN -//_MAKE_MOTATE_PIN( , 'B', 10); // USB_D- -//_MAKE_MOTATE_PIN( , 'B', 11); // USB_D+ -//_MAKE_MOTATE_PIN( , 'B', 12); // ERASE -_MAKE_MOTATE_PIN(kLED_USBRXPinNumber, 'B', 13); // LED_1 (Heartbeat) - PWM2 -_MAKE_MOTATE_PIN(kSocket4_SPISlaveSelectPinNumber, 'B', 14); // NOT CONNECTED - - -//_MAKE_MOTATE_PIN( , 'D', 0); // USB_VBUS -_MAKE_MOTATE_PIN(kInput9_PinNumber, 'D', 1); // -_MAKE_MOTATE_PIN(kInput10_PinNumber, 'D', 2); // -_MAKE_MOTATE_PIN(kInput8_PinNumber, 'D', 3); // -_MAKE_MOTATE_PIN(kInput7_PinNumber, 'D', 4); // -_MAKE_MOTATE_PIN(kInput6_PinNumber, 'D', 5); // -_MAKE_MOTATE_PIN(kInput5_PinNumber, 'D', 6); // -_MAKE_MOTATE_PIN(kInput3_PinNumber, 'D', 7); // -_MAKE_MOTATE_PIN(kInput2_PinNumber, 'D', 8); // ] -_MAKE_MOTATE_PIN(kUnassigned3, 'D', 9); // DIAG0 -_MAKE_MOTATE_PIN(kUnassigned4, 'D', 10); // -_MAKE_MOTATE_PIN(kSocket5_StepPinNumber, 'D', 11); // -_MAKE_MOTATE_PIN(kSocket3_SPISlaveSelectPinNumber, 'D', 12); // -_MAKE_MOTATE_PIN(kSocket5_DirPinNumber, 'D', 13); // -_MAKE_MOTATE_PIN(kSocket5_EnablePinNumber, 'D', 14); // -_MAKE_MOTATE_PIN(kUnassigned5, 'D', 15); // -_MAKE_MOTATE_PIN(kSocket4_StepPinNumber, 'D', 16); // -_MAKE_MOTATE_PIN(kSocket4_DirPinNumber, 'D', 17); // -_MAKE_MOTATE_PIN(kSocket3_StepPinNumber, 'D', 18); // -_MAKE_MOTATE_PIN(kUnassigned6, 'D', 19); // -_MAKE_MOTATE_PIN(kSPI0_MISOPinNumber, 'D', 20); // -_MAKE_MOTATE_PIN(kSPI0_MOSIPinNumber, 'D', 21); // -_MAKE_MOTATE_PIN(kSPI0_SCKPinNumber, 'D', 22); // -_MAKE_MOTATE_PIN(kUnassigned7, 'D', 23); // NO PHYSICAL PIN -_MAKE_MOTATE_PIN(kSocket2_StepPinNumber, 'D', 24); // -_MAKE_MOTATE_PIN(kSocket2_SPISlaveSelectPinNumber, 'D', 25); // -_MAKE_MOTATE_PIN(kOutput9_PinNumber, 'D', 26); // PWM 2 -_MAKE_MOTATE_PIN(kSocket1_DirPinNumber, 'D', 27); // -_MAKE_MOTATE_PIN(kSocket4_EnablePinNumber, 'D', 28); // -_MAKE_MOTATE_PIN(kUnassigned8, 'D', 29); // NO PHYSICAL PIN -_MAKE_MOTATE_PIN(kUnassigned9, 'D', 30); // INTERRUPT_OUT -_MAKE_MOTATE_PIN(kUnassigned10, 'D', 31); // - + // Unused: + // + // + // + // + // + + _MAKE_MOTATE_PIN(kLED_RGBWPixelPinNumber, 'A', 0); // + _MAKE_MOTATE_PIN(kHeaterOutput1_PinNumber, 'A', 1); // TC 0,1 + _MAKE_MOTATE_PIN(kHeaterOutput2_PinNumber, 'A', 2); // PWM 0,1 + _MAKE_MOTATE_PIN(kI2C1_SDAPinNumber, 'A', 3); // + _MAKE_MOTATE_PIN(kI2C1_SCLPinNumber, 'A', 4); // + _MAKE_MOTATE_PIN(kHeaterOutput11_PinNumber, 'A', 5); // PWM 1,3 + _MAKE_MOTATE_PIN(kExternalClock1_PinNumber, 'A', 6); // CPU_CLK + _MAKE_MOTATE_PIN(kOutput7_PinNumber, 'A', 7); // PWM 0,3 + _MAKE_MOTATE_PIN(kSerial_RTSPinNumber, 'A', 8); // + _MAKE_MOTATE_PIN(kSerial_RXPinNumber, 'A', 9); // + _MAKE_MOTATE_PIN(kSerial_TXPinNumber, 'A', 10); // + _MAKE_MOTATE_PIN(kSocket2_EnablePinNumber, 'A', 11); // + _MAKE_MOTATE_PIN(kOutput6_PinNumber, 'A', 12); // PWM 1,0 + _MAKE_MOTATE_PIN(kOutput8_PinNumber, 'A', 13); // PWM 0,2 + _MAKE_MOTATE_PIN(kSocket1_StepPinNumber, 'A', 14); // + _MAKE_MOTATE_PIN(kOutput3_PinNumber, 'A', 15); // TC 1,0 + _MAKE_MOTATE_PIN(kOutput4_PinNumber, 'A', 16); // TC 1,1 + _MAKE_MOTATE_PIN(kADC2_Neg_PinNumber, 'A', 17); // AFEC0,6 + _MAKE_MOTATE_PIN(kADC2_Pos_PinNumber, 'A', 18); // AFEC0,7 + _MAKE_MOTATE_PIN(kADC1_Neg_PinNumber, 'A', 19); // AFEC0,8 + _MAKE_MOTATE_PIN(kADC1_Pos_PinNumber, 'A', 20); // AFEC0,9 + _MAKE_MOTATE_PIN(kSerial_CTSPinNumber, 'A', 21); // + _MAKE_MOTATE_PIN(kSocket1_EnablePinNumber, 'A', 22); // + //_MAKE_MOTATE_PIN(kOutput10_PinNumber, 'A', 23); // PWM 1,2 + _MAKE_MOTATE_PIN(kServo1_PinNumber, 'A', 23); // + _MAKE_MOTATE_PIN(kSocket3_EnablePinNumber, 'A', 24); // + _MAKE_MOTATE_PIN(kSocket2_DirPinNumber, 'A', 25); // + _MAKE_MOTATE_PIN(kOutput5_PinNumber, 'A', 26); // TC 2,0 + _MAKE_MOTATE_PIN(kSocket3_DirPinNumber, 'A', 27); // On Timer 2! + _MAKE_MOTATE_PIN(kUnassigned1, 'A', 28); // DIAG1 + _MAKE_MOTATE_PIN(kUnassigned2, 'A', 29); // NO PHYSICAL PIN + _MAKE_MOTATE_PIN(kInput1_PinNumber, 'A', 30); // + _MAKE_MOTATE_PIN(kInput4_PinNumber, 'A', 31); // + + _MAKE_MOTATE_PIN(kInput12_PinNumber, 'B', 0); // + _MAKE_MOTATE_PIN(kInput11_PinNumber, 'B', 1); // was kInput11_PinNumber + _MAKE_MOTATE_PIN(kSocket1_SPISlaveSelectPinNumber, 'B', 2); // + _MAKE_MOTATE_PIN(kOutputSAFE_PinNumber, 'B', 3); // + //_MAKE_MOTATE_PIN( , 'B', 4); // TDI + //_MAKE_MOTATE_PIN( , 'B', 5); // TRACESDO + //_MAKE_MOTATE_PIN( , 'B', 6); // SWDIO + //_MAKE_MOTATE_PIN( , 'B', 7); // SWDCLK + //_MAKE_MOTATE_PIN( , 'B', 8); // XOUT + //_MAKE_MOTATE_PIN( , 'B', 9); // XIN + //_MAKE_MOTATE_PIN( , 'B', 10); // USB_D- + //_MAKE_MOTATE_PIN( , 'B', 11); // USB_D+ + //_MAKE_MOTATE_PIN( , 'B', 12); // ERASE + _MAKE_MOTATE_PIN(kLED_USBRXPinNumber, 'B', 13); // LED_1 (Heartbeat) - PWM2 + _MAKE_MOTATE_PIN(kSocket4_SPISlaveSelectPinNumber, 'B', 14); // NOT CONNECTED + + + //_MAKE_MOTATE_PIN( 'D', 0); // USB_VBUS + _MAKE_MOTATE_PIN(kInput9_PinNumber, 'D', 1); // + _MAKE_MOTATE_PIN(kInput10_PinNumber, 'D', 2); // + _MAKE_MOTATE_PIN(kInput8_PinNumber, 'D', 3); // + _MAKE_MOTATE_PIN(kInput7_PinNumber, 'D', 4); // + _MAKE_MOTATE_PIN(kInput6_PinNumber, 'D', 5); // + _MAKE_MOTATE_PIN(kInput5_PinNumber, 'D', 6); // + _MAKE_MOTATE_PIN(kInput3_PinNumber, 'D', 7); // + _MAKE_MOTATE_PIN(kInput2_PinNumber, 'D', 8); // ] + _MAKE_MOTATE_PIN(kTMC2130_DIAG0_pinNumber, 'D', 9); // DIAG0 + _MAKE_MOTATE_PIN(kUnassigned4, 'D', 10); // + _MAKE_MOTATE_PIN(kSocket5_StepPinNumber, 'D', 11); // + _MAKE_MOTATE_PIN(kSocket3_SPISlaveSelectPinNumber, 'D', 12); // + _MAKE_MOTATE_PIN(kSocket5_DirPinNumber, 'D', 13); // + _MAKE_MOTATE_PIN(kSocket5_EnablePinNumber, 'D', 14); // + _MAKE_MOTATE_PIN(kUnassigned5, 'D', 15); // + _MAKE_MOTATE_PIN(kSocket4_StepPinNumber, 'D', 16); // + _MAKE_MOTATE_PIN(kSocket4_DirPinNumber, 'D', 17); // + _MAKE_MOTATE_PIN(kSocket3_StepPinNumber, 'D', 18); // + _MAKE_MOTATE_PIN(kUnassigned6, 'D', 19); // + _MAKE_MOTATE_PIN(kSPI0_MISOPinNumber, 'D', 20); // + _MAKE_MOTATE_PIN(kSPI0_MOSIPinNumber, 'D', 21); // + _MAKE_MOTATE_PIN(kSPI0_SCKPinNumber, 'D', 22); // + _MAKE_MOTATE_PIN(kUnassigned7, 'D', 23); // NO PHYSICAL PIN + _MAKE_MOTATE_PIN(kSocket2_StepPinNumber, 'D', 24); // + _MAKE_MOTATE_PIN(kSocket2_SPISlaveSelectPinNumber, 'D', 25); // + _MAKE_MOTATE_PIN(kOutput9_PinNumber, 'D', 26); // PWM 2 + _MAKE_MOTATE_PIN(kSocket1_DirPinNumber, 'D', 27); // + _MAKE_MOTATE_PIN(kSocket4_EnablePinNumber, 'D', 28); // + _MAKE_MOTATE_PIN(kUnassigned8, 'D', 29); // NO PHYSICAL PIN + _MAKE_MOTATE_PIN(kUnassigned9, 'D', 30); // INTERRUPT_OUT + _MAKE_MOTATE_PIN(kUnassigned10, 'D', 31); // + } // namespace Motate // We then allow each chip-type to have it's onw function definitions diff --git a/g2core/board/gquintic/gquintic-c-pinout.h b/g2core/board/gquintic/gquintic-c-pinout.h new file mode 100755 index 000000000..d1c1659c4 --- /dev/null +++ b/g2core/board/gquintic/gquintic-c-pinout.h @@ -0,0 +1,215 @@ +/* + * gquintic-c-pinout.h - board pinout specification + * This file is part of the g2core project + * + * Copyright (c) 2017 Robert Giseburt + * Copyright (c) 2017 Alden S. Hart Jr. + * + * This file is part of the Motate Library. + * + * This file ("the software") is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License, version 2 as published by the + * Free Software Foundation. You should have received a copy of the GNU General Public + * License, version 2 along with the software. If not, see . + * + * As a special exception, you may use this file as part of a software library without + * restriction. Specifically, if other files instantiate templates or use macros or + * inline functions from this file, or you compile this file and link it with other + * files to produce an executable, this file does not by itself cause the resulting + * executable to be covered by the GNU General Public License. This exception does not + * however invalidate any other reasons why the executable file might be covered by the + * GNU General Public License. + * + * THE SOFTWARE IS DISTRIBUTED IN THE HOPE THAT IT WILL BE USEFUL, BUT WITHOUT ANY + * WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES + * OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT + * SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF + * OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + * + */ + +#ifndef gquintic_a_pinout_h +#define gquintic_a_pinout_h + +/* + * USAGE NOTES + * + * Read this first: + * https://github.com/synthetos/g2/wiki/Adding-and-Revising-Boards + * + * USAGE: + * + * This file is lays out all the pin capabilities of the SAM3X8C organized by pin number. + * Each pin has its associated functions listed at the bottom of the file, and is essentially + * immutable for each processor. + * + * To use, assign Motate pin numbers to the first value in the _MAKE_MOTATE_PIN() macro. + * ALL PINS MUST BE ASSIGNED A NUMBER, even if they are not used. There will NOT be a + * code-size or speed penalty for unused pins, but the WILL be a compiler-failure for + * unassigned pins. This new restriction allows for simplification of linkages deep in + * Motate. + */ +/* See motate_pin_assignments.h for pin names to be used int he rest of the G2 code. + * EXAMPLES: + * + * *** Vanilla pin example *** + * + * _MAKE_MOTATE_PIN(4, A, 'A', 27); // SPI0_SCKPinNumber + * + * This assigns Motate pin 4 to Port A, pin 27 (A27) + * Look in motate_pin_assignments.h to see that this is kSPI_SCKPinNumber + * + * ** Other pin functions *** + * + * Please look in /platform/atmel_sam/motate_chip_pin_functions.h + */ + + +#include + +// We don't have all of the inputs, so we have to indicate as much: +#define INPUT1_AVAILABLE 1 +#define INPUT2_AVAILABLE 1 +#define INPUT3_AVAILABLE 1 +#define INPUT4_AVAILABLE 1 +#define INPUT5_AVAILABLE 1 +#define INPUT6_AVAILABLE 1 +#define INPUT7_AVAILABLE 1 +#define INPUT8_AVAILABLE 1 +#define INPUT9_AVAILABLE 1 +#define INPUT10_AVAILABLE 1 +#define INPUT11_AVAILABLE 0 +#define INPUT12_AVAILABLE 0 +#define INPUT13_AVAILABLE 0 + +#define XIO_HAS_USB 1 +#define XIO_HAS_UART 1 +#define XIO_HAS_SPI 0 +#define XIO_HAS_I2C 0 + +#define TEMPERATURE_OUTPUT_ON 1 // NO ADC yet + +// Some pins, if the PWM capability is turned on, it will cause timer conflicts. +// So we have to explicitly enable them as PWM pins. +// Generated with: +// perl -e 'for($i=1;$i<14;$i++) { print "#define OUTPUT${i}_PWM 0\n";}' +//#define OUTPUT1_PWM 1 // TC 0,1 - Fet 1 +//#define OUTPUT2_PWM 1 // PWM 0,1 - Fet 2 +#define OUTPUT1_PWM 0 // Used by EX1 +#define OUTPUT2_PWM 0 // Used by EX2 +#define OUTPUT3_PWM 1 // TC 1,0 - Fan 1 +#define OUTPUT4_PWM 1 // TC 1,1 - Fan 2 +#define OUTPUT5_PWM 1 // TC 2,0 - Fan 3 +#define OUTPUT6_PWM 1 // PWM 1,0 +#define OUTPUT7_PWM 1 // PWM 0,3 +#define OUTPUT8_PWM 1 // PWM 0,2 +#define OUTPUT9_PWM 0 // PWM 0,2 +#define OUTPUT10_PWM 1 // PWM 1,2 +#define OUTPUT11_PWM 0 // Used by Heatbed +//#define OUTPUT11_PWM 1 // PWM 1,3 - Fet 3 +#define OUTPUT12_PWM 0 // Unused +#define OUTPUT13_PWM 0 // Unused + +namespace Motate { + +// Unused: +// +// +// +// +// + +_MAKE_MOTATE_PIN(kLED_RGBWPixelPinNumber, 'A', 0); // +_MAKE_MOTATE_PIN(kHeaterOutput1_PinNumber, 'A', 1); // TC 0,1 +_MAKE_MOTATE_PIN(kHeaterOutput2_PinNumber, 'A', 2); // PWM 0,1 +_MAKE_MOTATE_PIN(kI2C1_SDAPinNumber, 'A', 3); // +_MAKE_MOTATE_PIN(kI2C1_SCLPinNumber, 'A', 4); // +_MAKE_MOTATE_PIN(kHeaterOutput11_PinNumber, 'A', 5); // PWM 1,3 +_MAKE_MOTATE_PIN(kExternalClock1_PinNumber, 'A', 6); // CPU_CLK +_MAKE_MOTATE_PIN(kOutput7_PinNumber, 'A', 7); // PWM 0,3 +_MAKE_MOTATE_PIN(kSerial_RTSPinNumber, 'A', 8); // +_MAKE_MOTATE_PIN(kSerial_RXPinNumber, 'A', 9); // +_MAKE_MOTATE_PIN(kSerial_TXPinNumber, 'A', 10); // +_MAKE_MOTATE_PIN(kSocket2_EnablePinNumber, 'A', 11); // +_MAKE_MOTATE_PIN(kOutput6_PinNumber, 'A', 12); // PWM 1,0 +_MAKE_MOTATE_PIN(kOutput8_PinNumber, 'A', 13); // PWM 0,2 +_MAKE_MOTATE_PIN(kSocket1_StepPinNumber, 'A', 14); // +_MAKE_MOTATE_PIN(kOutput3_PinNumber, 'A', 15); // TC 1,0 +_MAKE_MOTATE_PIN(kOutput4_PinNumber, 'A', 16); // TC 1,1 +_MAKE_MOTATE_PIN(kADC2_Neg_PinNumber, 'A', 17); // AFEC0,6 +_MAKE_MOTATE_PIN(kADC2_Pos_PinNumber, 'A', 18); // AFEC0,7 +_MAKE_MOTATE_PIN(kADC1_Neg_PinNumber, 'A', 19); // AFEC0,8 +_MAKE_MOTATE_PIN(kADC1_Pos_PinNumber, 'A', 20); // AFEC0,9 +_MAKE_MOTATE_PIN(kADC3_Pos_PinNumber, 'A', 21); // AFEC0,1 +_MAKE_MOTATE_PIN(kSocket1_EnablePinNumber, 'A', 22); // +//_MAKE_MOTATE_PIN(kOutput10_PinNumber, 'A', 23); // PWM 1,2 +_MAKE_MOTATE_PIN(kServo1_PinNumber, 'A', 23); // +_MAKE_MOTATE_PIN(kSocket3_EnablePinNumber, 'A', 24); // +_MAKE_MOTATE_PIN(kSocket2_DirPinNumber, 'A', 25); // +_MAKE_MOTATE_PIN(kOutput5_PinNumber, 'A', 26); // TC 2,0 +_MAKE_MOTATE_PIN(kSocket3_DirPinNumber, 'A', 27); // On Timer 2! +_MAKE_MOTATE_PIN(kUnassigned1, 'A', 28); // DIAG1 +_MAKE_MOTATE_PIN(kUnassigned2, 'A', 29); // NO PHYSICAL PIN +_MAKE_MOTATE_PIN(kInput1_PinNumber, 'A', 30); // +_MAKE_MOTATE_PIN(kInput4_PinNumber, 'A', 31); // + +_MAKE_MOTATE_PIN(kSerial_CTSPinNumber, 'B', 0); // +_MAKE_MOTATE_PIN(kUnassigned9, 'B', 1); // AFEC1,0 - was kADC3_Neg_PinNumber, now INTERRUPT_OUT +_MAKE_MOTATE_PIN(kSocket1_SPISlaveSelectPinNumber, 'B', 2); // +_MAKE_MOTATE_PIN(kOutputSAFE_PinNumber, 'B', 3); // +//_MAKE_MOTATE_PIN( , 'B', 4); // TDI +//_MAKE_MOTATE_PIN( , 'B', 5); // TRACESDO +//_MAKE_MOTATE_PIN( , 'B', 6); // SWDIO +//_MAKE_MOTATE_PIN( , 'B', 7); // SWDCLK +//_MAKE_MOTATE_PIN( , 'B', 8); // XOUT +//_MAKE_MOTATE_PIN( , 'B', 9); // XIN +//_MAKE_MOTATE_PIN( , 'B', 10); // USB_D- +//_MAKE_MOTATE_PIN( , 'B', 11); // USB_D+ +//_MAKE_MOTATE_PIN( , 'B', 12); // ERASE +_MAKE_MOTATE_PIN(kLED_USBRXPinNumber, 'B', 13); // LED_1 (Heartbeat) - PWM2 +_MAKE_MOTATE_PIN(kSocket4_SPISlaveSelectPinNumber, 'B', 14); // NOT CONNECTED + + +//_MAKE_MOTATE_PIN( 'D', 0); // USB_VBUS +_MAKE_MOTATE_PIN(kInput9_PinNumber, 'D', 1); // +_MAKE_MOTATE_PIN(kInput10_PinNumber, 'D', 2); // +_MAKE_MOTATE_PIN(kInput8_PinNumber, 'D', 3); // +_MAKE_MOTATE_PIN(kInput7_PinNumber, 'D', 4); // +_MAKE_MOTATE_PIN(kInput6_PinNumber, 'D', 5); // +_MAKE_MOTATE_PIN(kInput5_PinNumber, 'D', 6); // +_MAKE_MOTATE_PIN(kInput3_PinNumber, 'D', 7); // +_MAKE_MOTATE_PIN(kInput2_PinNumber, 'D', 8); // ] +_MAKE_MOTATE_PIN(kTMC2130_DIAG0_pinNumber, 'D', 9); // DIAG0 +_MAKE_MOTATE_PIN(kUnassigned4, 'D', 10); // +_MAKE_MOTATE_PIN(kSocket5_StepPinNumber, 'D', 11); // +_MAKE_MOTATE_PIN(kSocket3_SPISlaveSelectPinNumber, 'D', 12); // +_MAKE_MOTATE_PIN(kSocket5_DirPinNumber, 'D', 13); // +_MAKE_MOTATE_PIN(kSocket5_EnablePinNumber, 'D', 14); // +_MAKE_MOTATE_PIN(kUnassigned5, 'D', 15); // +_MAKE_MOTATE_PIN(kSocket4_StepPinNumber, 'D', 16); // +_MAKE_MOTATE_PIN(kSocket4_DirPinNumber, 'D', 17); // +_MAKE_MOTATE_PIN(kSocket3_StepPinNumber, 'D', 18); // +_MAKE_MOTATE_PIN(kUnassigned6, 'D', 19); // +_MAKE_MOTATE_PIN(kSPI0_MISOPinNumber, 'D', 20); // +_MAKE_MOTATE_PIN(kSPI0_MOSIPinNumber, 'D', 21); // +_MAKE_MOTATE_PIN(kSPI0_SCKPinNumber, 'D', 22); // +_MAKE_MOTATE_PIN(kUnassigned7, 'D', 23); // NO PHYSICAL PIN +_MAKE_MOTATE_PIN(kSocket2_StepPinNumber, 'D', 24); // +_MAKE_MOTATE_PIN(kSocket2_SPISlaveSelectPinNumber, 'D', 25); // +_MAKE_MOTATE_PIN(kOutput9_PinNumber, 'D', 26); // PWM 2 +_MAKE_MOTATE_PIN(kSocket1_DirPinNumber, 'D', 27); // +_MAKE_MOTATE_PIN(kSocket4_EnablePinNumber, 'D', 28); // +_MAKE_MOTATE_PIN(kUnassigned8, 'D', 29); // NO PHYSICAL PIN +_MAKE_MOTATE_PIN(kADC3_Neg_PinNumber, 'D', 30); // AFEC0,0 - was INTERRUPT_OUT +_MAKE_MOTATE_PIN(kUnassigned10, 'D', 31); // + +} // namespace Motate + +// We then allow each chip-type to have it's onw function definitions +// that will refer to these pin assignments. +#include "motate_chip_pin_functions.h" + +#endif + +// gquintic_a_pinout_h diff --git a/g2core/boards.mk b/g2core/boards.mk index 9ab08c26d..d5ce82397 100644 --- a/g2core/boards.mk +++ b/g2core/boards.mk @@ -71,13 +71,20 @@ ifeq ("$(CONFIG)","TestV9") SETTINGS_FILE="settings_test.h" endif -ifeq ("$(CONFIG)","TestQuintic") +ifeq ("$(CONFIG)","TestQuintic-b") ifeq ("$(BOARD)","NONE") BOARD=gquintic-b endif SETTINGS_FILE="settings_test.h" endif +ifeq ("$(CONFIG)","TestQuintic") + ifeq ("$(BOARD)","NONE") + BOARD=gquintic-c + endif + SETTINGS_FILE="settings_test.h" +endif + ifeq ("$(CONFIG)","TestQuadratic") ifeq ("$(BOARD)","NONE") @@ -133,7 +140,7 @@ endif ifeq ("$(CONFIG)","Ultimaker2Plus") ifeq ("$(BOARD)","NONE") - BOARD=gquintic-b + BOARD=gquintic-c endif SETTINGS_FILE="settings_Ultimaker_2_Plus.h" endif From 6c1144410dc5a7bc39561e6032582262153479ab Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Tue, 16 May 2017 15:59:50 -0500 Subject: [PATCH 104/193] Corrections in GDB configs for use with SAM-ICE --- g2core/board/g2_default.gdb | 14 ++++---- .../board/gquintic/motate_pin_assignments.h | 34 +++++++------------ g2core/board/printrboardg2.gdb | 4 ++- 3 files changed, 23 insertions(+), 29 deletions(-) diff --git a/g2core/board/g2_default.gdb b/g2core/board/g2_default.gdb index f7e7e2282..4f5064525 100644 --- a/g2core/board/g2_default.gdb +++ b/g2core/board/g2_default.gdb @@ -10,13 +10,13 @@ set print pretty on # monitor adapter_khz 5000 -define reset - boot_from_flash - # for openocd - # monitor reset init - # for jlink - monitor reset -end +#define reset +# boot_from_flash +# # for openocd +# # monitor reset init +# # for jlink +# monitor reset +#end define flash make diff --git a/g2core/board/gquintic/motate_pin_assignments.h b/g2core/board/gquintic/motate_pin_assignments.h index ab6849e66..293ae1ec6 100755 --- a/g2core/board/gquintic/motate_pin_assignments.h +++ b/g2core/board/gquintic/motate_pin_assignments.h @@ -137,12 +137,13 @@ pin_number kInput4_PinNumber = 103; pin_number kInput5_PinNumber = 104; pin_number kInput6_PinNumber = 105; -pin_number kInput7_PinNumber = 106; -pin_number kInput8_PinNumber = 107; -pin_number kInput9_PinNumber = 108; -pin_number kInput10_PinNumber = 109; -pin_number kInput11_PinNumber = 110; -pin_number kInput12_PinNumber = 111; +pin_number kInput7_PinNumber = 106; +pin_number kInput8_PinNumber = 107; +pin_number kInput9_PinNumber = 108; +pin_number kInput10_PinNumber = 109; +pin_number kInput11_PinNumber = 110; +pin_number kInput12_PinNumber = -1; +pin_number kTMC2130_DIAG0_pinNumber = 111; // START DEBUG PINS - Convenient pins to hijack for hardware debugging // To reuse a pin for debug change the original pin number to -1 @@ -201,21 +202,12 @@ pin_number kOutput14_PinNumber = -1; // 143; pin_number kOutput15_PinNumber = -1; // 144; pin_number kOutput16_PinNumber = -1; // 145; -pin_number kADC1_PinNumber = 150; // Heated bed thermistor ADC -pin_number kADC2_PinNumber = 151; // Extruder1_ADC -pin_number kADC3_PinNumber = 152; // Extruder2_ADC -pin_number kADC4_PinNumber = 153; // Aux ADC -pin_number kADC5_PinNumber = 154; // Not physically pinned out -pin_number kADC6_PinNumber = 155; // Not physically pinned out -pin_number kADC7_PinNumber = 156; // Not physically pinned out -pin_number kADC8_PinNumber = 157; // Not physically pinned out -pin_number kADC9_PinNumber = 158; // Not physically pinned out -pin_number kADC10_PinNumber = 159; // Not physically pinned out -pin_number kADC11_PinNumber = 160; // Not physically pinned out -pin_number kADC12_PinNumber = 161; // Not physically pinned out -pin_number kADC13_PinNumber = 162; // Not physically pinned out -pin_number kADC14_PinNumber = 163; // Not physically pinned out -pin_number kADC15_PinNumber = 164; // Not physically pinned out +pin_number kADC1_Pos_PinNumber = 150; // Extruder1_ADC +pin_number kADC1_Neg_PinNumber = 151; // Extruder1_ADC +pin_number kADC2_Pos_PinNumber = 152; // Extruder2_ADC +pin_number kADC2_Neg_PinNumber = 153; // Extruder2_ADC +pin_number kADC3_Pos_PinNumber = 154; // Heated bed thermistor ADC +pin_number kADC3_Neg_PinNumber = 155; // Heated bed thermistor ADC pin_number kExternalClock1_PinNumber = 170; // External pins for exporting a clock signal (for Trinamics) diff --git a/g2core/board/printrboardg2.gdb b/g2core/board/printrboardg2.gdb index 95fbe7ff4..53b0d8f15 100644 --- a/g2core/board/printrboardg2.gdb +++ b/g2core/board/printrboardg2.gdb @@ -1,5 +1,7 @@ # Open and connect to openocd with the ATMEL-ICE -target remote | /usr/local/bin/openocd -c "set CHIPNAME ${CHIP}" -f ${MOTATE_PATH}/openocd.cfg -f ${MOTATE_PATH}/platform/atmel_sam/atmel_sam.cfg -c "gdb_port pipe; log_output openocd.log" +#target remote | /usr/local/bin/openocd -c "set CHIPNAME ${CHIP}" -f ${MOTATE_PATH}/openocd.cfg -f ${MOTATE_PATH}/platform/atmel_sam/atmel_sam.cfg -c "gdb_port pipe; log_output openocd.log" + +target extended-remote :2331 source ./board/g2_default.gdb From 8599d082429b88d47364a4da75f64a264f5455f2 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Tue, 16 May 2017 16:02:57 -0500 Subject: [PATCH 105/193] Added formal USING_A_MAX31865 define to allow disabling Motor_1 cleanly --- g2core/board/gquintic/board_stepper.cpp | 46 ++++++++++++++++----- g2core/board/gquintic/board_stepper.h | 34 ++++++++++++--- g2core/board/gquintic/hardware.h | 15 +++++-- g2core/settings/settings_Ultimaker_2_Plus.h | 2 + 4 files changed, 77 insertions(+), 20 deletions(-) diff --git a/g2core/board/gquintic/board_stepper.cpp b/g2core/board/gquintic/board_stepper.cpp index e8a202fce..06028948d 100755 --- a/g2core/board/gquintic/board_stepper.cpp +++ b/g2core/board/gquintic/board_stepper.cpp @@ -29,36 +29,60 @@ #include "board_stepper.h" // These are identical to board_stepper.h, except for the word "extern" and the initialization -//Trinamic2130 -// motor_1{spiBus, spiCSPinMux.getCS(4)}; +#if defined(USING_A_MAX31865) && USING_A_MAX31865 == 1 HOT_DATA Trinamic2130 - motor_1{spiBus, spiCSPinMux.getCS(3)}; + motor_1 {spiBus, spiCSPinMux.getCS(3)}; HOT_DATA Trinamic2130 - motor_2{spiBus, spiCSPinMux.getCS(2)}; + motor_2 {spiBus, spiCSPinMux.getCS(2)}; HOT_DATA Trinamic2130 - motor_3{spiBus, spiCSPinMux.getCS(1)}; + motor_3 {spiBus, spiCSPinMux.getCS(1)}; HOT_DATA Trinamic2130 - motor_4{spiBus, spiCSPinMux.getCS(0)}; - + motor_4 {spiBus, spiCSPinMux.getCS(0)}; HOT_DATA StepDirHobbyServo motor_5; Stepper* Motors[MOTORS] = {&motor_1, &motor_2, &motor_3, &motor_4, &motor_5}; -//Stepper* Motors[MOTORS] = {&motor_1, &motor_2, &motor_3, &motor_4, &motor_5, &motor_6}; +#else +HOT_DATA Trinamic2130 + motor_1 {spiBus, spiCSPinMux.getCS(4)}; +HOT_DATA Trinamic2130 + motor_2 {spiBus, spiCSPinMux.getCS(3)}; +HOT_DATA Trinamic2130 + motor_3 {spiBus, spiCSPinMux.getCS(2)}; +HOT_DATA Trinamic2130 + motor_4 {spiBus, spiCSPinMux.getCS(1)}; +HOT_DATA Trinamic2130 + motor_5 {spiBus, spiCSPinMux.getCS(0)}; +HOT_DATA StepDirHobbyServo motor_6; + +Stepper* Motors[MOTORS] = {&motor_1, &motor_2, &motor_3, &motor_4, &motor_5, &motor_6}; +#endif void board_stepper_init() { for (uint8_t motor = 0; motor < MOTORS; motor++) { Motors[motor]->init(); } diff --git a/g2core/board/gquintic/board_stepper.h b/g2core/board/gquintic/board_stepper.h index e8eac9d68..056bccc07 100755 --- a/g2core/board/gquintic/board_stepper.h +++ b/g2core/board/gquintic/board_stepper.h @@ -33,11 +33,7 @@ #include "step_dir_hobbyservo.h" // These are identical to board_stepper.h, except for the word "extern" and the initialization -//extern Trinamic2130 -// motor_1; +#if defined(USING_A_MAX31865) && USING_A_MAX31865 == 1 extern Trinamic2130 motor_4; extern StepDirHobbyServo motor_5; +#else +extern Trinamic2130 + motor_1; +extern Trinamic2130 + motor_2; +extern Trinamic2130 + motor_3; +extern Trinamic2130 + motor_4; +extern Trinamic2130 + motor_5; +extern StepDirHobbyServo motor_6; +#endif extern Stepper* Motors[MOTORS]; diff --git a/g2core/board/gquintic/hardware.h b/g2core/board/gquintic/hardware.h index d01953cb2..349818f9a 100644 --- a/g2core/board/gquintic/hardware.h +++ b/g2core/board/gquintic/hardware.h @@ -29,6 +29,7 @@ */ #include "config.h" +#include "settings.h" #include "error.h" #ifndef HARDWARE_H_ONCE @@ -58,7 +59,11 @@ enum hwPlatform { #define AXES 6 // number of axes supported in this version #define HOMING_AXES 4 // number of axes that can be homed (assumes Zxyabc sequence) -#define MOTORS 5 // number of motors on the board - 5 Trinamics + 1 servo +#if defined(USING_A_MAX31865) && USING_A_MAX31865 == 1 +#define MOTORS 5 // number of motors on the board - 4 Trinamics + 1 servo +#else +#define MOTORS 6 // number of motors on the board - 5 Trinamics + 1 servo +#endif #define COORDS 6 // number of supported coordinate systems (index starts at 1) #define PWMS 2 // number of supported PWM channels #define TOOLS 32 // number of entries in tool table (index starts at 1) @@ -67,8 +72,10 @@ enum hwPlatform { #define MOTOR_2_IS_TRINAMIC #define MOTOR_3_IS_TRINAMIC #define MOTOR_4_IS_TRINAMIC -//#define MOTOR_5_IS_TRINAMIC - +#if defined(USING_A_MAX31865) && USING_A_MAX31865 == 1 +#else +#define MOTOR_5_IS_TRINAMIC +#endif //////////////////////////// /////// ARM VERSION //////// //////////////////////////// @@ -129,7 +136,7 @@ using Motate::OutputPin; #define FREQUENCY_DDA 400000UL // Hz step frequency. Interrupts actually fire at 2x (300 KHz) #define FREQUENCY_DWELL 1000UL -#define MIN_SEGMENT_MS ((float)0.25) // S70 can handle much much smaller segements +#define MIN_SEGMENT_MS ((float)0.125) // S70 can handle much much smaller segements #define PLANNER_BUFFER_POOL_SIZE (60) diff --git a/g2core/settings/settings_Ultimaker_2_Plus.h b/g2core/settings/settings_Ultimaker_2_Plus.h index 3c6ccde0a..85b36a6a9 100644 --- a/g2core/settings/settings_Ultimaker_2_Plus.h +++ b/g2core/settings/settings_Ultimaker_2_Plus.h @@ -299,6 +299,8 @@ #include "device/max31865/max31865.h" +#define USING_A_MAX31865 1 + #define HAS_TEMPERATURE_SENSOR_1 true #if HAS_TEMPERATURE_SENSOR_1 // Must choose Thermistor or PT100 From 9d450c7b96cf111b0ba7f530bfe627742d6e2b46 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Tue, 16 May 2017 16:03:42 -0500 Subject: [PATCH 106/193] Ultimaker 2+ settings update --- g2core/settings/settings_Ultimaker_2_Plus.h | 139 +++++++++++++------- 1 file changed, 92 insertions(+), 47 deletions(-) diff --git a/g2core/settings/settings_Ultimaker_2_Plus.h b/g2core/settings/settings_Ultimaker_2_Plus.h index 85b36a6a9..7cca54a96 100644 --- a/g2core/settings/settings_Ultimaker_2_Plus.h +++ b/g2core/settings/settings_Ultimaker_2_Plus.h @@ -39,8 +39,8 @@ //**** GLOBAL / GENERAL SETTINGS ****************************************************** -#define JUNCTION_INTEGRATION_TIME 1.0 // cornering - between 0.10 and 2.00 (higher is faster) -//{jt:1.0} +#define JUNCTION_INTEGRATION_TIME 1.2 // cornering - between 0.10 and 2.00 (higher is faster) +//{jt:1.2} //{jt:0.75} #define CHORDAL_TOLERANCE 0.01 // chordal accuracy for arc drawing (in mm) @@ -85,8 +85,8 @@ //#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","he1t","he1st","he1at","he1op","pid1p","pid1i","pid1d","feed","vel","unit","path","stat" // Defaults for thermistor tuning -#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","he1t","he1st","he1at","he1tr","he1tv","he1op","he2t","he2st","he2at","he2tr","he2tv","he2op","he3t","he3st","he3at","he3tr","he3tv","he3op","feed","vel","unit","path","stat","1ts","2ts","1sgr","1sgs","2sgr","2sgs","_xs1","_xs2","_xs3","_xs4" -//{sr:{"line":t,"posx":t,"posy":t,"posz":t,"posa":t,"he1t":t,"he1st":t,"he1at":t,"he1tr":t,"he1tv":t,"he1op":t,"he3t":t,"he3st":t,"he3at":t,"he3tr":t,"he3tv":t,"he3op":t,"feed":t,"vel":t,"unit":t,"path":t,"stat":t}} +//#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","he1t","he1st","he1at","he1op","he3t","he3st","he3at","he3op","feed","vel","unit","path","stat","1ts","1sgr","1csa","2ts","2sgr","2csa","3ts","3sgr","3csa","4ts","4sgr","4csa" +#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","he1t","he1st","he1at","he1tr","he1tv","he1op","he2t","he2st","he2at","he2tr","he2tv","he2op","he3t","he3st","he3at","he3tr","he3tv","he3op","feed","vel","unit","path","stat","_xs1","_xs2","_xs3","_xs4" // Gcode startup defaults #define GCODE_DEFAULT_UNITS MILLIMETERS // MILLIMETERS or INCHES #define GCODE_DEFAULT_PLANE CANON_PLANE_XY // CANON_PLANE_XY, CANON_PLANE_XZ, or CANON_PLANE_YZ @@ -105,14 +105,23 @@ #define M1_STEP_ANGLE 1.8 // 1sa // Marlin says 80 steps/unit, and 16 microsteps, with a 200-step/rev motor #define M1_TRAVEL_PER_REV 40 // 1tr -#define M1_MICROSTEPS 128 // 1mi 1,2,4,8,16,32 +#define M1_MICROSTEPS 128 // 1mi 1,2,4,8,16,32 #define M1_POLARITY 0 // 1po 0=normal, 1=reversed #define M1_POWER_MODE MOTOR_POWERED_IN_CYCLE // 1pm standard -#define M1_POWER_LEVEL 0.5 // 1pl -#define M1_TMC2130_TPWMTHRS 500 // 1pth -#define M1_TMC2130_TCOOLTHRS 200 // 1cth -#define M1_TMC2130_THIGH 100 // 1hth +#define M1_POWER_LEVEL 0.8 // 1pl +#define M1_TMC2130_TPWMTHRS 1200 // 1pth +#define M1_TMC2130_TCOOLTHRS 1000 // 1cth +#define M1_TMC2130_THIGH 10 // 1hth #define M1_TMC2130_SGT 4 // 1sgt +#define M1_TMC2130_TBL 2 // 1tbl +#define M1_TMC2130_PWM_GRAD 1 // 1pgrd +#define M1_TMC2130_PWM_AMPL 200 // 1pamp +#define M1_TMC2130_HEND 0 // 1hend +#define M1_TMC2130_HSTRT 0 // 1hsrt +#define M1_TMC2130_SMIN 5 // 1smin +#define M1_TMC2130_SMAX 12 // 1smax +#define M1_TMC2130_SUP 2 // 1sup +#define M1_TMC2130_SDN 1 // 1sdn // 80 steps/mm at 1/16 microstepping = 40 mm/rev #define M2_MOTOR_MAP AXIS_Y @@ -122,11 +131,20 @@ #define M2_MICROSTEPS 128 #define M2_POLARITY 1 #define M2_POWER_MODE MOTOR_POWERED_IN_CYCLE -#define M2_POWER_LEVEL 0.5 -#define M2_TMC2130_TPWMTHRS 500 -#define M2_TMC2130_TCOOLTHRS 200 -#define M2_TMC2130_THIGH 100 +#define M2_POWER_LEVEL 0.8 +#define M2_TMC2130_TPWMTHRS 1200 +#define M2_TMC2130_TCOOLTHRS 1000 +#define M2_TMC2130_THIGH 10 #define M2_TMC2130_SGT 4 +#define M2_TMC2130_TBL 2 +#define M2_TMC2130_PWM_GRAD 1 +#define M2_TMC2130_PWM_AMPL 200 +#define M2_TMC2130_HEND 0 +#define M2_TMC2130_HSTRT 0 +#define M2_TMC2130_SMIN 5 +#define M2_TMC2130_SMAX 12 +#define M2_TMC2130_SUP 2 +#define M2_TMC2130_SDN 1 #define M3_MOTOR_MAP AXIS_Z #define M3_STEP_ANGLE 1.8 @@ -135,11 +153,20 @@ #define M3_MICROSTEPS 128 #define M3_POLARITY 0 #define M3_POWER_MODE MOTOR_POWERED_IN_CYCLE -#define M3_POWER_LEVEL 0.5 -#define M3_TMC2130_TPWMTHRS 500 +#define M3_POWER_LEVEL 0.4 +#define M3_TMC2130_TPWMTHRS 300 #define M3_TMC2130_TCOOLTHRS 200 -#define M3_TMC2130_THIGH 100 +#define M3_TMC2130_THIGH 10 #define M3_TMC2130_SGT 4 +#define M3_TMC2130_TBL 2 +#define M3_TMC2130_PWM_GRAD 1 +#define M3_TMC2130_PWM_AMPL 200 +#define M3_TMC2130_HEND 0 +#define M3_TMC2130_HSTRT 0 +#define M3_TMC2130_SMIN 5 +#define M3_TMC2130_SMAX 12 +#define M3_TMC2130_SUP 2 +#define M3_TMC2130_SDN 2 #define M4_MOTOR_MAP AXIS_A #define M4_STEP_ANGLE 1.8 @@ -147,23 +174,41 @@ #define M4_MICROSTEPS 128 #define M4_POLARITY 0 #define M4_POWER_MODE MOTOR_POWER_MODE -#define M4_POWER_LEVEL 0.6 -#define M4_TMC2130_TPWMTHRS 500 -#define M4_TMC2130_TCOOLTHRS 200 -#define M4_TMC2130_THIGH 100 -#define M4_TMC2130_SGT 4 +#define M4_POWER_LEVEL 0.8 +#define M4_TMC2130_TPWMTHRS 180000 +#define M4_TMC2130_TCOOLTHRS 100000 +#define M4_TMC2130_THIGH 10 +#define M4_TMC2130_SGT 3 +#define M4_TMC2130_TBL 2 +#define M4_TMC2130_PWM_GRAD 15 +#define M4_TMC2130_PWM_AMPL 255 +#define M4_TMC2130_HEND 0 +#define M4_TMC2130_HSTRT 0 +#define M4_TMC2130_SMIN 5 +#define M4_TMC2130_SMAX 10 +#define M4_TMC2130_SUP 3 +#define M4_TMC2130_SDN 0 #define M5_MOTOR_MAP AXIS_B #define M5_STEP_ANGLE 1.8 -#define M5_TRAVEL_PER_REV 360 // degrees moved per motor rev -#define M5_MICROSTEPS 64 -#define M5_POLARITY 0 -#define M5_POWER_MODE MOTOR_POWER_MODE +#define M5_TRAVEL_PER_REV 40 +#define M5_MICROSTEPS 128 +#define M5_POLARITY 1 +#define M5_POWER_MODE MOTOR_DISABLED #define M5_POWER_LEVEL 0.8 -#define M5_TMC2130_TPWMTHRS 500 -#define M5_TMC2130_TCOOLTHRS 200 -#define M5_TMC2130_THIGH 100 +#define M5_TMC2130_TPWMTHRS 1200 +#define M5_TMC2130_TCOOLTHRS 1000 +#define M5_TMC2130_THIGH 10 #define M5_TMC2130_SGT 4 +#define M5_TMC2130_TBL 2 +#define M5_TMC2130_PWM_GRAD 1 +#define M5_TMC2130_PWM_AMPL 200 +#define M5_TMC2130_HEND 0 +#define M5_TMC2130_HSTRT 0 +#define M5_TMC2130_SMIN 5 +#define M5_TMC2130_SMAX 12 +#define M5_TMC2130_SUP 2 +#define M5_TMC2130_SDN 1 // *** axis settings ********************************************************************************** @@ -212,9 +257,9 @@ #define Z_LATCH_BACKOFF 5 #define Z_ZERO_BACKOFF 0 -//#define G55_Z_OFFSET 0.3 // higher number is farther away from the bed +#define G55_Z_OFFSET 0.3 // higher number is farther away from the bed // {g55z:0.3} -#define G55_Z_OFFSET 0.25 // higher number is farther away from the bed +//#define G55_Z_OFFSET 0.25 // higher number is farther away from the bed // {g55z:0.25} // Rotary values are chosen to make the motor react the same as X for testing @@ -245,8 +290,8 @@ //#define A_FEEDRATE_MAX 36110.8 // ~15 mm/s //#define A_FEEDRATE_MAX 24073.9 // ~10 mm/s //#define A_FEEDRATE_MAX 12036.95 // ~5 mm/s -#define A_FEEDRATE_MAX 6018.475 // ~2.5 mm/s Testing: {afr:800} -//#define A_FEEDRATE_MAX 1000.0 // ~0.415 mm/s +//#define A_FEEDRATE_MAX 6018.475 // ~2.5 mm/s Testing: {afr:800} +#define A_FEEDRATE_MAX 1000.0 // ~0.415 mm/s //#define A_FEEDRATE_MAX 800.0 // WORKS WELL //#define A_FEEDRATE_MAX 500.0 // ~0.2075 mm/s #define A_TRAVEL_MIN 0 @@ -311,10 +356,10 @@ /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ } #else - #define TEMPERATURE_SENSOR_1_TYPE PT100> - #define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 2200, /*inline_resistance*/0.0, /*differential*/ true} -// #define TEMPERATURE_SENSOR_1_TYPE PT100> -// #define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 430, /*inline_resistance*/0, spiBus, spiCSPinMux.getCS(5)} + // #define TEMPERATURE_SENSOR_1_TYPE PT100> + // #define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 2000, /*inline_resistance*/0.0} + #define TEMPERATURE_SENSOR_1_TYPE PT100> + #define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 430, /*inline_resistance*/0, spiBus, spiCSPinMux.getCS(5)} #endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_1 @@ -330,10 +375,10 @@ /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ } #else -// #define TEMPERATURE_SENSOR_2_TYPE PT100> -// #define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 2200, /*inline_resistance*/0.0, /*differential*/ true} - #define TEMPERATURE_SENSOR_2_TYPE PT100> - #define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 430, /*inline_resistance*/0, spiBus, spiCSPinMux.getCS(5)} + #define TEMPERATURE_SENSOR_2_TYPE PT100> + #define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 200, /*inline_resistance*/0.0} +// #define TEMPERATURE_SENSOR_2_TYPE PT100> +// #define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 430, /*inline_resistance*/0, spiBus, spiCSPinMux.getCS(5)} #endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_2 @@ -348,10 +393,10 @@ /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ } #else -// #define TEMPERATURE_SENSOR_3_TYPE PT100> -// #define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 2200, /*inline_resistance*/0.003, /*differential*/ true} - #define TEMPERATURE_SENSOR_3_TYPE PT100> - #define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 430, /*inline_resistance*/0, spiBus, spiCSPinMux.getCS(6)} + // #define TEMPERATURE_SENSOR_3_TYPE PT100> + // #define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 200, /*inline_resistance*/0.0} + #define TEMPERATURE_SENSOR_3_TYPE PT100> + #define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 430, /*inline_resistance*/0, spiBus, spiCSPinMux.getCS(6)} #endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_3 @@ -463,7 +508,7 @@ // PID debug string: {sr:{"he1t":t,"he1st":t,"pid1p":t, "pid1i":t, "pid1d":t, "pid1f":t, "he1op":t, "line":t, "stat":t}} #define H1_DEFAULT_ENABLE true -#define H1_DEFAULT_P 1 +#define H1_DEFAULT_P 2 #define H1_DEFAULT_I 0.005 #define H1_DEFAULT_D 500 #define H1_DEFAULT_F 0.0015 @@ -485,5 +530,5 @@ #define H3_DEFAULT_ENABLE true #define H3_DEFAULT_P 9.0 #define H3_DEFAULT_I 0.012 -#define H3_DEFAULT_D 100 -#define H3_DEFAULT_F 0.0 +#define H3_DEFAULT_D 50 +#define H3_DEFAULT_F 0.0015 From 64c3056f0b59562730271425e8bb262304225cd6 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Tue, 16 May 2017 16:04:31 -0500 Subject: [PATCH 107/193] Corrections to PB Simple 1608 settings. --- .../settings/settings_Printrbot_Simple_1608.h | 22 ++++++++++++------- 1 file changed, 14 insertions(+), 8 deletions(-) diff --git a/g2core/settings/settings_Printrbot_Simple_1608.h b/g2core/settings/settings_Printrbot_Simple_1608.h index c4965a76e..cdb42593a 100644 --- a/g2core/settings/settings_Printrbot_Simple_1608.h +++ b/g2core/settings/settings_Printrbot_Simple_1608.h @@ -55,6 +55,8 @@ #define COOLANT_FLOOD_POLARITY 1 // 0=active low, 1=active high #define COOLANT_PAUSE_ON_HOLD false +#define TRAVERSE_AT_HIGH_JERK true // EXPERIMENTAL, primarily used here for retraction of extruder + // Communications and reporting settings #define MARLIN_COMPAT_ENABLED true // enable marlin compatibility mode @@ -71,8 +73,9 @@ #define STATUS_REPORT_INTERVAL_MS 250 // milliseconds - set $SV=0 to disable // Defaults for 3DP -#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","vel","he1t","he1st","he1at","feed","unit","path","stat" -// There are no heater two or three, but these would show those: ,"he2t","he2st","he2at","he3t","he3st","he3at" +#define STATUS_REPORT_DEFAULTS \ +"line","posx","posy","posz","posa","vel","he1t","he1st","he1at","he1op","feed","vel","unit","path","stat", \ +"he2t","he2st","he2at","he2op","he3t","he3st","he3at","he3op" // Defaults for motion debugging //#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","he1t","he1st","he1at","he2t","he2st","he2at","he3t","he3st","he3at","_fe5","_fe4","feed","vel","unit","path","stat" @@ -87,7 +90,7 @@ #define GCODE_DEFAULT_PATH_CONTROL PATH_CONTINUOUS #define GCODE_DEFAULT_DISTANCE_MODE ABSOLUTE_DISTANCE_MODE -#define MARLIN_G29_SCRIPT \ +#define MARLIN_G29_SCRIPT \ "(MSG Tramming started)\n" \ "M100 ({\"_leds\":3})\n" \ "G1 X0 Y145 Z6 F20000\n" \ @@ -102,7 +105,7 @@ "G38.2 Z-10 F200\n" \ "G1 Z5 F20000\n" \ "M100 ({\"_leds\":3})\n" \ - "M100 ({\"tram\":1})" \ + "M100 ({\"tram\":1})\n" \ "(MSG Tramming completed)\n" // *** motor settings ************************************************************************************ @@ -227,8 +230,8 @@ //#define A_FEEDRATE_MAX 9720.0 // 9720.0 = G1 rate ~15 mm/s, 900 mm/min #define A_TRAVEL_MIN 0 #define A_TRAVEL_MAX 10 -//#define A_JERK_MAX 81000 // 250 million mm/min^3 = 324000 -#define A_JERK_MAX 162000 // 250 million mm/min^3 = 324000 +//#define A_JERK_MAX 81000 // 250 million mm/min^3 = 324000 +#define A_JERK_MAX 162000 // 250 million mm/min^3 = 324000 //#define A_JERK_MAX 324000 // 500 million mm/min^3 = 324000 //#define A_JERK_MAX 648000 // 1,000 million mm/min^3 = 648000 // * a million IF it's over a million @@ -280,7 +283,7 @@ #define EXTRUDER_1_OUTPUT_PIN kOutput1_PinNumber #define EXTRUDER_1_FAN_PIN kOutput3_PinNumber -#define HAS_TEMPERATURE_SENSOR_2 true +#define HAS_TEMPERATURE_SENSOR_2 false #if HAS_TEMPERATURE_SENSOR_2 #if 1 // 1 if a Thermistor, 0 if a PT100 #define TEMPERATURE_SENSOR_2_TYPE Thermistor @@ -410,6 +413,9 @@ /*** Extruders / Heaters ***/ +#define TEMP_MIN_BED_RISE_DEGREES_OVER_TIME 0.5 + + #define MIX_FAN_VALUE 0.4 // (he1fm) at MIN_FAN_TEMP the fan comes on at this spped (0.0-1.0) #define MAX_FAN_VALUE 0.75 // (he1fp) at MAX_FAN_TEMP the fan is at this spped (0.0-1.0) #define MIN_FAN_TEMP 50.0 // (he1fl) at this temp the fan starts to ramp up linearly @@ -425,7 +431,7 @@ #define H2_DEFAULT_I 0.05 #define H2_DEFAULT_D 150.0 -#define H3_DEFAULT_ENABLE false +#define H3_DEFAULT_ENABLE true #define H3_DEFAULT_P 9.0 #define H3_DEFAULT_I 0.12 #define H3_DEFAULT_D 400.0 From 606e38833d55e2bfd04a3dd64151f18101ee9a5c Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Tue, 16 May 2017 16:07:00 -0500 Subject: [PATCH 108/193] Cleanup of temperature code. Utilizing new ADCPin.is_differential --- g2core/temperature.cpp | 23 ++++++++++++++--------- 1 file changed, 14 insertions(+), 9 deletions(-) diff --git a/g2core/temperature.cpp b/g2core/temperature.cpp index b983606bf..d382e9a94 100755 --- a/g2core/temperature.cpp +++ b/g2core/temperature.cpp @@ -230,7 +230,7 @@ struct Thermistor { float c1, c2, c3, pullup_resistance; // We'll pull adc top value from the adc_pin.getTop() - ADCPin adc_pin {kNormal, [&]{this->adc_has_new_value();} }; + ADCPin adc_pin; uint16_t raw_adc_value = 0; float raw_adc_voltage = 0.0; @@ -241,9 +241,15 @@ struct Thermistor { // http://hydraraptor.blogspot.com/2012/11/more-accurate-thermistor-tables.html Thermistor(const float temp_low, const float temp_med, const float temp_high, const float res_low, const float res_med, const float res_high, const float pullup_resistance_) - : pullup_resistance{ pullup_resistance_ } { + : pullup_resistance{ pullup_resistance_ }, + adc_pin {kNormal, [&]{this->adc_has_new_value();} } + { setup(temp_low, temp_med, temp_high, res_low, res_med, res_high); adc_pin.setInterrupts(kPinInterruptOnChange|kInterruptPriorityLow); + adc_pin.setVoltageRange(kSystemVoltage, + 0, //get_voltage_of_temp(min_temp), + kSystemVoltage, //get_voltage_of_temp(max_temp), + 6400.0); } void setup(const float temp_low, const float temp_med, const float temp_high, const float res_low, const float res_med, const float res_high) { @@ -333,10 +339,10 @@ struct PT100 { typedef PT100 type; - PT100(const float pullup_resistance_, const float inline_resistance_, const bool differential_ = false) + PT100(const float pullup_resistance_, const float inline_resistance_) : pullup_resistance{ pullup_resistance_ }, inline_resistance{ inline_resistance_ }, - differential{differential_}, + differential{adc_pin.is_differential}, gives_raw_resistance{false}, adc_pin{kDifferentialPair, [&]{this->adc_has_new_value();} } { @@ -357,8 +363,8 @@ struct PT100 { { adc_pin.setInterrupts(kPinInterruptOnChange|kInterruptPriorityLow); adc_pin.setVoltageRange(kSystemVoltage, - get_resistance_of_temp(min_temp), - get_resistance_of_temp(max_temp), + get_voltage_of_temp(min_temp), + get_voltage_of_temp(max_temp), 1); // ignored }; @@ -428,9 +434,8 @@ struct PT100 { raw_adc_voltage = (raw_adc_value*pullup_resistance)/32768; history.add_sample(raw_adc_voltage); } else { - raw_adc_value = adc_pin.getRaw(); -// raw_adc_voltage = (raw_adc_voltage*10.0 + adc_pin.getVoltage())/11.0; - history.add_sample(adc_pin.getVoltage()); + float v = fabs(adc_pin.getVoltage()); + history.add_sample(v); } }; }; From 98af94ccd42226385c35adeb6c3a11671f52843a Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Wed, 7 Jun 2017 16:53:52 -0500 Subject: [PATCH 109/193] UM2+ settings: Minor adjustments and notes --- g2core/settings/settings_Ultimaker_2_Plus.h | 89 ++++++++++++++------- 1 file changed, 62 insertions(+), 27 deletions(-) diff --git a/g2core/settings/settings_Ultimaker_2_Plus.h b/g2core/settings/settings_Ultimaker_2_Plus.h index 7cca54a96..79b03efdf 100644 --- a/g2core/settings/settings_Ultimaker_2_Plus.h +++ b/g2core/settings/settings_Ultimaker_2_Plus.h @@ -85,8 +85,8 @@ //#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","he1t","he1st","he1at","he1op","pid1p","pid1i","pid1d","feed","vel","unit","path","stat" // Defaults for thermistor tuning -//#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","he1t","he1st","he1at","he1op","he3t","he3st","he3at","he3op","feed","vel","unit","path","stat","1ts","1sgr","1csa","2ts","2sgr","2csa","3ts","3sgr","3csa","4ts","4sgr","4csa" -#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","he1t","he1st","he1at","he1tr","he1tv","he1op","he2t","he2st","he2at","he2tr","he2tv","he2op","he3t","he3st","he3at","he3tr","he3tv","he3op","feed","vel","unit","path","stat","_xs1","_xs2","_xs3","_xs4" +#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","he1t","he1st","he1at","he1op","he3t","he3st","he3at","he3op","feed","vel","unit","path","stat","1ts","1sgr","1csa","2ts","2sgr","2csa","3ts","3sgr","3csa","4ts","4sgr","4csa" +//#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","he1t","he1st","he1at","he1tr","he1tv","he1op","he2t","he2st","he2at","he2tr","he2tv","he2op","he3t","he3st","he3at","he3tr","he3tv","he3op","feed","vel","unit","path","stat","_xs1","_xs2","_xs3","_xs4" // Gcode startup defaults #define GCODE_DEFAULT_UNITS MILLIMETERS // MILLIMETERS or INCHES #define GCODE_DEFAULT_PLANE CANON_PLANE_XY // CANON_PLANE_XY, CANON_PLANE_XZ, or CANON_PLANE_YZ @@ -99,6 +99,22 @@ #define MOTOR_POWER_TIMEOUT 30 // don't disable motors (without an explicit {md:0}) for 30 seconds +#if 0 + +{jt:1.2} + +{afr:1000} + +{jt:1.0} + +{afr:900} +{sr:{"line":t,"posx":t,"posy":t,"posz":t,"posa":t,"he1t":t,"he1st":t,"he1at":t,"he1op":t,"he3t":t,"he3st":t,"he3at":t,"he3op":t,"feed":t,"vel":t,"stat":t,"1ts":t,"1sgr":t,"1csa":t,"2ts":t,"2sgr":t,"2csa":t,"3ts":t,"3sgr":t,"3csa":t,"4ts":t,"4sgr":t,"4csa":t}} + +{afr:2000} +{afr:6000} + +#endif + #define MOTOR_POWER_MODE MOTOR_POWERED_IN_CYCLE // default motor power mode (see cmMotorPowerMode in stepper.h) // 80 steps/mm at 1/16 microstepping = 40 mm/rev #define M1_MOTOR_MAP AXIS_X // 1ma @@ -119,7 +135,7 @@ #define M1_TMC2130_HEND 0 // 1hend #define M1_TMC2130_HSTRT 0 // 1hsrt #define M1_TMC2130_SMIN 5 // 1smin -#define M1_TMC2130_SMAX 12 // 1smax +#define M1_TMC2130_SMAX 5 // 1smax #define M1_TMC2130_SUP 2 // 1sup #define M1_TMC2130_SDN 1 // 1sdn @@ -142,7 +158,7 @@ #define M2_TMC2130_HEND 0 #define M2_TMC2130_HSTRT 0 #define M2_TMC2130_SMIN 5 -#define M2_TMC2130_SMAX 12 +#define M2_TMC2130_SMAX 5 #define M2_TMC2130_SUP 2 #define M2_TMC2130_SDN 1 @@ -213,7 +229,7 @@ // *** axis settings ********************************************************************************** #define X_AXIS_MODE AXIS_STANDARD // xam see canonical_machine.h cmAxisMode for valid values -#define X_VELOCITY_MAX 9000 // xvm G0 max velocity in mm/min +#define X_VELOCITY_MAX 8700 // xvm G0 max velocity in mm/min #define X_FEEDRATE_MAX X_VELOCITY_MAX // xfr G1 max feed rate in mm/min #define X_TRAVEL_MIN 0 // xtn minimum travel - used by soft limits and homing #define X_TRAVEL_MAX 230 // xtm travel between switches or crashes @@ -229,7 +245,7 @@ //{yjm:5000} #define Y_AXIS_MODE AXIS_STANDARD -#define Y_VELOCITY_MAX 9000 +#define Y_VELOCITY_MAX 8700 #define Y_FEEDRATE_MAX Y_VELOCITY_MAX #define Y_TRAVEL_MIN 0 #define Y_TRAVEL_MAX 224.5 @@ -257,8 +273,8 @@ #define Z_LATCH_BACKOFF 5 #define Z_ZERO_BACKOFF 0 -#define G55_Z_OFFSET 0.3 // higher number is farther away from the bed -// {g55z:0.3} +#define G55_Z_OFFSET 0.35 // higher number is farther away from the bed +// {g55z:0.35} //#define G55_Z_OFFSET 0.25 // higher number is farther away from the bed // {g55z:0.25} @@ -284,21 +300,25 @@ //#define A_VELOCITY_MAX 288886.4 //#define A_VELOCITY_MAX 144443.0 // G0 rate ~60 mm/s, 3,600 mm/min #define A_VELOCITY_MAX 72221.5 // G0 rate ~30 mm/s, 3,600 mm/min -//define A_VELOCITY_MAX 48147.7 // G0 rate ~20 mm/s +//NYLON +//#define A_VELOCITY_MAX 30000.0 // G0 rate ~20 mm/s {avm:60000.0} //#define A_FEEDRATE_MAX 48147.7 // ~20 mm/s //#define A_FEEDRATE_MAX 36110.8 // ~15 mm/s //#define A_FEEDRATE_MAX 24073.9 // ~10 mm/s //#define A_FEEDRATE_MAX 12036.95 // ~5 mm/s -//#define A_FEEDRATE_MAX 6018.475 // ~2.5 mm/s Testing: {afr:800} -#define A_FEEDRATE_MAX 1000.0 // ~0.415 mm/s -//#define A_FEEDRATE_MAX 800.0 // WORKS WELL +//#define A_FEEDRATE_MAX 6018.475 // ~2.5 mm/s +#define A_FEEDRATE_MAX 1000.0 // ~0.415 mm/s {afr:1000} +// NYLON +//#define A_FEEDRATE_MAX 800.0 // {afr:800} //#define A_FEEDRATE_MAX 500.0 // ~0.2075 mm/s #define A_TRAVEL_MIN 0 #define A_TRAVEL_MAX 10 //#define A_JERK_MAX 288886.4 // ~120 million mm/min^3 //#define A_JERK_MAX 144443.2 // ~60 million mm/min^3 #define A_JERK_MAX 48147.7 // ~20 million mm/min^3 {ajm:48147.7} +//NYLON +//#define A_JERK_MAX 25000.0 // ~20 million mm/min^3 {ajm:15000.0} #define A_HOMING_INPUT 0 #define A_HOMING_DIRECTION 0 #define A_SEARCH_VELOCITY 2000 @@ -307,7 +327,12 @@ #define A_ZERO_BACKOFF 2 //#define A_JERK_HIGH_SPEED 288886.4 // ~120 million mm/min^3 //#define A_JERK_HIGH_SPEED 240739.0 // ~100 million mm/min^3 -#define A_JERK_HIGH_SPEED 144443.2 // ~60 million mm/min^3 +//#define A_JERK_HIGH_SPEED 144443.2 // ~60 million mm/min^3 +#define A_JERK_HIGH_SPEED 120000.0 // +//#define A_JERK_HIGH_SPEED 95000.0 // ~40 million mm/min^3 +// NYLON +//#define A_JERK_HIGH_SPEED 35000.0 // ~30 million mm/min^3 {ajh:35000.0} + #define B_AXIS_MODE AXIS_RADIUS #define B_RADIUS 1.428 @@ -323,20 +348,22 @@ #define B_LATCH_BACKOFF 5 #define B_ZERO_BACKOFF 2 #define B_JERK_HIGH_SPEED 361108.0 // ~150 million mm/min^3 -// -//{afr:6018.475} -//{ajm:48147.7} -//{xjm:8000} -//{yjm:8000} -//{xfr:3000} -//{yfr:3000} -//{1pl:0.25} -//{2pl:0.25} -//{4pl:0.35} - -//{1pl:0.6} -//{2pl:0.6} -//{4pl:0.6} + +/* NYLON +M100.1 ({{avm:90000.0}}) +M100.1 ({{afr:1000}}) +M100.1 ({{ajm:25000.0}}) +M100.1 ({{ajh:144000.0}}) + + {ajh:50000.0} + {ajh:60000.0} + + {avm:90000.0} + {afr:1000} + {ajh:70000.0} + {ajm:25000.0} + {ajh:144000.0} + */ //*** Input / output settings *** @@ -519,6 +546,14 @@ {he1d:500} {he1f:0.0015} +{he1fp:0.25} +{out4:0.7} + +{he1fp:0.0} + +{he1fp:1.0} +{out4:1.0} + #endif #define H2_DEFAULT_ENABLE false From d27f105dacc2e15e2e956fcb0f328a2dab250406 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Fri, 16 Jun 2017 22:26:47 -0500 Subject: [PATCH 110/193] UM2+: Raise Z latch backoff --- g2core/settings/settings_Ultimaker_2_Plus.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/g2core/settings/settings_Ultimaker_2_Plus.h b/g2core/settings/settings_Ultimaker_2_Plus.h index 79b03efdf..0098be79b 100644 --- a/g2core/settings/settings_Ultimaker_2_Plus.h +++ b/g2core/settings/settings_Ultimaker_2_Plus.h @@ -270,7 +270,7 @@ #define Z_HOMING_DIRECTION 1 #define Z_SEARCH_VELOCITY 1000 #define Z_LATCH_VELOCITY 100 -#define Z_LATCH_BACKOFF 5 +#define Z_LATCH_BACKOFF 15 #define Z_ZERO_BACKOFF 0 #define G55_Z_OFFSET 0.35 // higher number is farther away from the bed From 5d21d842171e22fc4270e98e6416ec92ce394e3b Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Tue, 20 Jun 2017 20:40:54 -0500 Subject: [PATCH 111/193] UM2+: Adjust settings, mostly for Z --- g2core/settings/settings_Ultimaker_2_Plus.h | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/g2core/settings/settings_Ultimaker_2_Plus.h b/g2core/settings/settings_Ultimaker_2_Plus.h index 0098be79b..fbc54735a 100644 --- a/g2core/settings/settings_Ultimaker_2_Plus.h +++ b/g2core/settings/settings_Ultimaker_2_Plus.h @@ -169,7 +169,7 @@ #define M3_MICROSTEPS 128 #define M3_POLARITY 0 #define M3_POWER_MODE MOTOR_POWERED_IN_CYCLE -#define M3_POWER_LEVEL 0.4 +#define M3_POWER_LEVEL 0.8 #define M3_TMC2130_TPWMTHRS 300 #define M3_TMC2130_TCOOLTHRS 200 #define M3_TMC2130_THIGH 10 @@ -260,17 +260,17 @@ #define Z_AXIS_MODE AXIS_STANDARD #define Z_VELOCITY_MAX 1500 -#define Z_FEEDRATE_MAX Z_VELOCITY_MAX +#define Z_FEEDRATE_MAX 1000 #define Z_TRAVEL_MIN 0 #define Z_TRAVEL_MAX 215 -//#define Z_JERK_MAX 500 -#define Z_JERK_MAX 800 +#define Z_JERK_MAX 500 +//#define Z_JERK_MAX 800 #define Z_JERK_HIGH_SPEED 1000 #define Z_HOMING_INPUT 6 #define Z_HOMING_DIRECTION 1 #define Z_SEARCH_VELOCITY 1000 #define Z_LATCH_VELOCITY 100 -#define Z_LATCH_BACKOFF 15 +#define Z_LATCH_BACKOFF 10 #define Z_ZERO_BACKOFF 0 #define G55_Z_OFFSET 0.35 // higher number is farther away from the bed @@ -308,7 +308,7 @@ //#define A_FEEDRATE_MAX 24073.9 // ~10 mm/s //#define A_FEEDRATE_MAX 12036.95 // ~5 mm/s //#define A_FEEDRATE_MAX 6018.475 // ~2.5 mm/s -#define A_FEEDRATE_MAX 1000.0 // ~0.415 mm/s {afr:1000} +#define A_FEEDRATE_MAX 3000.0 // ~0.415 mm/s {afr:1000} // NYLON //#define A_FEEDRATE_MAX 800.0 // {afr:800} //#define A_FEEDRATE_MAX 500.0 // ~0.2075 mm/s @@ -316,7 +316,7 @@ #define A_TRAVEL_MAX 10 //#define A_JERK_MAX 288886.4 // ~120 million mm/min^3 //#define A_JERK_MAX 144443.2 // ~60 million mm/min^3 -#define A_JERK_MAX 48147.7 // ~20 million mm/min^3 {ajm:48147.7} +#define A_JERK_MAX 40000.0 // ~20 million mm/min^3 {ajm:48147.7} //NYLON //#define A_JERK_MAX 25000.0 // ~20 million mm/min^3 {ajm:15000.0} #define A_HOMING_INPUT 0 From 1203584a9dd08c073abed71f9871d64769be8669 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Tue, 20 Jun 2017 20:41:28 -0500 Subject: [PATCH 112/193] Marlin: Add support from M205, which changes jerk settings --- g2core/gcode_parser.cpp | 23 ++++++++++++++++++++++- 1 file changed, 22 insertions(+), 1 deletion(-) diff --git a/g2core/gcode_parser.cpp b/g2core/gcode_parser.cpp index 78cc2f184..03ca72c53 100644 --- a/g2core/gcode_parser.cpp +++ b/g2core/gcode_parser.cpp @@ -106,6 +106,7 @@ typedef enum { // these are in order to optimiz NEXT_ACTION_MARLIN_REPORT_VERSION, // M115 NEXT_ACTION_MARLIN_DISPLAY_ON_SCREEN, // M117 NEXT_ACTION_MARLIN_SET_BED_TEMP, // M140, M190 + NEXT_ACTION_MARLIN_SET_JERK, // M205 #endif } gpNextAction; @@ -851,6 +852,8 @@ stat_t _parse_gcode_block(char *buf, char *active_comment) case 115: SET_NON_MODAL (next_action, NEXT_ACTION_MARLIN_REPORT_VERSION); // report version information case 117: status = STAT_COMPLETE; break; //SET_NON_MODAL (next_action, NEXT_ACTION_MARLIN_DISPLAY_ON_SCREEN); + + case 205: SET_NON_MODAL (next_action, NEXT_ACTION_MARLIN_SET_JERK); // set jerk #endif // MARLIN_COMPAT_ENABLED default: status = STAT_MCODE_COMMAND_UNSUPPORTED; @@ -1218,7 +1221,25 @@ static stat_t _execute_gcode_block_marlin() break; } case NEXT_ACTION_MARLIN_RESET_LINE_NUMBERS:{ // M110 - js.json_mode = MARLIN_COMM_MODE; // we already did this above in if (gf.linenum) {} + js.json_mode = MARLIN_COMM_MODE; + return (STAT_OK); + } + case NEXT_ACTION_MARLIN_SET_JERK:{ // M205 + mst.marlin_flavor = true; // these gcodes are ONLY in marlin flavor + // example: M205 X20 + // This should translate to, roughly, {xjm:5832} + {yjm:5832} + if (gf.target[AXIS_X]) { + gf.target[AXIS_X] = false; // make sure nothing else picks it up + gv.target[AXIS_X] = (gv.target[AXIS_X] * gv.target[AXIS_X] * gv.target[AXIS_X]) * 0.216; // (X^3 * 60^3) / 1000000 + if (gv.target[AXIS_X] < JERK_INPUT_MIN) { + return (STAT_INPUT_LESS_THAN_MIN_VALUE); + } + if (gv.target[AXIS_X] > JERK_INPUT_MAX) { + return (STAT_INPUT_EXCEEDS_MAX_VALUE); + } + cm_set_axis_jerk(AXIS_X, gv.target[AXIS_X]); + cm_set_axis_jerk(AXIS_Y, gv.target[AXIS_X]); + } return (STAT_OK); } case NEXT_ACTION_DEFAULT: { From 058039d2ac5ddef9bcba83d3cb9c1184774c2be9 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Wed, 28 Jun 2017 17:24:46 -0500 Subject: [PATCH 113/193] Fixing cornering to include active jerk, not default jerk for the axes. --- g2core/canonical_machine.cpp | 5 +- g2core/canonical_machine.h | 2 +- g2core/plan_line.cpp | 118 +++++++++++++++-------------------- 3 files changed, 53 insertions(+), 72 deletions(-) diff --git a/g2core/canonical_machine.cpp b/g2core/canonical_machine.cpp index 81e144e39..63a783905 100644 --- a/g2core/canonical_machine.cpp +++ b/g2core/canonical_machine.cpp @@ -2545,18 +2545,17 @@ static const float _junction_accel_multiplier = sqrt(3.0)/10.0; // Important note: Actual jerk is stored jerk * JERK_MULTIPLIER, and // Time Quanta is junction_integration_time / 1000. +// We no longer incorporate jerk into this, since it can be channged per-move. void _cm_recalc_max_junction_accel(const uint8_t axis) { float T = cm.junction_integration_time / 1000.0; float T2 = T*T; - cm.a[axis].max_junction_accel = _junction_accel_multiplier * T2 * (cm.a[axis].jerk_max * JERK_MULTIPLIER); + cm.a[axis].max_junction_accel = _junction_accel_multiplier * T2 * JERK_MULTIPLIER; } void cm_set_axis_jerk(const uint8_t axis, const float jerk) { cm.a[axis].jerk_max = jerk; - // Must recalculate the max_junction_accel now that the jerk has changed. - _cm_recalc_max_junction_accel(axis); } stat_t cm_set_vm(nvObj_t *nv) diff --git a/g2core/canonical_machine.h b/g2core/canonical_machine.h index ac039ed4c..ab825b4ff 100644 --- a/g2core/canonical_machine.h +++ b/g2core/canonical_machine.h @@ -374,7 +374,7 @@ typedef struct cmAxis { float jerk_max; // max jerk (Jm) in mm/min^3 divided by 1 million float jerk_high; // high speed deceleration jerk (Jh) in mm/min^3 divided by 1 million //float recip_jerk; // stored reciprocal of current jerk value - has the million in it - float max_junction_accel; // high speed deceleration jerk (Jh) in mm/min^3 divided by 1 million + float max_junction_accel; // cornering time quanta times JERK_MULTIPLIER, must be multiplied by active jerk first! float junction_dev; // aka cornering delta -- DEPRICATED! float radius; // radius in mm for rotary axis modes diff --git a/g2core/plan_line.cpp b/g2core/plan_line.cpp index a36ea4f46..405a6b4e5 100644 --- a/g2core/plan_line.cpp +++ b/g2core/plan_line.cpp @@ -507,7 +507,23 @@ static void _calculate_override(mpBuf_t* bf) // execute ramp to adjust cruise v * Cost about ~65 uSec */ -static void _calculate_jerk(mpBuf_t* bf) +static float _get_axis_jerk(mpBuf_t* bf, uint8_t axis) +{ + #ifdef TRAVERSE_AT_HIGH_JERK + switch (bf->gm.motion_mode) { + case MOTION_MODE_STRAIGHT_TRAVERSE: + //case MOTION_MODE_STRAIGHT_PROBE: // <-- not sure on this one + return cm.a[axis].jerk_high; + break; + default: + return cm.a[axis].jerk_max; + } + #else + return cm.a[axis].jerk_max; + #endif +} + +static void _calculate_jerk(mpBuf_t* bf) { // compute the jerk as the largest jerk that still meets axis constraints bf->jerk = 8675309; // a ridiculously large number @@ -515,20 +531,7 @@ static void _calculate_jerk(mpBuf_t* bf) for (uint8_t axis = 0; axis < AXES; axis++) { if (fabs(bf->unit[axis]) > 0) { // if this axis is participating in the move - float axis_jerk = 0; -#ifdef TRAVERSE_AT_HIGH_JERK -#warning using experimental feature TRAVERSE_AT_HIGH_JERK! - switch (bf->gm.motion_mode) { - case MOTION_MODE_STRAIGHT_TRAVERSE: - //case MOTION_MODE_STRAIGHT_PROBE: // <-- not sure on this one - axis_jerk = cm.a[axis].jerk_high; - break; - default: - axis_jerk = cm.a[axis].jerk_max; - } -#else - axis_jerk = cm.a[axis].jerk_max; -#endif + float axis_jerk = _get_axis_jerk(bf, axis); jerk = axis_jerk / fabs(bf->unit[axis]); if (jerk < bf->jerk) { @@ -655,10 +658,10 @@ static void _calculate_vmaxes(mpBuf_t* bf, const float axis_length[], const floa /* * _calculate_junction_vmax() - Giseburt's Algorithm ;-) * - * WARNING: This description is out of date and needs updated. - * * Computes the maximum allowable junction speed by finding the velocity that will not - * violate the jerk value of any axis. + * violate the jerk value of any axis. We have one tunable parameter: the time we expect + * or allow the corner to take over which we apply the jerk of the relevant axes. This + * is stored in junction_integration_time. * * In order to achieve this we take the difference of the unit vectors of the two moves * of the corner, at the point from vector a to vector b. The unit vectors of those two @@ -666,44 +669,34 @@ static void _calculate_vmaxes(mpBuf_t* bf, const float axis_length[], const floa * * Delta[i] = (b_unit[i] - a_unit[i]) (1) * - * We take, axis by axis, the difference in "unit velocity" to get a vector that - * represents the direction of acceleration - which may be the opposite direction - * as that of the "a" vector to achieve deceleration. To get the actual acceleration, - * we use the corner velocity (what we intend to calculate) as the magnitude. + * We want to find the velocity V[i] where, when sacled by each Delta[i], the Peak Jerk of a move + * that takes T time will be at (or below) the set limit for each axis, or Max Jerk. The lowest + * velocity of all the relevant axes is the one used. * - * Acceleration[i] = UnitAccel[i] * Velocity[i] (2) + * MaxJerk[i] = (10/sqrt(3))*(Delta[i]*V[i])/T^2 * - * Since we need the jerk value, which is defined as the "rate of change of acceleration, - * that is, the derivative of acceleration with respect to time" (Wikipedia), we need to - * have a quantum of time where the change in acceleration is actually carried out by the - * physics. That will give us the time over which to "apply" the change of acceleration - * in order to get a physically realistic jerk. The yields a fairly simple formula: + * Solved for V[i]: * - * Jerk[i] = Acceleration[i] / Time (3) + * V[i] = sqrt(3)/10 * MaxJerk[i] * T^2 / D[i] (2) * - * Now that we can compute the jerk for a given corner, we need to know the maximum - * velocity that we can take the corner without violating that jerk for any axis. - * Let's incorporate formula (2) into formula (3), and solve for Velocity, using - * the known max Jerk and UnitAccel for this corner: * - * Velocity[i] = (Jerk[i] * Time) / UnitAccel[i] (4) + * Two edge cases: + * A) One or more axes do not change. Completely degenerate case is a straight line. + * We have to detect this or we'll have a divide-by-zero. + * To deal with this, we start at the cruise vmax, and lower from there. If nothing lowers it, + * then that's our cornering velocity. * - * We then compute (4) for each axis, and use the smallest (most limited) result or - * vmax, whichever is smaller. - */ -/* Note 1: - * junction_integration_time is the integration Time quantum expressed in minutes. - * This is roughly on the order of 1 DDA clock tick to integrate jerk to acceleration. - * This is a very small number, so we multiply JT by 1,000,000 for entry and display. - * A reasonable JA is therefore between 0.10 and 2.0 - * - * In formula 4 the jerk is multiplied by 1,000,000 and JT is divided by 1,000,000, - * so those terms cancel out. + * B) Over a series of very short (length) moves that have little angular change (a highly segmented circle with + * a very small radius, for example) then we will not slow down sufficiently. + * To deal with this, we keep track of the unit vector 0.5mm back, which may be in another move. We then use that + * We will use the max delta between the current vector and that vector or that of the next move. + * + * C) The last move (there is not "next move" yet) will have to compate to a unit vector of zero. */ static void _calculate_junction_vmax(mpBuf_t* bf) { - // special case for planning the last block + // (C) special case for planning the last block if (bf->nx->buffer_state == MP_BUFFER_EMPTY) { // Compute a junction velocity to full stop float velocity = bf->cruise_vmax; // start with our maximum possible velocity @@ -712,11 +705,9 @@ static void _calculate_junction_vmax(mpBuf_t* bf) if (bf->axis_flags[axis]) { // skip axes with no movement float delta = bf->unit[axis]; - // Corner case: If an axis has zero delta, we might have a straight line. - // Corner case: An axis doesn't change (and it's not a straight line). - // In either case, division-by-zero is bad, m'kay? + // if (delta > EPSILON) { - velocity = std::min(velocity, (cm.a[axis].max_junction_accel / delta)); + velocity = std::min(velocity, ((cm.a[axis].max_junction_accel * _get_axis_jerk(bf, axis)) / delta)); // formula (2) } } } @@ -726,10 +717,10 @@ static void _calculate_junction_vmax(mpBuf_t* bf) } // ++++ RG If we change cruise_vmax, we'll need to recompute junction_vmax, if we do this: + // (A) degenerate near-zero deltas to cruise_vmax float velocity = std::min(bf->cruise_vmax, bf->nx->cruise_vmax); // start with our maximum possible velocity - // uint8_t jerk_axis = AXIS_X; - // cmAxes jerk_axis = AXIS_X; + // (B) special case to deal with many very short moves that are almost linear bool using_junction_unit = false; float junction_length_since = bf->junction_length_since + bf->length; if (junction_length_since < 0.5) { @@ -741,32 +732,23 @@ static void _calculate_junction_vmax(mpBuf_t* bf) } for (uint8_t axis = 0; axis < AXES; axis++) { - if (bf->axis_flags[axis] || bf->nx->axis_flags[axis]) { // skip axes with no movement + if (bf->axis_flags[axis] || bf->nx->axis_flags[axis]) { // (A) skip axes with no movement float delta = fabs(bf->unit[axis] - bf->nx->unit[axis]); // formula (1) - if (using_junction_unit) { + if (using_junction_unit) { // (B) special case // use the highest delta of the two - delta = std::max(delta, fabs(bf->junction_unit[axis] - bf->nx->unit[axis])); + delta = std::max(delta, fabs(bf->junction_unit[axis] - bf->nx->unit[axis])); // formula (1) - // push the junction_unit for this axis into the next block + // push the junction_unit for this axis into the next block, for future (B) cases bf->nx->junction_unit[axis] = bf->junction_unit[axis]; - } else { + } else { // prepare for future (B) cases // push this unit to the next junction_unit bf->nx->junction_unit[axis] = bf->unit[axis]; } - // Corner case: If an axis has zero delta, we might have a straight line. - // Corner case: An axis doesn't change (and it's not a straight line). - // In either case, division-by-zero is bad, m'kay? + // (A) special case handling if (delta > EPSILON) { - // formula (4): (See Note 1, above) - - velocity = std::min(velocity, (cm.a[axis].max_junction_accel / delta)); - -// if ((cm.a[axis].max_junction_accel / delta) < velocity) { -// velocity = (cm.a[axis].max_junction_accel / delta); -// // bf->jerk_axis = axis; -// } + velocity = std::min(velocity, ((cm.a[axis].max_junction_accel * _get_axis_jerk(bf, axis)) / delta)); // formula (2) } } } From 8840ee6ac56f7c5a6ef72df8ecf0055fc4890045 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Fri, 30 Jun 2017 11:30:07 -0500 Subject: [PATCH 114/193] UM2+ Lowered Z power level, made PID more aggressive, and gave it more time to heat the bed. --- g2core/settings/settings_Ultimaker_2_Plus.h | 14 ++++++++------ 1 file changed, 8 insertions(+), 6 deletions(-) diff --git a/g2core/settings/settings_Ultimaker_2_Plus.h b/g2core/settings/settings_Ultimaker_2_Plus.h index fbc54735a..f63961ff0 100644 --- a/g2core/settings/settings_Ultimaker_2_Plus.h +++ b/g2core/settings/settings_Ultimaker_2_Plus.h @@ -169,7 +169,7 @@ #define M3_MICROSTEPS 128 #define M3_POLARITY 0 #define M3_POWER_MODE MOTOR_POWERED_IN_CYCLE -#define M3_POWER_LEVEL 0.8 +#define M3_POWER_LEVEL 0.6 #define M3_TMC2130_TPWMTHRS 300 #define M3_TMC2130_TCOOLTHRS 200 #define M3_TMC2130_THIGH 10 @@ -308,7 +308,7 @@ //#define A_FEEDRATE_MAX 24073.9 // ~10 mm/s //#define A_FEEDRATE_MAX 12036.95 // ~5 mm/s //#define A_FEEDRATE_MAX 6018.475 // ~2.5 mm/s -#define A_FEEDRATE_MAX 3000.0 // ~0.415 mm/s {afr:1000} +#define A_FEEDRATE_MAX 3000.0 // ~0.415 mm/s {afr:2000} // NYLON //#define A_FEEDRATE_MAX 800.0 // {afr:800} //#define A_FEEDRATE_MAX 500.0 // ~0.2075 mm/s @@ -535,8 +535,8 @@ M100.1 ({{ajh:144000.0}}) // PID debug string: {sr:{"he1t":t,"he1st":t,"pid1p":t, "pid1i":t, "pid1d":t, "pid1f":t, "he1op":t, "line":t, "stat":t}} #define H1_DEFAULT_ENABLE true -#define H1_DEFAULT_P 2 -#define H1_DEFAULT_I 0.005 +#define H1_DEFAULT_P 5 +#define H1_DEFAULT_I 0.01 #define H1_DEFAULT_D 500 #define H1_DEFAULT_F 0.0015 #if 0 @@ -563,7 +563,9 @@ M100.1 ({{ajh:144000.0}}) #define H2_DEFAULT_F 0.0 #define H3_DEFAULT_ENABLE true -#define H3_DEFAULT_P 9.0 -#define H3_DEFAULT_I 0.012 +#define H3_DEFAULT_P 20.0 +#define H3_DEFAULT_I 0.05 #define H3_DEFAULT_D 50 #define H3_DEFAULT_F 0.0015 + +#define TEMP_MIN_BED_RISE_DEGREES_OVER_TIME 0.1 From d87eeef406173db05a7dff4608cfdb0c0c3d8ff2 Mon Sep 17 00:00:00 2001 From: Riley Date: Sat, 15 Jul 2017 22:54:25 -0400 Subject: [PATCH 115/193] Added Ender 3d Printer Config --- g2core/settings/settings_ender.h | 494 +++++++++++++++++++++++++++++++ 1 file changed, 494 insertions(+) create mode 100644 g2core/settings/settings_ender.h diff --git a/g2core/settings/settings_ender.h b/g2core/settings/settings_ender.h new file mode 100644 index 000000000..c1c06a672 --- /dev/null +++ b/g2core/settings/settings_ender.h @@ -0,0 +1,494 @@ +/* + * settings_ender.h + * This file is part of the the g2core project + * + * Copyright (c) 2010 - 2016 Alden S. Hart, Jr. + * Copyright (c) 2010 - 2016 Robert Giseburt + * + * This file ("the software") is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License, version 2 as published by the + * Free Software Foundation. You should have received a copy of the GNU General Public + * License, version 2 along with the software. If not, see . + * + * As a special exception, you may use this file as part of a software library without + * restriction. Specifically, if other files instantiate templates or use macros or + * inline functions from this file, or you compile this file and link it with other + * files to produce an executable, this file does not by itself cause the resulting + * executable to be covered by the GNU General Public License. This exception does not + * however invalidate any other reasons why the executable file might be covered by the + * GNU General Public License. + * + * THE SOFTWARE IS DISTRIBUTED IN THE HOPE THAT IT WILL BE USEFUL, BUT WITHOUT ANY + * WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES + * OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT + * SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF + * OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + */ + +/***********************************************************************/ +/**** Printrbot Play profile *******************************************/ +/***********************************************************************/ + +// ***> NOTE: The init message must be a single line with no CRs or LFs +#define INIT_MESSAGE "Initializing configs to Ender Printer Play profile" +#define PROBE_REPORT_ENABLE 1 +#ifndef PI +#define PI 3.14159628 +#endif + +//**** GLOBAL / GENERAL SETTINGS ****************************************************** + +#define JUNCTION_INTEGRATION_TIME 1.2 // cornering - between 0.10 and 2.00 (higher is faster) +//{jt:1.2} +//{jt:0.75} +#define CHORDAL_TOLERANCE 0.01 // chordal accuracy for arc drawing (in mm) + +#define SOFT_LIMIT_ENABLE 0 // 0=off, 1=on +#define HARD_LIMIT_ENABLE 1 // 0=off, 1=on +#define SAFETY_INTERLOCK_ENABLE 1 // 0=off, 1=on + +#define SPINDLE_ENABLE_POLARITY 1 // 0=active low, 1=active high +#define SPINDLE_DIR_POLARITY 0 // 0=clockwise is low, 1=clockwise is high +#define SPINDLE_PAUSE_ON_HOLD true +#define SPINDLE_DWELL_TIME 1.0 + +#define COOLANT_MIST_POLARITY 1 // 0=active low, 1=active high +#define COOLANT_FLOOD_POLARITY 1 // 0=active low, 1=active high +#define COOLANT_PAUSE_ON_HOLD false + +#define TRAVERSE_AT_HIGH_JERK true // EXPERIMENTAL!! + +// Communications and reporting settings + +#define MARLIN_COMPAT_ENABLED true // enable marlin compatibility mode +#define COMM_MODE JSON_MODE // one of: TEXT_MODE, JSON_MODE +#define XIO_ENABLE_FLOW_CONTROL FLOW_CONTROL_RTS // FLOW_CONTROL_OFF, FLOW_CONTROL_RTS +#define XIO_UART_MUTES_WHEN_USB_CONNECTED 1 // Mute the UART when USB connects + +#define TEXT_VERBOSITY TV_VERBOSE // one of: TV_SILENT, TV_VERBOSE +#define JSON_VERBOSITY JV_LINENUM // one of: JV_SILENT, JV_FOOTER, JV_CONFIGS, JV_MESSAGES, JV_LINENUM, JV_VERBOSE +#define QUEUE_REPORT_VERBOSITY QR_OFF // one of: QR_OFF, QR_SINGLE, QR_TRIPLE + +#define STATUS_REPORT_VERBOSITY SR_FILTERED // one of: SR_OFF, SR_FILTERED, SR_VERBOSE +#define STATUS_REPORT_MIN_MS 100 // milliseconds - enforces a viable minimum +#define STATUS_REPORT_INTERVAL_MS 250 // milliseconds - set $SV=0 to disable + +// Defaults for 3DP +//#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","vel","he1t","he1st","he1at","feed","unit","path","stat" +// There are no heater two or three, but these would show those: ,"he2t","he2st","he2at","he3t","he3st","he3at" + +// Defaults for motion debugging +//#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","he1t","he1st","he1at","he2t","he2st","he2at","he3t","he3st","he3at","_fe5","_fe4","feed","vel","unit","path","stat" + +// Defaults for PID tuning +//#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","he1t","he1st","he1at","he1op","pid1p","pid1i","pid1d","feed","vel","unit","path","stat" + +// Defaults for thermistor tuning +#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","he1t","he1st","he1at","he1op","he3t","he3st","he3at","he3op","feed","vel","unit","path","stat","1ts","1sgr","1csa","2ts","2sgr","2csa","3ts","3sgr","3csa","4ts","4sgr","4csa" +//#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","he1t","he1st","he1at","he1tr","he1tv","he1op","he2t","he2st","he2at","he2tr","he2tv","he2op","he3t","he3st","he3at","he3tr","he3tv","he3op","feed","vel","unit","path","stat","_xs1","_xs2","_xs3","_xs4" +// Gcode startup defaults +#define GCODE_DEFAULT_UNITS MILLIMETERS // MILLIMETERS or INCHES +#define GCODE_DEFAULT_PLANE CANON_PLANE_XY // CANON_PLANE_XY, CANON_PLANE_XZ, or CANON_PLANE_YZ +#define GCODE_DEFAULT_COORD_SYSTEM G54 // G54, G55, G56, G57, G58 or G59 +#define GCODE_DEFAULT_PATH_CONTROL PATH_CONTINUOUS +#define GCODE_DEFAULT_DISTANCE_MODE ABSOLUTE_DISTANCE_MODE + + +// *** motor settings ************************************************************************************ + +#define MOTOR_POWER_MODE MOTOR_POWERED_IN_CYCLE // default motor power mode (see cmMotorPowerMode in stepper.h) +// 80 steps/mm at 1/16 microstepping = 40 mm/rev +#define M1_MOTOR_MAP AXIS_X // 1ma +#define M1_STEP_ANGLE 1.8 // 1sa +// Marlin says 80 steps/unit, and 16 microsteps, with a 200-step/rev motor +#define M1_TRAVEL_PER_REV 40.64 // 1tr +#define M1_MICROSTEPS 128 // 1mi 1,2,4,8,16,32 +#define M1_POLARITY 1 // 1po 0=normal, 1=reversed +#define M1_POWER_MODE MOTOR_POWERED_IN_CYCLE // 1pm standard +#define M1_POWER_LEVEL 0.8 // 1pl +#define M1_TMC2130_TPWMTHRS 1200 // 1pth +#define M1_TMC2130_TCOOLTHRS 1000 // 1cth +#define M1_TMC2130_THIGH 10 // 1hth +#define M1_TMC2130_SGT 4 // 1sgt +#define M1_TMC2130_TBL 2 // 1tbl +#define M1_TMC2130_PWM_GRAD 1 // 1pgrd +#define M1_TMC2130_PWM_AMPL 200 // 1pamp +#define M1_TMC2130_HEND 0 // 1hend +#define M1_TMC2130_HSTRT 0 // 1hsrt +#define M1_TMC2130_SMIN 5 // 1smin +#define M1_TMC2130_SMAX 5 // 1smax +#define M1_TMC2130_SUP 2 // 1sup +#define M1_TMC2130_SDN 1 // 1sdn + +// 80 steps/mm at 1/16 microstepping = 40 mm/rev +#define M2_MOTOR_MAP AXIS_Y +#define M2_STEP_ANGLE 1.8 +// Marlin says 80 steps/unit, and 16 microsteps, with a 200-step/rev motor +#define M2_TRAVEL_PER_REV 40.64 +#define M2_MICROSTEPS 128 +#define M2_POLARITY 0 +#define M2_POWER_MODE MOTOR_POWERED_IN_CYCLE +#define M2_POWER_LEVEL 0.8 +#define M2_TMC2130_TPWMTHRS 1200 +#define M2_TMC2130_TCOOLTHRS 1000 +#define M2_TMC2130_THIGH 10 +#define M2_TMC2130_SGT 4 +#define M2_TMC2130_TBL 2 +#define M2_TMC2130_PWM_GRAD 1 +#define M2_TMC2130_PWM_AMPL 200 +#define M2_TMC2130_HEND 0 +#define M2_TMC2130_HSTRT 0 +#define M2_TMC2130_SMIN 5 +#define M2_TMC2130_SMAX 5 +#define M2_TMC2130_SUP 2 +#define M2_TMC2130_SDN 1 + +#define M3_MOTOR_MAP AXIS_Z +#define M3_STEP_ANGLE 1.8 +#define M3_TRAVEL_PER_REV 1.5875 +#define M3_MICROSTEPS 128 +#define M3_POLARITY 0 +#define M3_POWER_MODE MOTOR_POWERED_IN_CYCLE +#define M3_POWER_LEVEL 0.6 +#define M3_TMC2130_TPWMTHRS 300 +#define M3_TMC2130_TCOOLTHRS 200 +#define M3_TMC2130_THIGH 10 +#define M3_TMC2130_SGT 4 +#define M3_TMC2130_TBL 2 +#define M3_TMC2130_PWM_GRAD 1 +#define M3_TMC2130_PWM_AMPL 200 +#define M3_TMC2130_HEND 0 +#define M3_TMC2130_HSTRT 0 +#define M3_TMC2130_SMIN 5 +#define M3_TMC2130_SMAX 12 +#define M3_TMC2130_SUP 2 +#define M3_TMC2130_SDN 2 + +#define M4_MOTOR_MAP AXIS_A +#define M4_STEP_ANGLE 1.8 +#define M4_TRAVEL_PER_REV 360 // degrees moved per motor rev +#define M4_MICROSTEPS 128 +#define M4_POLARITY 0 +#define M4_POWER_MODE MOTOR_POWER_MODE +#define M4_POWER_LEVEL 0.8 +#define M4_TMC2130_TPWMTHRS 180000 +#define M4_TMC2130_TCOOLTHRS 100000 +#define M4_TMC2130_THIGH 10 +#define M4_TMC2130_SGT 3 +#define M4_TMC2130_TBL 2 +#define M4_TMC2130_PWM_GRAD 15 +#define M4_TMC2130_PWM_AMPL 255 +#define M4_TMC2130_HEND 0 +#define M4_TMC2130_HSTRT 0 +#define M4_TMC2130_SMIN 5 +#define M4_TMC2130_SMAX 10 +#define M4_TMC2130_SUP 3 +#define M4_TMC2130_SDN 0 + +#define M5_MOTOR_MAP AXIS_B +#define M5_STEP_ANGLE 1.8 +#define M5_TRAVEL_PER_REV 40 +#define M5_MICROSTEPS 128 +#define M5_POLARITY 1 +#define M5_POWER_MODE MOTOR_DISABLED +#define M5_POWER_LEVEL 0.8 +#define M5_TMC2130_TPWMTHRS 1200 +#define M5_TMC2130_TCOOLTHRS 1000 +#define M5_TMC2130_THIGH 10 +#define M5_TMC2130_SGT 4 +#define M5_TMC2130_TBL 2 +#define M5_TMC2130_PWM_GRAD 1 +#define M5_TMC2130_PWM_AMPL 200 +#define M5_TMC2130_HEND 0 +#define M5_TMC2130_HSTRT 0 +#define M5_TMC2130_SMIN 5 +#define M5_TMC2130_SMAX 12 +#define M5_TMC2130_SUP 2 +#define M5_TMC2130_SDN 1 + +// *** axis settings ********************************************************************************** + +#define X_AXIS_MODE AXIS_STANDARD // xam see canonical_machine.h cmAxisMode for valid values +#define X_VELOCITY_MAX 30000 // xvm G0 max velocity in mm/min +#define X_FEEDRATE_MAX X_VELOCITY_MAX // xfr G1 max feed rate in mm/min +#define X_TRAVEL_MIN 0 // xtn minimum travel - used by soft limits and homing +#define X_TRAVEL_MAX 100 // xtm travel between switches or crashes +#define X_JERK_MAX 15000 // xjm yes, that's "100 billion" mm/(min^3) +#define X_JERK_HIGH_SPEED 20000 // xjh +#define X_HOMING_INPUT 1 // xhi input used for homing or 0 to disable +#define X_HOMING_DIRECTION 0 // xhd 0=search moves negative, 1= search moves positive +#define X_SEARCH_VELOCITY 3000 // xsv move in negative direction +#define X_LATCH_VELOCITY 200 // xlv mm/min +#define X_LATCH_BACKOFF 5 // xlb mm +#define X_ZERO_BACKOFF 0.5 // xzb mm + +#define Y_AXIS_MODE AXIS_STANDARD +#define Y_VELOCITY_MAX 30000 +#define Y_FEEDRATE_MAX Y_VELOCITY_MAX +#define Y_TRAVEL_MIN 0 +#define Y_TRAVEL_MAX 100 +#define Y_JERK_MAX 15000 +#define Y_JERK_HIGH_SPEED 20000 +#define Y_HOMING_INPUT 4 +#define Y_HOMING_DIRECTION 1 +#define Y_SEARCH_VELOCITY 1500 +#define Y_LATCH_VELOCITY 200 +#define Y_LATCH_BACKOFF 5 +#define Y_ZERO_BACKOFF 0.5 + +#define Z_AXIS_MODE AXIS_STANDARD +#define Z_VELOCITY_MAX 300 +#define Z_FEEDRATE_MAX Z_VELOCITY_MAX +#define Z_TRAVEL_MIN 0 +#define Z_TRAVEL_MAX 125 +#define Z_JERK_MAX 800 +#define Z_JERK_HIGH_SPEED 1600 +#define Z_HOMING_INPUT 5 +#define Z_HOMING_DIRECTION 0 +#define Z_SEARCH_VELOCITY 200 +#define Z_LATCH_VELOCITY 100 +#define Z_LATCH_BACKOFF 5 +#define Z_ZERO_BACKOFF 0 + +#define G55_Z_OFFSET 0.35 // higher number is farther away from the bed + +// Rotary values are chosen to make the motor react the same as X for testing +/*************************************************************************************** + * To calculate the speeds here, in Wolfram Alpha-speak: + * + * c=2*pi*r, r=0.609, d=c/360, s=((S*60)/d), S=40 for s + * c=2*pi*r, r=5.30516476972984, d=c/360, s=((S*60)/d), S=40 for s + * + * Change r to A_RADIUS, and S to the desired speed, in mm/s or mm/s/s/s. + * + * It will return s= as the value you want to enter. + * + * If the value is over 1 million, the code will divide it by 1 million, + * so you have to pre-multiply it by 1000000.0. (The value is in millions, btw.) + * + * Note that you need these to be floating point values, so always have a .0 at the end! + * + ***************************************************************************************/ + +#define A_AXIS_MODE AXIS_RADIUS +#define A_RADIUS 5.30516476972984 +#define A_VELOCITY_MAX 77760.0 // G0 rate ~120 mm/s, 2,400 mm/min +#define A_FEEDRATE_MAX 9720.0 // 9720.0 = G1 rate ~15 mm/s, 900 mm/min +#define A_TRAVEL_MIN 0 +#define A_TRAVEL_MAX 10 +#define A_JERK_MAX 40000.0 // ~20 million mm/min^3 {ajm:48147.7} +#define A_HOMING_INPUT 0 +#define A_HOMING_DIRECTION 0 +#define A_SEARCH_VELOCITY 2000 +#define A_LATCH_VELOCITY 2000 +#define A_LATCH_BACKOFF 5 +#define A_ZERO_BACKOFF 2 +#define A_JERK_HIGH_SPEED 120000.0 // + + +#define B_AXIS_MODE AXIS_RADIUS +#define B_RADIUS 1.428 +#define B_VELOCITY_MAX 144443.0 // G0 rate ~60 mm/s, 3,600 mm/min +#define B_FEEDRATE_MAX 96295.4 // ~40 mm/s +#define B_TRAVEL_MIN 0 +#define B_TRAVEL_MAX 10 +#define B_JERK_MAX 180554.0 // ~75 million mm/min^3 +#define B_HOMING_INPUT 0 +#define B_HOMING_DIRECTION 0 +#define B_SEARCH_VELOCITY 2000 +#define B_LATCH_VELOCITY 2000 +#define B_LATCH_BACKOFF 5 +#define B_ZERO_BACKOFF 2 +#define B_JERK_HIGH_SPEED 361108.0 // ~150 million mm/min^3 + + +//*** Input / output settings *** + +//** Temperature Sensors ** + +//#include "device/max31865/max31865.h" + +//#define USING_A_MAX31865 1 + +#define HAS_TEMPERATURE_SENSOR_1 true + +#if HAS_TEMPERATURE_SENSOR_1 +// Must choose Thermistor or PT100 +#if 1 // 1 if a Thermistor, 0 if a PT100 + #define TEMPERATURE_SENSOR_1_TYPE Thermistor> + #define TEMPERATURE_SENSOR_1_INIT { \ + /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ + /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ + } +#else + // #define TEMPERATURE_SENSOR_1_TYPE PT100> + // #define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 2000, /*inline_resistance*/0.0} + #define TEMPERATURE_SENSOR_1_TYPE PT100> + #define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 430, /*inline_resistance*/0, spiBus, spiCSPinMux.getCS(5)} +#endif // 0 or 1 +#endif // HAS_TEMPERATURE_SENSOR_1 + +#define EXTRUDER_1_OUTPUT_PIN kHeaterOutput1_PinNumber +#define EXTRUDER_1_FAN_PIN kOutput5_PinNumber + +#define HAS_TEMPERATURE_SENSOR_2 false +#if HAS_TEMPERATURE_SENSOR_2 +#if 1 // 1 if a Thermistor, 0 if a PT100 + #define TEMPERATURE_SENSOR_2_TYPE Thermistor> + #define TEMPERATURE_SENSOR_2_INIT { \ + /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ + /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ + } +#else + #define TEMPERATURE_SENSOR_2_TYPE PT100> + #define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 200, /*inline_resistance*/0.0} +// #define TEMPERATURE_SENSOR_2_TYPE PT100> +// #define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 430, /*inline_resistance*/0, spiBus, spiCSPinMux.getCS(5)} +#endif // 0 or 1 +#endif // HAS_TEMPERATURE_SENSOR_2 + +#define EXTRUDER_2_OUTPUT_PIN kHeaterOutput2_PinNumber + +#define HAS_TEMPERATURE_SENSOR_3 true +#if HAS_TEMPERATURE_SENSOR_3 +#if 1 // 1 if a Thermistor, 0 if a PT100 + #define TEMPERATURE_SENSOR_3_TYPE Thermistor> + #define TEMPERATURE_SENSOR_3_INIT { \ + /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ + /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ + } +#else + // #define TEMPERATURE_SENSOR_3_TYPE PT100> + // #define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 200, /*inline_resistance*/0.0} + #define TEMPERATURE_SENSOR_3_TYPE PT100> + #define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 430, /*inline_resistance*/0, spiBus, spiCSPinMux.getCS(6)} + +#endif // 0 or 1 +#endif // HAS_TEMPERATURE_SENSOR_3 + +#define BED_OUTPUT_PIN kHeaterOutput11_PinNumber + +//** Digital Inputs ** +/* + IO_MODE_DISABLED + IO_ACTIVE_LOW aka NORMALLY_OPEN + IO_ACTIVE_HIGH aka NORMALLY_CLOSED + + INPUT_ACTION_NONE + INPUT_ACTION_STOP + INPUT_ACTION_FAST_STOP + INPUT_ACTION_HALT + INPUT_ACTION_RESET + + INPUT_FUNCTION_NONE + INPUT_FUNCTION_LIMIT + INPUT_FUNCTION_INTERLOCK + INPUT_FUNCTION_SHUTDOWN + INPUT_FUNCTION_PANIC + */ +// Inputs are defined for the g2ref(a) board +// Xmn (board label) +#define DI1_MODE IO_ACTIVE_LOW +#define DI1_ACTION INPUT_ACTION_NONE +#define DI1_FUNCTION INPUT_FUNCTION_NONE + +// Xmax +#define DI2_MODE IO_MODE_DISABLED +#define DI2_ACTION INPUT_ACTION_NONE +#define DI2_FUNCTION INPUT_FUNCTION_NONE + +// Ymin +#define DI3_MODE IO_MODE_DISABLED +#define DI3_ACTION INPUT_ACTION_NONE +#define DI3_FUNCTION INPUT_FUNCTION_NONE + +// Ymax +#define DI4_MODE IO_ACTIVE_LOW +#define DI4_ACTION INPUT_ACTION_NONE +#define DI4_FUNCTION INPUT_FUNCTION_NONE + +// Zmin +#define DI5_MODE IO_ACTIVE_LOW +#define DI5_ACTION INPUT_ACTION_NONE +#define DI5_FUNCTION INPUT_FUNCTION_NONE + +// Zmax +#define DI6_MODE IO_MODE_DISABLED +#define DI6_ACTION INPUT_ACTION_NONE +#define DI6_FUNCTION INPUT_FUNCTION_NONE + +// Shutdown (Amin on v9 board) +#define DI7_MODE IO_MODE_DISABLED +#define DI7_ACTION INPUT_ACTION_NONE +#define DI7_FUNCTION INPUT_FUNCTION_NONE + +// High Voltage Z Probe In (Amax on v9 board) +#define DI8_MODE IO_ACTIVE_LOW +#define DI8_ACTION INPUT_ACTION_NONE +#define DI8_FUNCTION INPUT_FUNCTION_NONE + +// Hardware interlock input +#define DI9_MODE IO_MODE_DISABLED +#define DI9_ACTION INPUT_ACTION_NONE +#define DI9_FUNCTION INPUT_FUNCTION_NONE + +//Extruder1_PWM +#define DO1_MODE IO_ACTIVE_HIGH // unavailable, is the extruder output + +//Extruder2_PWM +#define DO2_MODE IO_ACTIVE_HIGH // unavailable, is the extruder output + +//Fan1A_PWM +#define DO3_MODE IO_ACTIVE_LOW + +//Fan1B_PWM +#define DO4_MODE IO_ACTIVE_HIGH + +#define DO5_MODE IO_ACTIVE_HIGH +#define DO6_MODE IO_ACTIVE_HIGH +#define DO7_MODE IO_ACTIVE_HIGH +#define DO8_MODE IO_ACTIVE_HIGH // 5V Fan + +//SAFEin (Output) signal +#define DO9_MODE IO_ACTIVE_HIGH + +#define DO10_MODE IO_ACTIVE_HIGH + +//Header Bed FET +#define DO11_MODE IO_ACTIVE_LOW // unavailable, is the extruder output + +//Indicator_LED +#define DO12_MODE IO_ACTIVE_HIGH + +#define DO13_MODE IO_ACTIVE_HIGH + + +/*** Extruders / Heaters ***/ + +#define MIN_FAN_VALUE 0.4 // (he1fm) at MIN_FAN_TEMP the fan comes on at this spped (0.0-1.0) +#define MAX_FAN_VALUE 1.0 // (he1fp) at MAX_FAN_TEMP the fan is at this spped (0.0-1.0) +#define MIN_FAN_TEMP 50.0 // (he1fl) at this temp the fan starts to ramp up linearly +#define MAX_FAN_TEMP 100.0 // (he1fh) at this temperature the fan is at "full speed" (MAX_FAN_VALUE) + +// PID debug string: {sr:{"he1t":t,"he1st":t,"pid1p":t, "pid1i":t, "pid1d":t, "pid1f":t, "he1op":t, "line":t, "stat":t}} + +#define H1_DEFAULT_ENABLE true +#define H1_DEFAULT_P 5 +#define H1_DEFAULT_I 0.01 +#define H1_DEFAULT_D 500 +#define H1_DEFAULT_F 0.0015 + +#define H2_DEFAULT_ENABLE false +#define H2_DEFAULT_P 7.0 +#define H2_DEFAULT_I 0.05 +#define H2_DEFAULT_D 150.0 +#define H2_DEFAULT_F 0.0 + +#define H3_DEFAULT_ENABLE true +#define H3_DEFAULT_P 20.0 +#define H3_DEFAULT_I 0.05 +#define H3_DEFAULT_D 50 +#define H3_DEFAULT_F 0.0015 + +#define TEMP_MIN_BED_RISE_DEGREES_OVER_TIME 0.1 \ No newline at end of file From 5609c8740d722e4a689354e74e7d41a8f3f036ee Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Sat, 15 Jul 2017 22:29:10 -0500 Subject: [PATCH 116/193] Fixes for Thermistor not accepting ADCDifferentialPair<...> correctly. --- g2core/temperature.cpp | 25 +++++++++++++++++++------ 1 file changed, 19 insertions(+), 6 deletions(-) diff --git a/g2core/temperature.cpp b/g2core/temperature.cpp index d382e9a94..11cdc8866 100755 --- a/g2core/temperature.cpp +++ b/g2core/temperature.cpp @@ -225,16 +225,16 @@ struct ValueHistory { }; -template +template struct Thermistor { float c1, c2, c3, pullup_resistance; // We'll pull adc top value from the adc_pin.getTop() - ADCPin adc_pin; + ADC_t adc_pin; uint16_t raw_adc_value = 0; float raw_adc_voltage = 0.0; - typedef Thermistor type; + typedef Thermistor type; // References for thermistor formulas: // http://assets.newport.com/webDocuments-EN/images/AN04_Thermistor_Calibration_IX.PDF @@ -242,7 +242,7 @@ struct Thermistor { Thermistor(const float temp_low, const float temp_med, const float temp_high, const float res_low, const float res_med, const float res_high, const float pullup_resistance_) : pullup_resistance{ pullup_resistance_ }, - adc_pin {kNormal, [&]{this->adc_has_new_value();} } + adc_pin {ADC_t::is_differential ? kDifferentialPair : kNormal, [&]{this->adc_has_new_value();} } { setup(temp_low, temp_med, temp_high, res_low, res_med, res_high); adc_pin.setInterrupts(kPinInterruptOnChange|kInterruptPriorityLow); @@ -250,7 +250,20 @@ struct Thermistor { 0, //get_voltage_of_temp(min_temp), kSystemVoltage, //get_voltage_of_temp(max_temp), 6400.0); - } + }; + + template + Thermistor(const float temp_low, const float temp_med, const float temp_high, const float res_low, const float res_med, const float res_high, const float pullup_resistance_, Ts&&... additional_values) + : pullup_resistance{ pullup_resistance_ }, + adc_pin{ADC_t::is_differential ? kDifferentialPair : kNormal, [&]{this->adc_has_new_value();}, additional_values...} + { + setup(temp_low, temp_med, temp_high, res_low, res_med, res_high); + adc_pin.setInterrupts(kPinInterruptOnChange|kInterruptPriorityLow); + adc_pin.setVoltageRange(kSystemVoltage, + 0, //get_voltage_of_temp(min_temp), + kSystemVoltage, //get_voltage_of_temp(max_temp), + 6400.0); + }; void setup(const float temp_low, const float temp_med, const float temp_high, const float res_low, const float res_med, const float res_high) { float temp_low_fixed = temp_low + 273.15; @@ -344,7 +357,7 @@ struct PT100 { inline_resistance{ inline_resistance_ }, differential{adc_pin.is_differential}, gives_raw_resistance{false}, - adc_pin{kDifferentialPair, [&]{this->adc_has_new_value();} } + adc_pin{ADC_t::is_differential ? kDifferentialPair : kNormal, [&]{this->adc_has_new_value();} } { adc_pin.setInterrupts(kPinInterruptOnChange|kInterruptPriorityLow); adc_pin.setVoltageRange(kSystemVoltage, From 2de08704cd9d41c6f6937ceaffa34c3dc970dc8f Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Sat, 15 Jul 2017 22:35:45 -0500 Subject: [PATCH 117/193] Highly experimental segment linear-velocity-interpolation --- g2core/plan_exec.cpp | 153 +++++++++++++++++++++++++---------- g2core/planner.h | 5 +- g2core/stepper.cpp | 184 ++++++++++++++++++++++++++++++++++--------- g2core/stepper.h | 19 +++-- 4 files changed, 274 insertions(+), 87 deletions(-) diff --git a/g2core/plan_exec.cpp b/g2core/plan_exec.cpp index 01ea5b0e4..ed891e463 100644 --- a/g2core/plan_exec.cpp +++ b/g2core/plan_exec.cpp @@ -50,17 +50,17 @@ static void _init_forward_diffs(float v_0, float v_1); * mp_forward_plan() - plan commands and moves ahead of exec; call ramping for moves * **** WARNING **** - * This function should NOT be called directly! - * Instead call st_request_forward_plan(), which mediates access. + * This function should NOT be called directly! + * Instead call st_request_forward_plan(), which mediates access. * - * mp_forward_plan() performs just-in-time forward planning immediately before - * lines and commands are queued to the move execution runtime (exec). + * mp_forward_plan() performs just-in-time forward planning immediately before + * lines and commands are queued to the move execution runtime (exec). * Unlike backward planning, buffers are only forward planned once. * * mp_forward_plan() is called aggressively via st_request_forward_plan(). * It has a relatively low interrupt level to call its own. * See also: Planner Overview notes in planner.h - * + * * It examines the currently running buffer and its adjacent buffers to: * * - Stop the system from re-planning or planning something that's not prepped @@ -68,43 +68,43 @@ static void _init_forward_diffs(float v_0, float v_1); * - Skip past/ or pre-plan COMMAND blocks while labeling them as PLANNED * * Returns: - * - STAT_OK if exec should be called to kickstart (or continue) movement + * - STAT_OK if exec should be called to kickstart (or continue) movement * - STAT_NOOP to exit with no action taken (do not call exec) */ /* * --- Forward Planning Processing and Cases --- - * - * These cases describe all possible sequences of buffers in the planner queue starting + * + * These cases describe all possible sequences of buffers in the planner queue starting * with the currently executing (or about to execute) Run buffer, looking forward - * to more recently arrived buffers. In most cases only one or two buffers need to - * be examined, but contiguous groups of commands may need to be processed. + * to more recently arrived buffers. In most cases only one or two buffers need to + * be examined, but contiguous groups of commands may need to be processed. * * 'Running' cases are where the run buffer state is RUNNING. Bootstrap handles all other cases. * 'Bootstrap' occurs during the startup phase where moves are collected before starting movement. * Conditions that are impossible based on this definition are not listed in the tables below. * - * See planner.h / bufferState enum for shorthand used in the descriptions. + * See planner.h / bufferState enum for shorthand used in the descriptions. * All cases assume a mix of moves and commands, as noted in the shorthand. - * All cases assume 2 'blocks' - Run block & Plan block. Cases will need to be - * revisited and generalized if more blocks are used in the future (deeper + * All cases assume 2 'blocks' - Run block & Plan block. Cases will need to be + * revisited and generalized if more blocks are used in the future (deeper * forward planning). * * 'NOT_PREPPED' refers to any preliminary state below PREPPED, i.e. < PREPPED. * ' NOT_PREPPED' can be either a move or command, we don't care so it's not specified. * * 'COMMAND' or 'COMMAND(s)' refers to one command or a contiguous group of command buffers - * that may be in PREPPED or PLANNED states. Processing is always the same. Plan all + * that may be in PREPPED or PLANNED states. Processing is always the same. Plan all * PREPPED commands and skip past all PLANNED commands. * - * Note 1: For MOVEs use the exit velocity of the Run block (mr.r->exit_velocity) as the + * Note 1: For MOVEs use the exit velocity of the Run block (mr.r->exit_velocity) as the * entry velocity of the next adjacent move. * - * Note 1a: In this special COMMAND case we trust mr.r->exit_velocity because the + * Note 1a: In this special COMMAND case we trust mr.r->exit_velocity because the * backplanner has already handled this case for us. * * Note 2: For COMMANDs use the entry velocity of the current runtime (mr.entry_velocity) - * as the entry velocity for the next adjacent move. mr.entry_velocity is almost always 0, - * but could be non-0 in a race condition. + * as the entry velocity for the next adjacent move. mr.entry_velocity is almost always 0, + * but could be non-0 in a race condition. * FYI: mr.entry_velocity is set at the end of the last running block in mp_exec_aline(). * * @@ -197,7 +197,7 @@ stat_t mp_forward_plan() { mpBuf_t *bf = mp_get_run_buffer(); float entry_velocity; - + // Case 0: Examine current running buffer for early exit conditions if (bf == NULL) { // case 0a: NULL means nothing is running - this is OK st_prep_null(); @@ -221,11 +221,11 @@ stat_t mp_forward_plan() // bf now points to the first non-command buffer past the command(s) if ((bf->block_type == BLOCK_TYPE_ALINE) && (bf->buffer_state > MP_BUFFER_PREPPED )) { // case 1i entry_velocity = mr.r->exit_velocity; // set entry_velocity for Note 1a - } - } + } + } // bf will always be on a non-command at this point - either a move or empty buffer - // process move + // process move if (bf->block_type == BLOCK_TYPE_ALINE) { // do cases 1a - 1e; finish cases 1f - 1k if (bf->buffer_state == MP_BUFFER_PREPPED) {// do 1a; finish 1f, 1j, 2d, 2i return (_plan_move(bf, entry_velocity)); @@ -322,12 +322,12 @@ stat_t mp_exec_move() * STAT_NOOP cause no operation from the steppers - do not load the move * STAT_xxxxx fatal error. Ends the move and frees the bf buffer * - * This routine is called from the (LO) interrupt level. The interrupt sequencing - * relies on the behaviors of the routines being exactly correct. Each call to - * _exec_aline() must execute and prep *one and only one* segment. If the segment - * is the not the last segment in the bf buffer the _aline() must return STAT_EAGAIN. - * If it's the last segment it must return STAT_OK. If it encounters a fatal error - * that would terminate the move it should return a valid error code. Failure to + * This routine is called from the (LO) interrupt level. The interrupt sequencing + * relies on the behaviors of the routines being exactly correct. Each call to + * _exec_aline() must execute and prep *one and only one* segment. If the segment + * is the not the last segment in the bf buffer the _aline() must return STAT_EAGAIN. + * If it's the last segment it must return STAT_OK. If it encounters a fatal error + * that would terminate the move it should return a valid error code. Failure to * obey this will introduce subtle and very difficult to diagnose bugs (trust us on this). * * Note 1: Returning STAT_OK ends the move and frees the bf buffer. @@ -358,26 +358,26 @@ stat_t mp_exec_move() */ /* Synchronization of run BUFFER and run BLOCK * - * Note first: mp_exec_aline() makes a huge assumption: When it comes time to get a - * new run block (mr.r) it assumes the planner block (mr.p) has been fully planned + * Note first: mp_exec_aline() makes a huge assumption: When it comes time to get a + * new run block (mr.r) it assumes the planner block (mr.p) has been fully planned * via the JIT forward planning and is ready for use as the new run block. * - * The runtime uses 2 structures for the current move or commend, the run BUFFER - * from the planner queue (mb.r, aka bf), and the run BLOCK from the runtime - * singleton (mr.r). These structures are synchronized implicitly, but not - * explicitly referenced, as pointers can lead to race conditions. + * The runtime uses 2 structures for the current move or commend, the run BUFFER + * from the planner queue (mb.r, aka bf), and the run BLOCK from the runtime + * singleton (mr.r). These structures are synchronized implicitly, but not + * explicitly referenced, as pointers can lead to race conditions. * See plan_zoid.cpp / mp_calculate_ramps() for more details * - * When mp_exec_aline() needs to grab a new planner buffer for a new move or command + * When mp_exec_aline() needs to grab a new planner buffer for a new move or command * (i.e. block state is inactive) it swaps (rolls) the run and planner BLOCKS so that - * mr.p (planner block) is now the mr.r (run block), and the old mr.r block becomes + * mr.p (planner block) is now the mr.r (run block), and the old mr.r block becomes * available for planning; it becomes mr.p block. * - * At the same time, it's when finished with its current run buffer (mb.r), it has already + * At the same time, it's when finished with its current run buffer (mb.r), it has already * advanced to the next buffer. mp_exec_move() does this at the end of previous move. * Or in the bootstrap case, there never was a previous mb.r, so the current one is OK. - * - * As if by magic, the new mb.r aligns with the run block that was just moved in from + * + * As if by magic, the new mb.r aligns with the run block that was just moved in from * the planning block. */ @@ -786,6 +786,16 @@ void mp_exit_hold_state() * F_1 = 120Ah^5 * * Note that with our current control points, D and E are actually 0. + * + * Further expansion, if we can do linear extroplation during a segment, we actually do want to start + * at t = 0. + * + * F_5(h)-F_5(0) = Ah^5 + Bh^4 + Ch^3 + Dh^2 + Eh + * F_4(h)-F_4(0) = 30Ah^5 + 14Bh^4 + 6Ch^3 + 2Dh^2 + * F_3(h)-F_3(0) = 150Ah^5 + 36Bh^4 + 6Ch^3 + * F_2(h)-F_2(0) = 240Ah^5 + 24Bh^4 + * F_1(h)-F_1(0) = 120Ah^5 + * */ // Total time: 147us @@ -829,6 +839,7 @@ static void _init_forward_diffs(const float v_0, const float v_1) const float Bh_4 = B * h_4; const float Ch_3 = C * h_3; +#if !defined(NEW_FWD_DIFF) || (NEW_FWD_DIFF==0) const float const1 = 7.5625; // (121.0/16.0) const float const2 = 3.25; // ( 13.0/ 4.0) const float const3 = 82.5; // (165.0/ 2.0) @@ -858,6 +869,28 @@ static void _init_forward_diffs(const float v_0, const float v_1) const float half_Ah_5 = A * half_h_5; mr.segment_velocity = half_Ah_5 + half_Bh_4 + half_Ch_3 + v_0; + +#else + // NEW_FWD_DIFF == 1 + + /* + * F_5 = A h^5 + B h^4 + C h^3 + D h^2 + E h + * F_4 = 30 A h^5 + 14 B h^4 + 6 C h^3 + 2 D h^2 + * F_3 = 150 A h^5 + 36 B h^4 + 6 C h^3 + * F_2 = 240 A h^5 + 24 B h^4 + * F_1 = 120 A h^5 + */ + + mr.forward_diff_5 = Ah_5 + Bh_4 + Ch_3; + mr.forward_diff_4 = 30.0*Ah_5 + 14.0*Bh_4 + 6.0*Ch_3; + mr.forward_diff_3 = 150.0*Ah_5 + 36.0*Bh_4 + 6.0*Ch_3; + mr.forward_diff_2 = 240.0*Ah_5 + 24.0*Bh_4; + mr.forward_diff_1 = 120.0*Ah_5; + + mr.segment_velocity = v_0; + mr.target_velocity = v_0 + mr.forward_diff_5; +#endif + } /********************************************************************************************* @@ -868,7 +901,9 @@ static stat_t _exec_aline_head(mpBuf_t *bf) { bool first_pass = false; if (mr.section_state == SECTION_NEW) { // INITIALIZATION +#if !defined(NEW_FWD_DIFF) || (NEW_FWD_DIFF==0) first_pass = true; +#endif if (fp_ZERO(mr.r->head_length)) { mr.section = SECTION_BODY; return(_exec_aline_body(bf)); // skip ahead to the body generator @@ -879,7 +914,13 @@ static stat_t _exec_aline_head(mpBuf_t *bf) if (mr.segment_count == 1) { // We will only have one segment, simply average the velocities +#if !defined(NEW_FWD_DIFF) || (NEW_FWD_DIFF==0) mr.segment_velocity = mr.r->head_length / mr.segment_time; +#else + mr.segment_velocity = mr.entry_velocity; + mr.target_velocity = mr.r->cruise_velocity; +#endif + } else { _init_forward_diffs(mr.entry_velocity, mr.r->cruise_velocity); // <-- sets inital segment_velocity } @@ -890,7 +931,12 @@ static stat_t _exec_aline_head(mpBuf_t *bf) mr.section = SECTION_HEAD; mr.section_state = SECTION_RUNNING; } else { +#if !defined(NEW_FWD_DIFF) || (NEW_FWD_DIFF==0) mr.segment_velocity += mr.forward_diff_5; +#else + mr.segment_velocity = mr.target_velocity; + mr.target_velocity += mr.forward_diff_5; +#endif } if (_exec_aline_segment() == STAT_OK) { // set up for second half @@ -927,6 +973,7 @@ static stat_t _exec_aline_body(mpBuf_t *bf) mr.segments = ceil(uSec(body_time) / NOM_SEGMENT_USEC); mr.segment_time = body_time / mr.segments; mr.segment_velocity = mr.r->cruise_velocity; + mr.target_velocity = mr.segment_velocity; mr.segment_count = (uint32_t)mr.segments; if (mr.segment_time < MIN_SEGMENT_TIME) { _debug_trap("mr.segment_time < MIN_SEGMENT_TIME"); @@ -954,7 +1001,9 @@ static stat_t _exec_aline_tail(mpBuf_t *bf) { bool first_pass = false; if (mr.section_state == SECTION_NEW) { // INITIALIZATION +#if !defined(NEW_FWD_DIFF) || (NEW_FWD_DIFF==0) first_pass = true; +#endif // Mark the block as unplannable bf->plannable = false; @@ -965,7 +1014,12 @@ static stat_t _exec_aline_tail(mpBuf_t *bf) mr.segment_time = mr.r->tail_time / mr.segments; // time to advance for each segment if (mr.segment_count == 1) { +#if !defined(NEW_FWD_DIFF) || (NEW_FWD_DIFF==0) mr.segment_velocity = mr.r->tail_length / mr.segment_time; +#else + mr.segment_velocity = mr.r->cruise_velocity; + mr.target_velocity = mr.r->exit_velocity; +#endif } else { _init_forward_diffs(mr.r->cruise_velocity, mr.r->exit_velocity); // <-- sets inital segment_velocity } @@ -977,7 +1031,12 @@ static stat_t _exec_aline_tail(mpBuf_t *bf) mr.section = SECTION_TAIL; mr.section_state = SECTION_RUNNING; } else { +#if !defined(NEW_FWD_DIFF) || (NEW_FWD_DIFF==0) mr.segment_velocity += mr.forward_diff_5; +#else + mr.segment_velocity = mr.target_velocity; + mr.target_velocity += mr.forward_diff_5; +#endif } if (_exec_aline_segment() == STAT_OK) { @@ -1023,18 +1082,21 @@ static stat_t _exec_aline_segment() if ((--mr.segment_count == 0) && (cm.motion_state != MOTION_HOLD)) { copy_vector(mr.gm.target, mr.waypoint[mr.section]); } else { +#if !defined(NEW_FWD_DIFF) || (NEW_FWD_DIFF==0) float segment_length = mr.segment_velocity * mr.segment_time; +#else + float segment_length = (mr.segment_velocity+mr.target_velocity) * 0.5 * mr.segment_time; +#endif // see https://en.wikipedia.org/wiki/Kahan_summation_algorithm // for the summation compensation description for (uint8_t a=0; a 0) { - motor_1.stepStart(); // turn step bit on + if ((st_run.mot[MOTOR_1].substep_accumulator += st_run.mot[MOTOR_1].substep_increment) > 0) { + motor_1.stepStart(); // turn step bit on #if NEW_DDA == 1 - st_run.mot[MOTOR_1].substep_accumulator -= DDA_SUBSTEPS; //st_run.dda_ticks_X_substeps; + st_run.mot[MOTOR_1].substep_accumulator -= DDA_SUBSTEPS; //st_run.dda_ticks_X_substeps; #else - st_run.mot[MOTOR_1].substep_accumulator -= st_run.dda_ticks_X_substeps; + st_run.mot[MOTOR_1].substep_accumulator -= st_run.dda_ticks_X_substeps; #endif - INCREMENT_ENCODER(MOTOR_1); - } - if ((st_run.mot[MOTOR_2].substep_accumulator += st_run.mot[MOTOR_2].substep_increment) > 0) { - motor_2.stepStart(); // turn step bit on + INCREMENT_ENCODER(MOTOR_1); + } +#if defined(NEW_FWD_DIFF) && (NEW_FWD_DIFF==1) + st_run.mot[MOTOR_1].substep_increment += st_run.mot[MOTOR_1].substep_increment_increment; +#endif + if ((st_run.mot[MOTOR_2].substep_accumulator += st_run.mot[MOTOR_2].substep_increment) > 0) { + motor_2.stepStart(); // turn step bit on #if NEW_DDA == 1 - st_run.mot[MOTOR_2].substep_accumulator -= DDA_SUBSTEPS; //st_run.dda_ticks_X_substeps; + st_run.mot[MOTOR_2].substep_accumulator -= DDA_SUBSTEPS; //st_run.dda_ticks_X_substeps; #else - st_run.mot[MOTOR_2].substep_accumulator -= st_run.dda_ticks_X_substeps; + st_run.mot[MOTOR_2].substep_accumulator -= st_run.dda_ticks_X_substeps; +#endif + INCREMENT_ENCODER(MOTOR_2); + } +#if defined(NEW_FWD_DIFF) && (NEW_FWD_DIFF==1) + st_run.mot[MOTOR_2].substep_increment += st_run.mot[MOTOR_2].substep_increment_increment; #endif - INCREMENT_ENCODER(MOTOR_2); - } #if MOTORS > 2 - if ((st_run.mot[MOTOR_3].substep_accumulator += st_run.mot[MOTOR_3].substep_increment) > 0) { - motor_3.stepStart(); // turn step bit on + if ((st_run.mot[MOTOR_3].substep_accumulator += st_run.mot[MOTOR_3].substep_increment) > 0) { + motor_3.stepStart(); // turn step bit on #if NEW_DDA == 1 - st_run.mot[MOTOR_3].substep_accumulator -= DDA_SUBSTEPS; //st_run.dda_ticks_X_substeps; + st_run.mot[MOTOR_3].substep_accumulator -= DDA_SUBSTEPS; //st_run.dda_ticks_X_substeps; #else - st_run.mot[MOTOR_3].substep_accumulator -= st_run.dda_ticks_X_substeps; + st_run.mot[MOTOR_3].substep_accumulator -= st_run.dda_ticks_X_substeps; +#endif + INCREMENT_ENCODER(MOTOR_3); + } +#if defined(NEW_FWD_DIFF) && (NEW_FWD_DIFF==1) + st_run.mot[MOTOR_3].substep_increment += st_run.mot[MOTOR_3].substep_increment_increment; #endif - INCREMENT_ENCODER(MOTOR_3); - } #endif #if MOTORS > 3 - if ((st_run.mot[MOTOR_4].substep_accumulator += st_run.mot[MOTOR_4].substep_increment) > 0) { - motor_4.stepStart(); // turn step bit on + if ((st_run.mot[MOTOR_4].substep_accumulator += st_run.mot[MOTOR_4].substep_increment) > 0) { + motor_4.stepStart(); // turn step bit on #if NEW_DDA == 1 - st_run.mot[MOTOR_4].substep_accumulator -= DDA_SUBSTEPS; //st_run.dda_ticks_X_substeps; + st_run.mot[MOTOR_4].substep_accumulator -= DDA_SUBSTEPS; //st_run.dda_ticks_X_substeps; #else - st_run.mot[MOTOR_4].substep_accumulator -= st_run.dda_ticks_X_substeps; + st_run.mot[MOTOR_4].substep_accumulator -= st_run.dda_ticks_X_substeps; +#endif + INCREMENT_ENCODER(MOTOR_4); + } +#if defined(NEW_FWD_DIFF) && (NEW_FWD_DIFF==1) + st_run.mot[MOTOR_4].substep_increment += st_run.mot[MOTOR_4].substep_increment_increment; #endif - INCREMENT_ENCODER(MOTOR_4); - } #endif #if MOTORS > 4 - if ((st_run.mot[MOTOR_5].substep_accumulator += st_run.mot[MOTOR_5].substep_increment) > 0) { - motor_5.stepStart(); // turn step bit on + if ((st_run.mot[MOTOR_5].substep_accumulator += st_run.mot[MOTOR_5].substep_increment) > 0) { + motor_5.stepStart(); // turn step bit on #if NEW_DDA == 1 - st_run.mot[MOTOR_5].substep_accumulator -= DDA_SUBSTEPS; //st_run.dda_ticks_X_substeps; + st_run.mot[MOTOR_5].substep_accumulator -= DDA_SUBSTEPS; //st_run.dda_ticks_X_substeps; #else - st_run.mot[MOTOR_5].substep_accumulator -= st_run.dda_ticks_X_substeps; + st_run.mot[MOTOR_5].substep_accumulator -= st_run.dda_ticks_X_substeps; #endif - INCREMENT_ENCODER(MOTOR_5); - } + INCREMENT_ENCODER(MOTOR_5); +#if defined(NEW_FWD_DIFF) && (NEW_FWD_DIFF==1) + st_run.mot[MOTOR_5].substep_increment += st_run.mot[MOTOR_5].substep_increment_increment; +#endif + } #endif #if MOTORS > 5 - if ((st_run.mot[MOTOR_6].substep_accumulator += st_run.mot[MOTOR_6].substep_increment) > 0) { - motor_6.stepStart(); // turn step bit on + if ((st_run.mot[MOTOR_6].substep_accumulator += st_run.mot[MOTOR_6].substep_increment) > 0) { + motor_6.stepStart(); // turn step bit on #if NEW_DDA == 1 - st_run.mot[MOTOR_6].substep_accumulator -= DDA_SUBSTEPS; //st_run.dda_ticks_X_substeps; + st_run.mot[MOTOR_6].substep_accumulator -= DDA_SUBSTEPS; //st_run.dda_ticks_X_substeps; #else - st_run.mot[MOTOR_6].substep_accumulator -= st_run.dda_ticks_X_substeps; + st_run.mot[MOTOR_6].substep_accumulator -= st_run.dda_ticks_X_substeps; +#endif + INCREMENT_ENCODER(MOTOR_6); + } +#if defined(NEW_FWD_DIFF) && (NEW_FWD_DIFF==1) + st_run.mot[MOTOR_6].substep_increment += st_run.mot[MOTOR_6].substep_increment_increment; #endif - INCREMENT_ENCODER(MOTOR_6); - } #endif // Process end of segment. @@ -527,13 +545,15 @@ static void _load_move() // the following if() statement sets the runtime substep increment value or zeroes it if ((st_run.mot[MOTOR_1].substep_increment = st_pre.mot[MOTOR_1].substep_increment) != 0) { - // NB: If motor has 0 steps the following is all skipped. This ensures that state comparisons // always operate on the last segment actually run by this motor, regardless of how many // segments it may have been inactive in between. // Apply accumulator correction if the time base has changed since previous segment #if NEW_DDA == 1 +#if defined(NEW_FWD_DIFF) && (NEW_FWD_DIFF==1) + st_run.mot[MOTOR_1].substep_increment_increment = st_pre.mot[MOTOR_1].substep_increment_increment; +#endif #else if (st_pre.mot[MOTOR_1].accumulator_correction_flag == true) { st_pre.mot[MOTOR_1].accumulator_correction_flag = false; @@ -560,6 +580,9 @@ static void _load_move() SET_ENCODER_STEP_SIGN(MOTOR_1, st_pre.mot[MOTOR_1].step_sign); } else { // Motor has 0 steps; might need to energize motor for power mode processing +#if defined(NEW_FWD_DIFF) && (NEW_FWD_DIFF==1) + st_run.mot[MOTOR_1].substep_increment_increment = 0; +#endif motor_1.motionStopped(); } // accumulate counted steps to the step position and zero out counted steps for the segment currently being loaded @@ -568,6 +591,9 @@ static void _load_move() #if (MOTORS >= 2) if ((st_run.mot[MOTOR_2].substep_increment = st_pre.mot[MOTOR_2].substep_increment) != 0) { #if NEW_DDA == 1 +#if defined(NEW_FWD_DIFF) && (NEW_FWD_DIFF==1) + st_run.mot[MOTOR_2].substep_increment_increment = st_pre.mot[MOTOR_2].substep_increment_increment; +#endif #else if (st_pre.mot[MOTOR_2].accumulator_correction_flag == true) { st_pre.mot[MOTOR_2].accumulator_correction_flag = false; @@ -586,6 +612,9 @@ static void _load_move() motor_2.enable(); SET_ENCODER_STEP_SIGN(MOTOR_2, st_pre.mot[MOTOR_2].step_sign); } else { +#if defined(NEW_FWD_DIFF) && (NEW_FWD_DIFF==1) + st_run.mot[MOTOR_2].substep_increment_increment = 0; +#endif motor_2.motionStopped(); } ACCUMULATE_ENCODER(MOTOR_2); @@ -593,6 +622,9 @@ static void _load_move() #if (MOTORS >= 3) if ((st_run.mot[MOTOR_3].substep_increment = st_pre.mot[MOTOR_3].substep_increment) != 0) { #if NEW_DDA == 1 +#if defined(NEW_FWD_DIFF) && (NEW_FWD_DIFF==1) + st_run.mot[MOTOR_3].substep_increment_increment = st_pre.mot[MOTOR_3].substep_increment_increment; +#endif #else if (st_pre.mot[MOTOR_3].accumulator_correction_flag == true) { st_pre.mot[MOTOR_3].accumulator_correction_flag = false; @@ -611,6 +643,9 @@ static void _load_move() motor_3.enable(); SET_ENCODER_STEP_SIGN(MOTOR_3, st_pre.mot[MOTOR_3].step_sign); } else { +#if defined(NEW_FWD_DIFF) && (NEW_FWD_DIFF==1) + st_run.mot[MOTOR_3].substep_increment_increment = 0; +#endif motor_3.motionStopped(); } ACCUMULATE_ENCODER(MOTOR_3); @@ -618,6 +653,9 @@ static void _load_move() #if (MOTORS >= 4) if ((st_run.mot[MOTOR_4].substep_increment = st_pre.mot[MOTOR_4].substep_increment) != 0) { #if NEW_DDA == 1 +#if defined(NEW_FWD_DIFF) && (NEW_FWD_DIFF==1) + st_run.mot[MOTOR_4].substep_increment_increment = st_pre.mot[MOTOR_4].substep_increment_increment; +#endif #else if (st_pre.mot[MOTOR_4].accumulator_correction_flag == true) { st_pre.mot[MOTOR_4].accumulator_correction_flag = false; @@ -636,6 +674,9 @@ static void _load_move() motor_4.enable(); SET_ENCODER_STEP_SIGN(MOTOR_4, st_pre.mot[MOTOR_4].step_sign); } else { +#if defined(NEW_FWD_DIFF) && (NEW_FWD_DIFF==1) + st_run.mot[MOTOR_4].substep_increment_increment = 0; +#endif motor_4.motionStopped(); } ACCUMULATE_ENCODER(MOTOR_4); @@ -643,6 +684,9 @@ static void _load_move() #if (MOTORS >= 5) if ((st_run.mot[MOTOR_5].substep_increment = st_pre.mot[MOTOR_5].substep_increment) != 0) { #if NEW_DDA == 1 +#if defined(NEW_FWD_DIFF) && (NEW_FWD_DIFF==1) + st_run.mot[MOTOR_5].substep_increment_increment = st_pre.mot[MOTOR_5].substep_increment_increment; +#endif #else if (st_pre.mot[MOTOR_5].accumulator_correction_flag == true) { st_pre.mot[MOTOR_5].accumulator_correction_flag = false; @@ -661,6 +705,9 @@ static void _load_move() motor_5.enable(); SET_ENCODER_STEP_SIGN(MOTOR_5, st_pre.mot[MOTOR_5].step_sign); } else { +#if defined(NEW_FWD_DIFF) && (NEW_FWD_DIFF==1) + st_run.mot[MOTOR_5].substep_increment_increment = 0; +#endif motor_5.motionStopped(); } ACCUMULATE_ENCODER(MOTOR_5); @@ -668,6 +715,9 @@ static void _load_move() #if (MOTORS >= 6) if ((st_run.mot[MOTOR_6].substep_increment = st_pre.mot[MOTOR_6].substep_increment) != 0) { #if NEW_DDA == 1 +#if defined(NEW_FWD_DIFF) && (NEW_FWD_DIFF==1) + st_run.mot[MOTOR_6].substep_increment_increment = st_pre.mot[MOTOR_6].substep_increment_increment; +#endif #else if (st_pre.mot[MOTOR_6].accumulator_correction_flag == true) { st_pre.mot[MOTOR_6].accumulator_correction_flag = false; @@ -686,6 +736,9 @@ static void _load_move() motor_6.enable(); SET_ENCODER_STEP_SIGN(MOTOR_6, st_pre.mot[MOTOR_6].step_sign); } else { +#if defined(NEW_FWD_DIFF) && (NEW_FWD_DIFF==1) + st_run.mot[MOTOR_6].substep_increment_increment = 0; +#endif motor_6.motionStopped(); } ACCUMULATE_ENCODER(MOTOR_6); @@ -738,7 +791,11 @@ static void _load_move() * dda_ticks_X_substeps = (int32_t)((microseconds/1000000) * f_dda * dda_substeps); */ +#if !defined(NEW_FWD_DIFF) || (NEW_FWD_DIFF==0) stat_t st_prep_line(float travel_steps[], float following_error[], float segment_time) +#else +stat_t st_prep_line(float start_velocity, float end_velocity, float travel_steps[], float following_error[], float segment_time) +#endif { stepper_debug("😶"); // trap assertion failures and other conditions that would prevent queuing the line @@ -763,6 +820,10 @@ stat_t st_prep_line(float travel_steps[], float following_error[], float segment #endif // setup motor parameters +#if defined(NEW_FWD_DIFF) && (NEW_FWD_DIFF==1) + // this is explained later + float t_v0_v1 = (float)st_pre.dda_ticks * (start_velocity + end_velocity); +#endif float correction_steps; for (uint8_t motor=0; motorgetPowerMode() == MOTOR_ALWAYS_POWERED) { return; @@ -535,7 +537,8 @@ struct Stepper { // turn off motor is only powered when moving // HOT - called from the DDA interrupt - void motionStopped() HOT_FUNC { + void motionStopped() //HOT_FUNC + { if (_power_mode == MOTOR_POWERED_IN_CYCLE) { this->enable(); _power_state = MOTOR_POWER_TIMEOUT_START; @@ -607,7 +610,11 @@ void st_prep_null(void); void st_prep_command(void *bf); // use a void pointer since we don't know about mpBuf_t yet) void st_prep_dwell(float milliseconds); void st_request_out_of_band_dwell(float microseconds); +#if !defined(NEW_FWD_DIFF) || (NEW_FWD_DIFF==0) stat_t st_prep_line(float travel_steps[], float following_error[], float segment_time) HOT_FUNC; +#else +stat_t st_prep_line(float start_velocity, float end_velocity, float travel_steps[], float following_error[], float segment_time) HOT_FUNC; +#endif stat_t st_set_ma(nvObj_t *nv); stat_t st_set_sa(nvObj_t *nv); From 65c675ca1e44011e961f11c451e7398712bf162e Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Sat, 15 Jul 2017 22:36:13 -0500 Subject: [PATCH 118/193] Added Ender config to boards.mk --- g2core/boards.mk | 11 ++++++++++- 1 file changed, 10 insertions(+), 1 deletion(-) diff --git a/g2core/boards.mk b/g2core/boards.mk index d5ce82397..85f631411 100644 --- a/g2core/boards.mk +++ b/g2core/boards.mk @@ -168,6 +168,15 @@ ifeq ("$(CONFIG)","AxiDrawv3") SETTINGS_FILE="settings_axidraw_v3.h" endif +########## +# Ender config: +# http://www.gearbest.com/3d-printers-3d-printer-kits/pp_620372.html -include $(wildcard ./board/$(STAR).mk) +ifeq ("$(CONFIG)","Quintic-Ender") + ifeq ("$(BOARD)","NONE") + BOARD=gquintic-c + endif + SETTINGS_FILE="settings_ender.h" +endif +include $(wildcard ./board/$(STAR).mk) From 578db0c12b28b8b976fb313ef38a9c611dcdef14 Mon Sep 17 00:00:00 2001 From: Riley Date: Sun, 16 Jul 2017 16:03:42 -0400 Subject: [PATCH 119/193] Added support for building the ender3d printer configs --- g2core.atsln | 8 ++++++++ g2core/boards.mk | 13 +++++++++++++ g2core/settings/settings_ender.h | 20 ++++++++++---------- g2core/stepper.h | 8 ++++---- 4 files changed, 35 insertions(+), 14 deletions(-) diff --git a/g2core.atsln b/g2core.atsln index c8f6bcae0..bd2054536 100644 --- a/g2core.atsln +++ b/g2core.atsln @@ -17,6 +17,7 @@ Global PrintrbotSimple1403-printrboardG2v3|ARM = PrintrbotSimple1403-printrboardG2v3|ARM PrintrbotSimple1608-printrboardG2v3|ARM = PrintrbotSimple1608-printrboardG2v3|ARM ProbotixV90|ARM = ProbotixV90|ARM + Quintic-Ender|ARM = Quintic-Ender|ARM sbv300|ARM = sbv300|ARM Shapeoko2|ARM = Shapeoko2|ARM shopbotShield|ARM = shopbotShield|ARM @@ -25,6 +26,7 @@ Global TestQuintic|ARM = TestQuintic|ARM TestV9|ARM = TestV9|ARM Ultimakerv9k|ARM = Ultimakerv9k|ARM + xcarve-extended|ARM = xcarve-extended|ARM Zen7x12|ARM = Zen7x12|ARM EndGlobalSection GlobalSection(ProjectConfigurationPlatforms) = postSolution @@ -47,6 +49,8 @@ Global {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.PrintrbotSimple1608-printrboardG2v3|ARM.Build.0 = PrintrbotSimple1608-printrboardG2v3|ARM {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.ProbotixV90|ARM.ActiveCfg = ProbotixV90|ARM {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.ProbotixV90|ARM.Build.0 = ProbotixV90|ARM + {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.Quintic-Ender|ARM.ActiveCfg = Quintic|ARM + {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.Quintic-Ender|ARM.Build.0 = Quintic|ARM {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.sbv300|ARM.ActiveCfg = sbv300|ARM {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.sbv300|ARM.Build.0 = sbv300|ARM {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.Shapeoko2|ARM.ActiveCfg = Shapeoko2|ARM @@ -62,6 +66,8 @@ Global {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.TestV9|ARM.Build.0 = TestV9|ARM {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.Ultimakerv9k|ARM.ActiveCfg = Ultimakerv9k|ARM {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.Ultimakerv9k|ARM.Build.0 = Ultimakerv9k|ARM + {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.xcarve-extended|ARM.ActiveCfg = xcarve-extended|ARM + {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.xcarve-extended|ARM.Build.0 = xcarve-extended|ARM {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.Zen7x12|ARM.ActiveCfg = Zen7x12|ARM {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.Zen7x12|ARM.Build.0 = Zen7x12|ARM {D7779B24-5CD6-4A1B-893C-2CAE8CF7A3A0}.G2v9k|ARM.ActiveCfg = Stub|ARM @@ -73,6 +79,7 @@ Global {D7779B24-5CD6-4A1B-893C-2CAE8CF7A3A0}.PrintrbotSimple1403-printrboardG2v3|ARM.ActiveCfg = Stub|ARM {D7779B24-5CD6-4A1B-893C-2CAE8CF7A3A0}.PrintrbotSimple1608-printrboardG2v3|ARM.ActiveCfg = Stub|ARM {D7779B24-5CD6-4A1B-893C-2CAE8CF7A3A0}.ProbotixV90|ARM.ActiveCfg = Stub|ARM + {D7779B24-5CD6-4A1B-893C-2CAE8CF7A3A0}.Quintic-Ender|ARM.ActiveCfg = Quintic|ARM {D7779B24-5CD6-4A1B-893C-2CAE8CF7A3A0}.sbv300|ARM.ActiveCfg = Stub|ARM {D7779B24-5CD6-4A1B-893C-2CAE8CF7A3A0}.Shapeoko2|ARM.ActiveCfg = Stub|ARM {D7779B24-5CD6-4A1B-893C-2CAE8CF7A3A0}.shopbotShield|ARM.ActiveCfg = Stub|ARM @@ -81,6 +88,7 @@ Global {D7779B24-5CD6-4A1B-893C-2CAE8CF7A3A0}.TestQuintic|ARM.ActiveCfg = Stub|ARM {D7779B24-5CD6-4A1B-893C-2CAE8CF7A3A0}.TestV9|ARM.ActiveCfg = Stub|ARM {D7779B24-5CD6-4A1B-893C-2CAE8CF7A3A0}.Ultimakerv9k|ARM.ActiveCfg = Stub|ARM + {D7779B24-5CD6-4A1B-893C-2CAE8CF7A3A0}.xcarve-extended|ARM.ActiveCfg = xcarve-extended|ARM {D7779B24-5CD6-4A1B-893C-2CAE8CF7A3A0}.Zen7x12|ARM.ActiveCfg = Stub|ARM EndGlobalSection GlobalSection(SolutionProperties) = preSolution diff --git a/g2core/boards.mk b/g2core/boards.mk index d5ce82397..41bdafc13 100644 --- a/g2core/boards.mk +++ b/g2core/boards.mk @@ -85,6 +85,19 @@ ifeq ("$(CONFIG)","TestQuintic") SETTINGS_FILE="settings_test.h" endif +ifeq ("$(CONFIG)","Quintic-Ender") + ifeq ("$(BOARD)","NONE") + BOARD=gquintic-c + endif + SETTINGS_FILE="settings_ender.h" +endif + +ifeq ("$(CONFIG)","Quintic-Xcarve-Extended") + ifeq ("$(BOARD)","NONE") + BOARD=gquintic-c + endif + SETTINGS_FILE="settings_xcarve_extended.h" +endif ifeq ("$(CONFIG)","TestQuadratic") ifeq ("$(BOARD)","NONE") diff --git a/g2core/settings/settings_ender.h b/g2core/settings/settings_ender.h index c1c06a672..7c47517b5 100644 --- a/g2core/settings/settings_ender.h +++ b/g2core/settings/settings_ender.h @@ -104,7 +104,7 @@ // Marlin says 80 steps/unit, and 16 microsteps, with a 200-step/rev motor #define M1_TRAVEL_PER_REV 40.64 // 1tr #define M1_MICROSTEPS 128 // 1mi 1,2,4,8,16,32 -#define M1_POLARITY 1 // 1po 0=normal, 1=reversed +#define M1_POLARITY 0 // 1po 0=normal, 1=reversed #define M1_POWER_MODE MOTOR_POWERED_IN_CYCLE // 1pm standard #define M1_POWER_LEVEL 0.8 // 1pl #define M1_TMC2130_TPWMTHRS 1200 // 1pth @@ -146,9 +146,9 @@ #define M3_MOTOR_MAP AXIS_Z #define M3_STEP_ANGLE 1.8 -#define M3_TRAVEL_PER_REV 1.5875 +#define M3_TRAVEL_PER_REV 2 #define M3_MICROSTEPS 128 -#define M3_POLARITY 0 +#define M3_POLARITY 1 #define M3_POWER_MODE MOTOR_POWERED_IN_CYCLE #define M3_POWER_LEVEL 0.6 #define M3_TMC2130_TPWMTHRS 300 @@ -213,7 +213,7 @@ #define X_VELOCITY_MAX 30000 // xvm G0 max velocity in mm/min #define X_FEEDRATE_MAX X_VELOCITY_MAX // xfr G1 max feed rate in mm/min #define X_TRAVEL_MIN 0 // xtn minimum travel - used by soft limits and homing -#define X_TRAVEL_MAX 100 // xtm travel between switches or crashes +#define X_TRAVEL_MAX 150 // xtm travel between switches or crashes #define X_JERK_MAX 15000 // xjm yes, that's "100 billion" mm/(min^3) #define X_JERK_HIGH_SPEED 20000 // xjh #define X_HOMING_INPUT 1 // xhi input used for homing or 0 to disable @@ -227,9 +227,9 @@ #define Y_VELOCITY_MAX 30000 #define Y_FEEDRATE_MAX Y_VELOCITY_MAX #define Y_TRAVEL_MIN 0 -#define Y_TRAVEL_MAX 100 +#define Y_TRAVEL_MAX 150 #define Y_JERK_MAX 15000 -#define Y_JERK_HIGH_SPEED 20000 +#define Y_JERK_HIGH_SPEED 25000 #define Y_HOMING_INPUT 4 #define Y_HOMING_DIRECTION 1 #define Y_SEARCH_VELOCITY 1500 @@ -241,7 +241,7 @@ #define Z_VELOCITY_MAX 300 #define Z_FEEDRATE_MAX Z_VELOCITY_MAX #define Z_TRAVEL_MIN 0 -#define Z_TRAVEL_MAX 125 +#define Z_TRAVEL_MAX 200 #define Z_JERK_MAX 800 #define Z_JERK_HIGH_SPEED 1600 #define Z_HOMING_INPUT 5 @@ -389,7 +389,7 @@ */ // Inputs are defined for the g2ref(a) board // Xmn (board label) -#define DI1_MODE IO_ACTIVE_LOW +#define DI1_MODE NORMALLY_CLOSED #define DI1_ACTION INPUT_ACTION_NONE #define DI1_FUNCTION INPUT_FUNCTION_NONE @@ -399,7 +399,7 @@ #define DI2_FUNCTION INPUT_FUNCTION_NONE // Ymin -#define DI3_MODE IO_MODE_DISABLED +#define DI3_MODE NORMALLY_CLOSED #define DI3_ACTION INPUT_ACTION_NONE #define DI3_FUNCTION INPUT_FUNCTION_NONE @@ -409,7 +409,7 @@ #define DI4_FUNCTION INPUT_FUNCTION_NONE // Zmin -#define DI5_MODE IO_ACTIVE_LOW +#define DI5_MODE NORMALLY_CLOSED #define DI5_ACTION INPUT_ACTION_NONE #define DI5_FUNCTION INPUT_FUNCTION_NONE diff --git a/g2core/stepper.h b/g2core/stepper.h index c9f277872..06bcf47fc 100644 --- a/g2core/stepper.h +++ b/g2core/stepper.h @@ -492,7 +492,7 @@ struct Stepper { // turn on motor in all cases unless it's disabled // this version is called from the loader, and explicitly does NOT have floating point computations // HOT - called from the DDA interrupt - void enable() HOT_FUNC + void enable() { if (_power_mode == MOTOR_DISABLED) { return; @@ -505,7 +505,7 @@ struct Stepper { // turn on motor in all cases unless it's disabled // this version has the timeout computed here, as provided - void enable(float timeout) HOT_FUNC + void enable(float timeout) { if (_power_mode == MOTOR_DISABLED) { return; @@ -523,7 +523,7 @@ struct Stepper { // turn off motor in all cases unless it's permanently enabled // HOT - called from the DDA interrupt - void disable() HOT_FUNC + void disable() { if (this->getPowerMode() == MOTOR_ALWAYS_POWERED) { return; @@ -535,7 +535,7 @@ struct Stepper { // turn off motor is only powered when moving // HOT - called from the DDA interrupt - void motionStopped() HOT_FUNC { + void motionStopped() { if (_power_mode == MOTOR_POWERED_IN_CYCLE) { this->enable(); _power_state = MOTOR_POWER_TIMEOUT_START; From d68d94d3f42f881abf59cd38922fab42d3be5f04 Mon Sep 17 00:00:00 2001 From: Riley Date: Mon, 17 Jul 2017 20:41:31 -0400 Subject: [PATCH 120/193] some more settings improvements --- g2core/settings/settings_ender.h | 38 ++++++++++++++++---------------- 1 file changed, 19 insertions(+), 19 deletions(-) diff --git a/g2core/settings/settings_ender.h b/g2core/settings/settings_ender.h index 7c47517b5..782ef196a 100644 --- a/g2core/settings/settings_ender.h +++ b/g2core/settings/settings_ender.h @@ -27,11 +27,11 @@ */ /***********************************************************************/ -/**** Printrbot Play profile *******************************************/ +/**** Ender 3d Printer profile *****************************************/ /***********************************************************************/ // ***> NOTE: The init message must be a single line with no CRs or LFs -#define INIT_MESSAGE "Initializing configs to Ender Printer Play profile" +#define INIT_MESSAGE "Initializing configs to Ender Printer profile" #define PROBE_REPORT_ENABLE 1 #ifndef PI #define PI 3.14159628 @@ -70,7 +70,7 @@ #define JSON_VERBOSITY JV_LINENUM // one of: JV_SILENT, JV_FOOTER, JV_CONFIGS, JV_MESSAGES, JV_LINENUM, JV_VERBOSE #define QUEUE_REPORT_VERBOSITY QR_OFF // one of: QR_OFF, QR_SINGLE, QR_TRIPLE -#define STATUS_REPORT_VERBOSITY SR_FILTERED // one of: SR_OFF, SR_FILTERED, SR_VERBOSE +#define STATUS_REPORT_VERBOSITY SR_VERBOSE // one of: SR_OFF, SR_FILTERED, SR_VERBOSE #define STATUS_REPORT_MIN_MS 100 // milliseconds - enforces a viable minimum #define STATUS_REPORT_INTERVAL_MS 250 // milliseconds - set $SV=0 to disable @@ -97,13 +97,13 @@ // *** motor settings ************************************************************************************ -#define MOTOR_POWER_MODE MOTOR_POWERED_IN_CYCLE // default motor power mode (see cmMotorPowerMode in stepper.h) +#define MOTOR_POWER_MODE MOTOR_ALWAYS_POWERED // default motor power mode (see cmMotorPowerMode in stepper.h) // 80 steps/mm at 1/16 microstepping = 40 mm/rev #define M1_MOTOR_MAP AXIS_X // 1ma #define M1_STEP_ANGLE 1.8 // 1sa // Marlin says 80 steps/unit, and 16 microsteps, with a 200-step/rev motor -#define M1_TRAVEL_PER_REV 40.64 // 1tr -#define M1_MICROSTEPS 128 // 1mi 1,2,4,8,16,32 +#define M1_TRAVEL_PER_REV 40 // 1tr +#define M1_MICROSTEPS 32 // 1mi 1,2,4,8,16,32 #define M1_POLARITY 0 // 1po 0=normal, 1=reversed #define M1_POWER_MODE MOTOR_POWERED_IN_CYCLE // 1pm standard #define M1_POWER_LEVEL 0.8 // 1pl @@ -117,7 +117,7 @@ #define M1_TMC2130_HEND 0 // 1hend #define M1_TMC2130_HSTRT 0 // 1hsrt #define M1_TMC2130_SMIN 5 // 1smin -#define M1_TMC2130_SMAX 5 // 1smax +#define M1_TMC2130_SMAX 5 // 1smax #define M1_TMC2130_SUP 2 // 1sup #define M1_TMC2130_SDN 1 // 1sdn @@ -125,10 +125,10 @@ #define M2_MOTOR_MAP AXIS_Y #define M2_STEP_ANGLE 1.8 // Marlin says 80 steps/unit, and 16 microsteps, with a 200-step/rev motor -#define M2_TRAVEL_PER_REV 40.64 -#define M2_MICROSTEPS 128 -#define M2_POLARITY 0 -#define M2_POWER_MODE MOTOR_POWERED_IN_CYCLE +#define M2_TRAVEL_PER_REV 40 +#define M2_MICROSTEPS 32 +#define M2_POLARITY 1 +#define M2_POWER_MODE MOTOR_ALWAYS_POWERED #define M2_POWER_LEVEL 0.8 #define M2_TMC2130_TPWMTHRS 1200 #define M2_TMC2130_TCOOLTHRS 1000 @@ -146,11 +146,11 @@ #define M3_MOTOR_MAP AXIS_Z #define M3_STEP_ANGLE 1.8 -#define M3_TRAVEL_PER_REV 2 -#define M3_MICROSTEPS 128 +#define M3_TRAVEL_PER_REV 8 +#define M3_MICROSTEPS 32 #define M3_POLARITY 1 -#define M3_POWER_MODE MOTOR_POWERED_IN_CYCLE -#define M3_POWER_LEVEL 0.6 +#define M3_POWER_MODE MOTOR_ALWAYS_POWERED +#define M3_POWER_LEVEL 0.5 #define M3_TMC2130_TPWMTHRS 300 #define M3_TMC2130_TCOOLTHRS 200 #define M3_TMC2130_THIGH 10 @@ -230,8 +230,8 @@ #define Y_TRAVEL_MAX 150 #define Y_JERK_MAX 15000 #define Y_JERK_HIGH_SPEED 25000 -#define Y_HOMING_INPUT 4 -#define Y_HOMING_DIRECTION 1 +#define Y_HOMING_INPUT 3 +#define Y_HOMING_DIRECTION 0 #define Y_SEARCH_VELOCITY 1500 #define Y_LATCH_VELOCITY 200 #define Y_LATCH_BACKOFF 5 @@ -319,7 +319,7 @@ #define TEMPERATURE_SENSOR_1_TYPE Thermistor> #define TEMPERATURE_SENSOR_1_INIT { \ /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ - /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ + /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 200 \ } #else // #define TEMPERATURE_SENSOR_1_TYPE PT100> @@ -404,7 +404,7 @@ #define DI3_FUNCTION INPUT_FUNCTION_NONE // Ymax -#define DI4_MODE IO_ACTIVE_LOW +#define DI4_MODE IO_MODE_DISABLED #define DI4_ACTION INPUT_ACTION_NONE #define DI4_FUNCTION INPUT_FUNCTION_NONE From 2cddd940d4bf28d474f015eb303b72f6e037904a Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Tue, 18 Jul 2017 09:18:47 -0500 Subject: [PATCH 121/193] Update Printrbot Play settings, added CONFIG=PrintrbotPlayQuintic --- g2core/boards.mk | 7 + g2core/settings/settings_Printrbot_Play.h | 528 +++++++++++++--------- 2 files changed, 313 insertions(+), 222 deletions(-) diff --git a/g2core/boards.mk b/g2core/boards.mk index 85f631411..700127a0d 100644 --- a/g2core/boards.mk +++ b/g2core/boards.mk @@ -135,6 +135,13 @@ ifeq ("$(CONFIG)","PrintrbotPlay") SETTINGS_FILE="settings_Printrbot_Play.h" endif +ifeq ("$(CONFIG)","PrintrbotPlayQuintic") + ifeq ("$(BOARD)","NONE") + BOARD=gquintic-c + endif + SETTINGS_FILE="settings_Printrbot_Play.h" +endif + ########## # Ultimaker configs: diff --git a/g2core/settings/settings_Printrbot_Play.h b/g2core/settings/settings_Printrbot_Play.h index 6342af679..cb66fcd20 100644 --- a/g2core/settings/settings_Printrbot_Play.h +++ b/g2core/settings/settings_Printrbot_Play.h @@ -39,149 +39,219 @@ //**** GLOBAL / GENERAL SETTINGS ****************************************************** -#define JUNCTION_INTEGRATION_TIME 1.1 // cornering - between 0.10 and 2.00 (higher is faster) -#define CHORDAL_TOLERANCE 0.01 // chordal accuracy for arc drawing (in mm) +#define JUNCTION_INTEGRATION_TIME 1.2 // cornering - between 0.10 and 2.00 (higher is faster) +//{jt:1.2} +//{jt:0.75} +#define CHORDAL_TOLERANCE 0.01 // chordal accuracy for arc drawing (in mm) -#define SOFT_LIMIT_ENABLE 0 // 0=off, 1=on -#define HARD_LIMIT_ENABLE 1 // 0=off, 1=on -#define SAFETY_INTERLOCK_ENABLE 1 // 0=off, 1=on +#define SOFT_LIMIT_ENABLE 0 // 0=off, 1=on +#define HARD_LIMIT_ENABLE 1 // 0=off, 1=on +#define SAFETY_INTERLOCK_ENABLE 1 // 0=off, 1=on -#define SPINDLE_ENABLE_POLARITY 1 // 0=active low, 1=active high -#define SPINDLE_DIR_POLARITY 0 // 0=clockwise is low, 1=clockwise is high -#define SPINDLE_PAUSE_ON_HOLD true -#define SPINDLE_DWELL_TIME 1.0 +#define SPINDLE_ENABLE_POLARITY 1 // 0=active low, 1=active high +#define SPINDLE_DIR_POLARITY 0 // 0=clockwise is low, 1=clockwise is high +#define SPINDLE_PAUSE_ON_HOLD true +#define SPINDLE_DWELL_TIME 1.0 -#define COOLANT_MIST_POLARITY 1 // 0=active low, 1=active high -#define COOLANT_FLOOD_POLARITY 1 // 0=active low, 1=active high -#define COOLANT_PAUSE_ON_HOLD false +#define COOLANT_MIST_POLARITY 1 // 0=active low, 1=active high +#define COOLANT_FLOOD_POLARITY 1 // 0=active low, 1=active high +#define COOLANT_PAUSE_ON_HOLD false + +#define TRAVERSE_AT_HIGH_JERK true // EXPERIMENTAL!! // Communications and reporting settings -#define MARLIN_COMPAT_ENABLED true // enable marlin compatibility mode -#define COMM_MODE JSON_MODE // one of: TEXT_MODE, JSON_MODE -#define XIO_ENABLE_FLOW_CONTROL FLOW_CONTROL_RTS // FLOW_CONTROL_OFF, FLOW_CONTROL_RTS -#define XIO_UART_MUTES_WHEN_USB_CONNECTED 1 // Mute the UART when USB connects +#define MARLIN_COMPAT_ENABLED true // enable marlin compatibility mode +#define COMM_MODE JSON_MODE // one of: TEXT_MODE, JSON_MODE +#define XIO_ENABLE_FLOW_CONTROL FLOW_CONTROL_RTS // FLOW_CONTROL_OFF, FLOW_CONTROL_RTS +#define XIO_UART_MUTES_WHEN_USB_CONNECTED 1 // Mute the UART when USB connects -#define TEXT_VERBOSITY TV_VERBOSE // one of: TV_SILENT, TV_VERBOSE -#define JSON_VERBOSITY JV_LINENUM // one of: JV_SILENT, JV_FOOTER, JV_CONFIGS, JV_MESSAGES, JV_LINENUM, JV_VERBOSE -#define QUEUE_REPORT_VERBOSITY QR_OFF // one of: QR_OFF, QR_SINGLE, QR_TRIPLE +#define TEXT_VERBOSITY TV_VERBOSE // one of: TV_SILENT, TV_VERBOSE +#define JSON_VERBOSITY JV_LINENUM // one of: JV_SILENT, JV_FOOTER, JV_CONFIGS, JV_MESSAGES, JV_LINENUM, JV_VERBOSE +#define QUEUE_REPORT_VERBOSITY QR_OFF // one of: QR_OFF, QR_SINGLE, QR_TRIPLE -#define STATUS_REPORT_VERBOSITY SR_FILTERED // one of: SR_OFF, SR_FILTERED, SR_VERBOSE -#define STATUS_REPORT_MIN_MS 100 // milliseconds - enforces a viable minimum -#define STATUS_REPORT_INTERVAL_MS 250 // milliseconds - set $SV=0 to disable +#define STATUS_REPORT_VERBOSITY SR_FILTERED // one of: SR_OFF, SR_FILTERED, SR_VERBOSE +#define STATUS_REPORT_MIN_MS 100 // milliseconds - enforces a viable minimum +#define STATUS_REPORT_INTERVAL_MS 250 // milliseconds - set $SV=0 to disable // Defaults for 3DP -//#define STATUS_REPORT_DEFAULTS -//"line","posx","posy","posz","posa","vel","he1t","he1st","he1at","feed","vel","unit","path","stat" +//#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","vel","he1t","he1st","he1at","feed","unit","path","stat" // There are no heater two or three, but these would show those: ,"he2t","he2st","he2at","he3t","he3st","he3at" // Defaults for motion debugging -//#define STATUS_REPORT_DEFAULTS -//"line","posx","posy","posz","posa","vel","he1t","he1st","he1at","he2t","he2st","he2at","he3t","he3st","he3at","_fe5","_fe4","feed","vel","unit","path","stat" +//#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","he1t","he1st","he1at","he2t","he2st","he2at","he3t","he3st","he3at","_fe5","_fe4","feed","vel","unit","path","stat" // Defaults for PID tuning -#define STATUS_REPORT_DEFAULTS \ - "line", "posx", "posy", "posz", "posa", "vel", "he1t", "he1st", "he1at", "he1op", "pid1p", "pid1i", "pid1d", \ - "feed", "vel", "unit", "path", "stat" +//#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","he1t","he1st","he1at","he1op","pid1p","pid1i","pid1d","feed","vel","unit","path","stat" +// Defaults for thermistor tuning +#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","he1t","he1st","he1at","he1op","he3t","he3st","he3at","he3op","feed","vel","unit","path","stat","1ts","1sgr","1csa","2ts","2sgr","2csa","3ts","3sgr","3csa","4ts","4sgr","4csa" +//#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","he1t","he1st","he1at","he1tr","he1tv","he1op","he2t","he2st","he2at","he2tr","he2tv","he2op","he3t","he3st","he3at","he3tr","he3tv","he3op","feed","vel","unit","path","stat","_xs1","_xs2","_xs3","_xs4" // Gcode startup defaults -#define GCODE_DEFAULT_UNITS MILLIMETERS // MILLIMETERS or INCHES -#define GCODE_DEFAULT_PLANE CANON_PLANE_XY // CANON_PLANE_XY, CANON_PLANE_XZ, or CANON_PLANE_YZ -#define GCODE_DEFAULT_COORD_SYSTEM G54 // G54, G55, G56, G57, G58 or G59 -#define GCODE_DEFAULT_PATH_CONTROL PATH_CONTINUOUS +#define GCODE_DEFAULT_UNITS MILLIMETERS // MILLIMETERS or INCHES +#define GCODE_DEFAULT_PLANE CANON_PLANE_XY // CANON_PLANE_XY, CANON_PLANE_XZ, or CANON_PLANE_YZ +#define GCODE_DEFAULT_COORD_SYSTEM G54 // G54, G55, G56, G57, G58 or G59 +#define GCODE_DEFAULT_PATH_CONTROL PATH_CONTINUOUS #define GCODE_DEFAULT_DISTANCE_MODE ABSOLUTE_DISTANCE_MODE // *** motor settings ************************************************************************************ -#define MOTOR_POWER_MODE MOTOR_POWERED_IN_CYCLE // default motor power mode (see cmMotorPowerMode in stepper.h) +#define MOTOR_POWER_MODE MOTOR_POWERED_IN_CYCLE // default motor power mode (see cmMotorPowerMode in stepper.h) // 80 steps/mm at 1/16 microstepping = 40 mm/rev -#define M1_MOTOR_MAP AXIS_X // 1ma -#define M1_STEP_ANGLE 1.8 // 1sa -#define M1_TRAVEL_PER_REV 40.64 // 1tr -#define M1_MICROSTEPS 32 // 1mi 1,2,4,8,16,32 -#define M1_POLARITY 1 // 1po 0=normal, 1=reversed -#define M1_POWER_MODE MOTOR_POWER_MODE // 1pm standard -#define M1_POWER_LEVEL 0.4 // 1mp +#define M1_MOTOR_MAP AXIS_X // 1ma +#define M1_STEP_ANGLE 1.8 // 1sa +// Marlin says 80 steps/unit, and 16 microsteps, with a 200-step/rev motor +#define M1_TRAVEL_PER_REV 40.64 // 1tr +#define M1_MICROSTEPS 128 // 1mi 1,2,4,8,16,32 +#define M1_POLARITY 1 // 1po 0=normal, 1=reversed +#define M1_POWER_MODE MOTOR_POWERED_IN_CYCLE // 1pm standard +#define M1_POWER_LEVEL 0.8 // 1pl +#define M1_TMC2130_TPWMTHRS 1200 // 1pth +#define M1_TMC2130_TCOOLTHRS 1000 // 1cth +#define M1_TMC2130_THIGH 10 // 1hth +#define M1_TMC2130_SGT 4 // 1sgt +#define M1_TMC2130_TBL 2 // 1tbl +#define M1_TMC2130_PWM_GRAD 1 // 1pgrd +#define M1_TMC2130_PWM_AMPL 200 // 1pamp +#define M1_TMC2130_HEND 0 // 1hend +#define M1_TMC2130_HSTRT 0 // 1hsrt +#define M1_TMC2130_SMIN 5 // 1smin +#define M1_TMC2130_SMAX 5 // 1smax +#define M1_TMC2130_SUP 2 // 1sup +#define M1_TMC2130_SDN 1 // 1sdn // 80 steps/mm at 1/16 microstepping = 40 mm/rev -#define M5_MOTOR_MAP AXIS_Y -#define M5_STEP_ANGLE 1.8 -#define M5_TRAVEL_PER_REV 40.64 -#define M5_MICROSTEPS 32 -#define M5_POLARITY 0 -#define M5_POWER_MODE MOTOR_POWER_MODE -#define M5_POWER_LEVEL 0.4 - -#define M2_MOTOR_MAP AXIS_Z -#define M2_STEP_ANGLE 1.8 -#define M2_TRAVEL_PER_REV 1.5875 -#define M2_MICROSTEPS 32 -#define M2_POLARITY 1 -#define M2_POWER_MODE MOTOR_POWER_MODE -#define M2_POWER_LEVEL 0.4 - -// 96 steps/mm at 1/16 microstepping = 33.3333 mm/rev -#define M4_MOTOR_MAP AXIS_A -#define M4_STEP_ANGLE 1.8 -#define M4_TRAVEL_PER_REV 360 // degrees moved per motor rev -#define M4_MICROSTEPS 32 -#define M4_POLARITY 0 -#define M4_POWER_MODE MOTOR_POWER_MODE -#define M4_POWER_LEVEL 0.4 - -// 96 steps/mm at 1/16 microstepping = 33.3333 mm/rev -#define M3_MOTOR_MAP AXIS_B -#define M3_STEP_ANGLE 1.8 -#define M3_TRAVEL_PER_REV 360 // degrees moved per motor rev -#define M3_MICROSTEPS 32 -#define M3_POLARITY 0 -#define M3_POWER_MODE MOTOR_POWER_MODE -#define M3_POWER_LEVEL 0.35 +#define M2_MOTOR_MAP AXIS_Y +#define M2_STEP_ANGLE 1.8 +// Marlin says 80 steps/unit, and 16 microsteps, with a 200-step/rev motor +#define M2_TRAVEL_PER_REV 40.64 +#define M2_MICROSTEPS 128 +#define M2_POLARITY 0 +#define M2_POWER_MODE MOTOR_POWERED_IN_CYCLE +#define M2_POWER_LEVEL 0.8 +#define M2_TMC2130_TPWMTHRS 1200 +#define M2_TMC2130_TCOOLTHRS 1000 +#define M2_TMC2130_THIGH 10 +#define M2_TMC2130_SGT 4 +#define M2_TMC2130_TBL 2 +#define M2_TMC2130_PWM_GRAD 1 +#define M2_TMC2130_PWM_AMPL 200 +#define M2_TMC2130_HEND 0 +#define M2_TMC2130_HSTRT 0 +#define M2_TMC2130_SMIN 5 +#define M2_TMC2130_SMAX 5 +#define M2_TMC2130_SUP 2 +#define M2_TMC2130_SDN 1 + +#define M3_MOTOR_MAP AXIS_Z +#define M3_STEP_ANGLE 1.8 +#define M3_TRAVEL_PER_REV 1.5875 +#define M3_MICROSTEPS 128 +#define M3_POLARITY 0 +#define M3_POWER_MODE MOTOR_POWERED_IN_CYCLE +#define M3_POWER_LEVEL 0.6 +#define M3_TMC2130_TPWMTHRS 300 +#define M3_TMC2130_TCOOLTHRS 200 +#define M3_TMC2130_THIGH 10 +#define M3_TMC2130_SGT 4 +#define M3_TMC2130_TBL 2 +#define M3_TMC2130_PWM_GRAD 1 +#define M3_TMC2130_PWM_AMPL 200 +#define M3_TMC2130_HEND 0 +#define M3_TMC2130_HSTRT 0 +#define M3_TMC2130_SMIN 5 +#define M3_TMC2130_SMAX 12 +#define M3_TMC2130_SUP 2 +#define M3_TMC2130_SDN 2 + +#define M4_MOTOR_MAP AXIS_A +#define M4_STEP_ANGLE 1.8 +#define M4_TRAVEL_PER_REV 360 // degrees moved per motor rev +#define M4_MICROSTEPS 128 +#define M4_POLARITY 0 +#define M4_POWER_MODE MOTOR_POWER_MODE +#define M4_POWER_LEVEL 0.8 +#define M4_TMC2130_TPWMTHRS 180000 +#define M4_TMC2130_TCOOLTHRS 100000 +#define M4_TMC2130_THIGH 10 +#define M4_TMC2130_SGT 3 +#define M4_TMC2130_TBL 2 +#define M4_TMC2130_PWM_GRAD 15 +#define M4_TMC2130_PWM_AMPL 255 +#define M4_TMC2130_HEND 0 +#define M4_TMC2130_HSTRT 0 +#define M4_TMC2130_SMIN 5 +#define M4_TMC2130_SMAX 10 +#define M4_TMC2130_SUP 3 +#define M4_TMC2130_SDN 0 + +#define M5_MOTOR_MAP AXIS_B +#define M5_STEP_ANGLE 1.8 +#define M5_TRAVEL_PER_REV 40 +#define M5_MICROSTEPS 128 +#define M5_POLARITY 1 +#define M5_POWER_MODE MOTOR_DISABLED +#define M5_POWER_LEVEL 0.8 +#define M5_TMC2130_TPWMTHRS 1200 +#define M5_TMC2130_TCOOLTHRS 1000 +#define M5_TMC2130_THIGH 10 +#define M5_TMC2130_SGT 4 +#define M5_TMC2130_TBL 2 +#define M5_TMC2130_PWM_GRAD 1 +#define M5_TMC2130_PWM_AMPL 200 +#define M5_TMC2130_HEND 0 +#define M5_TMC2130_HSTRT 0 +#define M5_TMC2130_SMIN 5 +#define M5_TMC2130_SMAX 12 +#define M5_TMC2130_SUP 2 +#define M5_TMC2130_SDN 1 // *** axis settings ********************************************************************************** -#define X_AXIS_MODE AXIS_STANDARD // xam see canonical_machine.h cmAxisMode for valid values +#define X_AXIS_MODE AXIS_STANDARD // xam see canonical_machine.h cmAxisMode for valid values #define X_VELOCITY_MAX 30000 // xvm G0 max velocity in mm/min -#define X_FEEDRATE_MAX X_VELOCITY_MAX // xfr G1 max feed rate in mm/min -#define X_TRAVEL_MIN 0 // xtn minimum travel - used by soft limits and homing +#define X_FEEDRATE_MAX X_VELOCITY_MAX // xfr G1 max feed rate in mm/min +#define X_TRAVEL_MIN 0 // xtn minimum travel - used by soft limits and homing #define X_TRAVEL_MAX 100 // xtm travel between switches or crashes #define X_JERK_MAX 15000 // xjm yes, that's "100 billion" mm/(min^3) #define X_JERK_HIGH_SPEED 20000 // xjh -#define X_HOMING_INPUT 1 // xhi input used for homing or 0 to disable -#define X_HOMING_DIRECTION 0 // xhd 0=search moves negative, 1= search moves positive +#define X_HOMING_INPUT 1 // xhi input used for homing or 0 to disable +#define X_HOMING_DIRECTION 0 // xhd 0=search moves negative, 1= search moves positive #define X_SEARCH_VELOCITY 3000 // xsv move in negative direction -#define X_LATCH_VELOCITY 200 // xlv mm/min +#define X_LATCH_VELOCITY 200 // xlv mm/min #define X_LATCH_BACKOFF 5 // xlb mm -#define X_ZERO_BACKOFF 0.5 // xzb mm +#define X_ZERO_BACKOFF 0.5 // xzb mm -#define Y_AXIS_MODE AXIS_STANDARD +#define Y_AXIS_MODE AXIS_STANDARD #define Y_VELOCITY_MAX 30000 -#define Y_FEEDRATE_MAX Y_VELOCITY_MAX -#define Y_TRAVEL_MIN 0 +#define Y_FEEDRATE_MAX Y_VELOCITY_MAX +#define Y_TRAVEL_MIN 0 #define Y_TRAVEL_MAX 100 #define Y_JERK_MAX 15000 #define Y_JERK_HIGH_SPEED 20000 #define Y_HOMING_INPUT 4 -#define Y_HOMING_DIRECTION 1 +#define Y_HOMING_DIRECTION 1 #define Y_SEARCH_VELOCITY 1500 -#define Y_LATCH_VELOCITY 200 +#define Y_LATCH_VELOCITY 200 #define Y_LATCH_BACKOFF 5 -#define Y_ZERO_BACKOFF 0.5 +#define Y_ZERO_BACKOFF 0.5 -#define Z_AXIS_MODE AXIS_STANDARD +#define Z_AXIS_MODE AXIS_STANDARD #define Z_VELOCITY_MAX 300 #define Z_FEEDRATE_MAX Z_VELOCITY_MAX -#define Z_TRAVEL_MIN 0 +#define Z_TRAVEL_MIN 0 #define Z_TRAVEL_MAX 125 #define Z_JERK_MAX 800 #define Z_JERK_HIGH_SPEED 1600 #define Z_HOMING_INPUT 5 #define Z_HOMING_DIRECTION 0 #define Z_SEARCH_VELOCITY 200 -#define Z_LATCH_VELOCITY 100 +#define Z_LATCH_VELOCITY 100 #define Z_LATCH_BACKOFF 5 -#define Z_ZERO_BACKOFF 0 +#define Z_ZERO_BACKOFF 0 + +#define G55_Z_OFFSET 0.35 // higher number is farther away from the bed // Rotary values are chosen to make the motor react the same as X for testing /*************************************************************************************** @@ -201,209 +271,223 @@ * ***************************************************************************************/ -#define A_AXIS_MODE AXIS_RADIUS +#define A_AXIS_MODE AXIS_RADIUS #define A_RADIUS 5.30516476972984 -//#define A_VELOCITY_MAX 25920.0 // ~40 mm/s, 2,400 mm/min -//#define A_FEEDRATE_MAX 25920.0/2.0 // ~20 mm/s, 1,200 mm/min #define A_VELOCITY_MAX 77760.0 // G0 rate ~120 mm/s, 2,400 mm/min #define A_FEEDRATE_MAX 9720.0 // 9720.0 = G1 rate ~15 mm/s, 900 mm/min -#define A_TRAVEL_MIN 0 -#define A_TRAVEL_MAX 10 -#define A_JERK_MAX 648000 // 1,000 million mm/min^3 = 648000 - // * a million IF it's over a million - // c=2*pi*r, r=5.30516476972984, d=c/360, s=((1000*60)/d) -#define A_HOMING_INPUT 0 -#define A_HOMING_DIRECTION 0 -#define A_SEARCH_VELOCITY 2000 -#define A_LATCH_VELOCITY 2000 -#define A_LATCH_BACKOFF 5 -#define A_ZERO_BACKOFF 2 -#define A_JERK_HIGH_SPEED A_JERK_MAX - -#define B_AXIS_MODE AXIS_DISABLED -#define B_RADIUS 1 -#define B_VELOCITY_MAX 3600 -#define B_FEEDRATE_MAX B_VELOCITY_MAX -#define B_TRAVEL_MIN 0 -#define B_TRAVEL_MAX -1 -//#define B_JERK_MAX 20000000 -#define B_JERK_MAX 20 -#define B_HOMING_INPUT 0 -#define B_HOMING_DIRECTION 0 -#define B_SEARCH_VELOCITY 600 -#define B_LATCH_VELOCITY 100 -#define B_LATCH_BACKOFF 10 -#define B_ZERO_BACKOFF 2 -#define B_JERK_HIGH_SPEED A_JERK_MAX - - +#define A_TRAVEL_MIN 0 +#define A_TRAVEL_MAX 10 +#define A_JERK_MAX 40000.0 // ~20 million mm/min^3 {ajm:48147.7} +#define A_HOMING_INPUT 0 +#define A_HOMING_DIRECTION 0 +#define A_SEARCH_VELOCITY 2000 +#define A_LATCH_VELOCITY 2000 +#define A_LATCH_BACKOFF 5 +#define A_ZERO_BACKOFF 2 +#define A_JERK_HIGH_SPEED 120000.0 // + + +#define B_AXIS_MODE AXIS_RADIUS +#define B_RADIUS 1.428 +#define B_VELOCITY_MAX 144443.0 // G0 rate ~60 mm/s, 3,600 mm/min +#define B_FEEDRATE_MAX 96295.4 // ~40 mm/s +#define B_TRAVEL_MIN 0 +#define B_TRAVEL_MAX 10 +#define B_JERK_MAX 180554.0 // ~75 million mm/min^3 +#define B_HOMING_INPUT 0 +#define B_HOMING_DIRECTION 0 +#define B_SEARCH_VELOCITY 2000 +#define B_LATCH_VELOCITY 2000 +#define B_LATCH_BACKOFF 5 +#define B_ZERO_BACKOFF 2 +#define B_JERK_HIGH_SPEED 361108.0 // ~150 million mm/min^3 + + //*** Input / output settings *** //** Temperature Sensors ** +//#include "device/max31865/max31865.h" + +//#define USING_A_MAX31865 1 + #define HAS_TEMPERATURE_SENSOR_1 true #if HAS_TEMPERATURE_SENSOR_1 // Must choose Thermistor or PT100 #if 1 // 1 if a Thermistor, 0 if a PT100 - #define TEMPERATURE_SENSOR_1_TYPE Thermistor + #define TEMPERATURE_SENSOR_1_TYPE Thermistor> #define TEMPERATURE_SENSOR_1_INIT { \ - /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ - /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ + /*T1:*/ 25.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ + /*R1:*/ 99500.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 200 \ } #else - #define TEMPERATURE_SENSOR_1_TYPE PT100 - #define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} + // #define TEMPERATURE_SENSOR_1_TYPE PT100> + // #define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 2000, /*inline_resistance*/0.0} + #define TEMPERATURE_SENSOR_1_TYPE PT100> + #define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 430, /*inline_resistance*/0, spiBus, spiCSPinMux.getCS(5)} #endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_1 -#define EXTRUDER_1_OUTPUT_PIN kOutput1_PinNumber -#define EXTRUDER_1_FAN_PIN kOutput3_PinNumber +#define EXTRUDER_1_OUTPUT_PIN kHeaterOutput1_PinNumber +#define EXTRUDER_1_FAN_PIN kOutput5_PinNumber -#define HAS_TEMPERATURE_SENSOR_2 true +#define HAS_TEMPERATURE_SENSOR_2 false #if HAS_TEMPERATURE_SENSOR_2 #if 1 // 1 if a Thermistor, 0 if a PT100 - #define TEMPERATURE_SENSOR_2_TYPE Thermistor + #define TEMPERATURE_SENSOR_2_TYPE Thermistor> #define TEMPERATURE_SENSOR_2_INIT { \ - /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ - /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ + /*T1:*/ 25.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ + /*R1:*/ 99500.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 200 \ } #else - #define TEMPERATURE_SENSOR_2_TYPE PT100 - #define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} + #define TEMPERATURE_SENSOR_2_TYPE PT100> + #define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 200, /*inline_resistance*/0.0} +// #define TEMPERATURE_SENSOR_2_TYPE PT100> +// #define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 430, /*inline_resistance*/0, spiBus, spiCSPinMux.getCS(5)} #endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_2 -#define EXTRUDER_2_OUTPUT_PIN kOutput2_PinNumber +#define EXTRUDER_2_OUTPUT_PIN kHeaterOutput2_PinNumber #define HAS_TEMPERATURE_SENSOR_3 true #if HAS_TEMPERATURE_SENSOR_3 #if 1 // 1 if a Thermistor, 0 if a PT100 - #define TEMPERATURE_SENSOR_3_TYPE Thermistor + #define TEMPERATURE_SENSOR_3_TYPE Thermistor> #define TEMPERATURE_SENSOR_3_INIT { \ /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ - /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ + /*R1:*/ 100000.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 200 \ } #else - #define TEMPERATURE_SENSOR_3_TYPE PT100 - #define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} + // #define TEMPERATURE_SENSOR_3_TYPE PT100> + // #define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 200, /*inline_resistance*/0.0} + #define TEMPERATURE_SENSOR_3_TYPE PT100> + #define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 430, /*inline_resistance*/0, spiBus, spiCSPinMux.getCS(6)} + #endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_3 -#define BED_OUTPUT_PIN kOutput11_PinNumber - +#define BED_OUTPUT_PIN kHeaterOutput11_PinNumber //** Digital Inputs ** - /* - IO_MODE_DISABLED - IO_ACTIVE_LOW aka NORMALLY_OPEN - IO_ACTIVE_HIGH aka NORMALLY_CLOSED - - INPUT_ACTION_NONE - INPUT_ACTION_STOP - INPUT_ACTION_FAST_STOP - INPUT_ACTION_HALT - INPUT_ACTION_RESET - - INPUT_FUNCTION_NONE - INPUT_FUNCTION_LIMIT - INPUT_FUNCTION_INTERLOCK - INPUT_FUNCTION_SHUTDOWN - INPUT_FUNCTION_PANIC -*/ + IO_MODE_DISABLED + IO_ACTIVE_LOW aka NORMALLY_OPEN + IO_ACTIVE_HIGH aka NORMALLY_CLOSED + + INPUT_ACTION_NONE + INPUT_ACTION_STOP + INPUT_ACTION_FAST_STOP + INPUT_ACTION_HALT + INPUT_ACTION_RESET + + INPUT_FUNCTION_NONE + INPUT_FUNCTION_LIMIT + INPUT_FUNCTION_INTERLOCK + INPUT_FUNCTION_SHUTDOWN + INPUT_FUNCTION_PANIC + */ // Inputs are defined for the g2ref(a) board // Xmn (board label) -#define DI1_MODE IO_ACTIVE_HIGH -#define DI1_ACTION INPUT_ACTION_NONE -#define DI1_FUNCTION INPUT_FUNCTION_NONE +#define DI1_MODE IO_ACTIVE_LOW +#define DI1_ACTION INPUT_ACTION_NONE +#define DI1_FUNCTION INPUT_FUNCTION_NONE // Xmax -#define DI2_MODE IO_MODE_DISABLED -#define DI2_ACTION INPUT_ACTION_NONE -#define DI2_FUNCTION INPUT_FUNCTION_NONE +#define DI2_MODE IO_MODE_DISABLED +#define DI2_ACTION INPUT_ACTION_NONE +#define DI2_FUNCTION INPUT_FUNCTION_NONE // Ymin -#define DI3_MODE IO_MODE_DISABLED -#define DI3_ACTION INPUT_ACTION_NONE -#define DI3_FUNCTION INPUT_FUNCTION_NONE +#define DI3_MODE IO_MODE_DISABLED +#define DI3_ACTION INPUT_ACTION_NONE +#define DI3_FUNCTION INPUT_FUNCTION_NONE // Ymax -#define DI4_MODE IO_ACTIVE_HIGH -#define DI4_ACTION INPUT_ACTION_NONE -#define DI4_FUNCTION INPUT_FUNCTION_NONE +#define DI4_MODE IO_ACTIVE_LOW +#define DI4_ACTION INPUT_ACTION_NONE +#define DI4_FUNCTION INPUT_FUNCTION_NONE // Zmin -#define DI5_MODE IO_ACTIVE_LOW // Z probe -#define DI5_ACTION INPUT_ACTION_NONE -#define DI5_FUNCTION INPUT_FUNCTION_NONE +#define DI5_MODE IO_ACTIVE_LOW +#define DI5_ACTION INPUT_ACTION_NONE +#define DI5_FUNCTION INPUT_FUNCTION_NONE // Zmax -#define DI6_MODE IO_MODE_DISABLED -#define DI6_ACTION INPUT_ACTION_NONE -#define DI6_FUNCTION INPUT_FUNCTION_NONE +#define DI6_MODE IO_MODE_DISABLED +#define DI6_ACTION INPUT_ACTION_NONE +#define DI6_FUNCTION INPUT_FUNCTION_NONE // Shutdown (Amin on v9 board) -#define DI7_MODE IO_MODE_DISABLED -#define DI7_ACTION INPUT_ACTION_NONE -#define DI7_FUNCTION INPUT_FUNCTION_NONE +#define DI7_MODE IO_MODE_DISABLED +#define DI7_ACTION INPUT_ACTION_NONE +#define DI7_FUNCTION INPUT_FUNCTION_NONE // High Voltage Z Probe In (Amax on v9 board) -#define DI8_MODE IO_ACTIVE_LOW -#define DI8_ACTION INPUT_ACTION_NONE -#define DI8_FUNCTION INPUT_FUNCTION_NONE +#define DI8_MODE IO_ACTIVE_LOW +#define DI8_ACTION INPUT_ACTION_NONE +#define DI8_FUNCTION INPUT_FUNCTION_NONE // Hardware interlock input -#define DI9_MODE IO_MODE_DISABLED -#define DI9_ACTION INPUT_ACTION_NONE -#define DI9_FUNCTION INPUT_FUNCTION_NONE +#define DI9_MODE IO_MODE_DISABLED +#define DI9_ACTION INPUT_ACTION_NONE +#define DI9_FUNCTION INPUT_FUNCTION_NONE -// Extruder1_PWM -#define DO1_MODE IO_ACTIVE_HIGH +//Extruder1_PWM +#define DO1_MODE IO_ACTIVE_HIGH // unavailable, is the extruder output -// Extruder2_PWM -#define DO2_MODE IO_ACTIVE_HIGH +//Extruder2_PWM +#define DO2_MODE IO_ACTIVE_HIGH // unavailable, is the extruder output -// Fan1A_PWM -#define DO3_MODE IO_ACTIVE_HIGH +//Fan1A_PWM +#define DO3_MODE IO_ACTIVE_LOW -// Fan1B_PWM -#define DO4_MODE IO_ACTIVE_HIGH +//Fan1B_PWM +#define DO4_MODE IO_ACTIVE_HIGH -#define DO5_MODE IO_ACTIVE_HIGH -#define DO6_MODE IO_ACTIVE_HIGH -#define DO7_MODE IO_ACTIVE_HIGH -#define DO8_MODE IO_ACTIVE_HIGH +#define DO5_MODE IO_ACTIVE_HIGH +#define DO6_MODE IO_ACTIVE_HIGH +#define DO7_MODE IO_ACTIVE_HIGH +#define DO8_MODE IO_ACTIVE_HIGH // 5V Fan -// SAFEin (Output) signal -#define DO9_MODE IO_ACTIVE_HIGH +//SAFEin (Output) signal +#define DO9_MODE IO_ACTIVE_HIGH -#define DO10_MODE IO_ACTIVE_HIGH +#define DO10_MODE IO_ACTIVE_HIGH -// Header Bed FET -#define DO11_MODE IO_ACTIVE_HIGH +//Header Bed FET +#define DO11_MODE IO_ACTIVE_LOW // unavailable, is the extruder output -// Indicator_LED -#define DO12_MODE IO_ACTIVE_HIGH +//Indicator_LED +#define DO12_MODE IO_ACTIVE_HIGH -#define DO13_MODE IO_ACTIVE_HIGH +#define DO13_MODE IO_ACTIVE_HIGH /*** Extruders / Heaters ***/ -#define MIN_FAN_TEMP 50.0 -#define MAX_FAN_TEMP 100.0 +#define MIN_FAN_VALUE 0.4 // (he1fm) at MIN_FAN_TEMP the fan comes on at this spped (0.0-1.0) +#define MAX_FAN_VALUE 1.0 // (he1fp) at MAX_FAN_TEMP the fan is at this spped (0.0-1.0) +#define MIN_FAN_TEMP 50.0 // (he1fl) at this temp the fan starts to ramp up linearly +#define MAX_FAN_TEMP 100.0 // (he1fh) at this temperature the fan is at "full speed" (MAX_FAN_VALUE) + +// PID debug string: {sr:{"he1t":t,"he1st":t,"pid1p":t, "pid1i":t, "pid1d":t, "pid1f":t, "he1op":t, "line":t, "stat":t}} + +#define H1_DEFAULT_ENABLE true +#define H1_DEFAULT_P 5 +#define H1_DEFAULT_I 0.01 +#define H1_DEFAULT_D 500 +#define H1_DEFAULT_F 0.0015 -#define H1_DEFAULT_ENABLE true -#define H1_DEFAULT_P 7.0 -#define H1_DEFAULT_I 0.05 -#define H1_DEFAULT_D 150.0 +#define H2_DEFAULT_ENABLE false +#define H2_DEFAULT_P 7.0 +#define H2_DEFAULT_I 0.05 +#define H2_DEFAULT_D 150.0 +#define H2_DEFAULT_F 0.0 -#define H2_DEFAULT_ENABLE false -#define H2_DEFAULT_P 7.0 -#define H2_DEFAULT_I 0.05 -#define H2_DEFAULT_D 150.0 +#define H3_DEFAULT_ENABLE true +#define H3_DEFAULT_P 20.0 +#define H3_DEFAULT_I 0.05 +#define H3_DEFAULT_D 50 +#define H3_DEFAULT_F 0.0015 -#define H3_DEFAULT_ENABLE false -#define H3_DEFAULT_P 9.0 -#define H3_DEFAULT_I 0.12 -#define H3_DEFAULT_D 400.0 +#define TEMP_MIN_BED_RISE_DEGREES_OVER_TIME 0.1 From 5d552e43146b8bc18cf18b269ffb7210b240d83e Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Tue, 18 Jul 2017 09:22:24 -0500 Subject: [PATCH 122/193] Add differential ADC support to Thermistor object --- g2core/temperature.cpp | 54 ++++++++++++++++++++++++++++++------------ 1 file changed, 39 insertions(+), 15 deletions(-) diff --git a/g2core/temperature.cpp b/g2core/temperature.cpp index 11cdc8866..63a9e3f8b 100755 --- a/g2core/temperature.cpp +++ b/g2core/temperature.cpp @@ -227,6 +227,8 @@ struct ValueHistory { template struct Thermistor { + const bool differential; + float c1, c2, c3, pullup_resistance; // We'll pull adc top value from the adc_pin.getTop() @@ -234,6 +236,9 @@ struct Thermistor { uint16_t raw_adc_value = 0; float raw_adc_voltage = 0.0; + const float variance_max = 1.1; + ValueHistory<20> history {variance_max}; + typedef Thermistor type; // References for thermistor formulas: @@ -241,28 +246,28 @@ struct Thermistor { // http://hydraraptor.blogspot.com/2012/11/more-accurate-thermistor-tables.html Thermistor(const float temp_low, const float temp_med, const float temp_high, const float res_low, const float res_med, const float res_high, const float pullup_resistance_) - : pullup_resistance{ pullup_resistance_ }, - adc_pin {ADC_t::is_differential ? kDifferentialPair : kNormal, [&]{this->adc_has_new_value();} } + : differential{ adc_pin.is_differential }, pullup_resistance{ pullup_resistance_ }, + adc_pin {adc_pin.is_differential ? kDifferentialPair : kNormal, [&]{this->adc_has_new_value();} } { setup(temp_low, temp_med, temp_high, res_low, res_med, res_high); adc_pin.setInterrupts(kPinInterruptOnChange|kInterruptPriorityLow); adc_pin.setVoltageRange(kSystemVoltage, 0, //get_voltage_of_temp(min_temp), kSystemVoltage, //get_voltage_of_temp(max_temp), - 6400.0); + 1000000.0); }; template Thermistor(const float temp_low, const float temp_med, const float temp_high, const float res_low, const float res_med, const float res_high, const float pullup_resistance_, Ts&&... additional_values) - : pullup_resistance{ pullup_resistance_ }, - adc_pin{ADC_t::is_differential ? kDifferentialPair : kNormal, [&]{this->adc_has_new_value();}, additional_values...} + : differential{ adc_pin.is_differential }, pullup_resistance{ pullup_resistance_ }, + adc_pin{adc_pin.is_differential ? kDifferentialPair : kNormal, [&]{this->adc_has_new_value();}, additional_values...} { setup(temp_low, temp_med, temp_high, res_low, res_med, res_high); adc_pin.setInterrupts(kPinInterruptOnChange|kInterruptPriorityLow); adc_pin.setVoltageRange(kSystemVoltage, 0, //get_voltage_of_temp(min_temp), kSystemVoltage, //get_voltage_of_temp(max_temp), - 6400.0); + 1000000.0); }; void setup(const float temp_low, const float temp_med, const float temp_high, const float res_low, const float res_med, const float res_high) { @@ -295,8 +300,7 @@ struct Thermistor { return -1; // invalid temperature from a thermistor } - float v = raw_adc_voltage; // convert the ADC value to a voltage - float r = ((pullup_resistance * v) / (kSystemVoltage - v)); // resistance of thermistor + float r = get_resistance(); // resistance of thermistor if ((r < 0) || (r > TEMP_MIN_DISCONNECTED_RESISTANCE)) { return -1; @@ -308,14 +312,33 @@ struct Thermistor { }; float get_resistance() { - if (raw_adc_value < 1) { - return -1; // invalid temperature from a thermistor + float r; + raw_adc_voltage = history.value(); + + if (isnan(raw_adc_voltage)) { + return -1; } - float v = raw_adc_voltage; // convert the ADC value to a voltage - return ((pullup_resistance * v) / (kSystemVoltage - v)); // resistance of thermistor + if (differential) { + float v = raw_adc_voltage / kSystemVoltage; + r = (v * 2.0 * pullup_resistance)/(1.0 - v);// - inline_resistance; + } + else { + float v = raw_adc_voltage; + r = ((pullup_resistance * v) / (kSystemVoltage - v));// - inline_resistance; + } + return r; }; +// float get_resistance() { +// if (raw_adc_value < 1) { +// return -1; // invalid temperature from a thermistor +// } +// +// float v = raw_adc_voltage; // convert the ADC value to a voltage +// return ((pullup_resistance * v) / (kSystemVoltage - v)); // resistance of thermistor +// }; + uint16_t get_raw_value() { return raw_adc_value; }; @@ -330,8 +353,9 @@ struct Thermistor { // Call back function from the ADC to tell it that the ADC has a new sample... void adc_has_new_value() { - raw_adc_voltage = (raw_adc_voltage * 2.0 + adc_pin.getVoltage())/3.0; - raw_adc_value = (adc_pin.getRaw() + (9 * raw_adc_value))/10; + raw_adc_value = adc_pin.getRaw(); + float v = fabs(adc_pin.getVoltage()); + history.add_sample(v); }; }; @@ -340,7 +364,7 @@ template struct PT100 { const float pullup_resistance; const float inline_resistance; - bool differential; + const bool differential; bool gives_raw_resistance = false; ADC_t adc_pin; From f4e7beccbf20df6b903ea4021e92948882de62e4 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Tue, 18 Jul 2017 09:31:47 -0500 Subject: [PATCH 123/193] Removed accidental duplicate Quintic-Ender in boards.mk --- g2core/boards.mk | 7 ------- 1 file changed, 7 deletions(-) diff --git a/g2core/boards.mk b/g2core/boards.mk index 4666ccfad..b2a643358 100644 --- a/g2core/boards.mk +++ b/g2core/boards.mk @@ -85,13 +85,6 @@ ifeq ("$(CONFIG)","TestQuintic") SETTINGS_FILE="settings_test.h" endif -ifeq ("$(CONFIG)","Quintic-Ender") - ifeq ("$(BOARD)","NONE") - BOARD=gquintic-c - endif - SETTINGS_FILE="settings_ender.h" -endif - ifeq ("$(CONFIG)","Quintic-Xcarve-Extended") ifeq ("$(BOARD)","NONE") BOARD=gquintic-c From 14209f87271b9d95757800407ae03ac083781d43 Mon Sep 17 00:00:00 2001 From: Riley Date: Sun, 23 Jul 2017 17:58:50 -0400 Subject: [PATCH 124/193] added xcarve_extended setting file --- g2core/settings/settings_xcarve_extended.h | 335 +++++++++++++++++++++ 1 file changed, 335 insertions(+) create mode 100644 g2core/settings/settings_xcarve_extended.h diff --git a/g2core/settings/settings_xcarve_extended.h b/g2core/settings/settings_xcarve_extended.h new file mode 100644 index 000000000..3efa8f090 --- /dev/null +++ b/g2core/settings/settings_xcarve_extended.h @@ -0,0 +1,335 @@ +/* + * settings_xcarve_extended.h - Xcarve Extended table + * This file is part of the TinyG project + * + * Copyright (c) 2010 - 2017 Riley C. Porter & Alden S. Hart, Jr. + * + * This file ("the software") is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License, version 2 as published by the + * Free Software Foundation. You should have received a copy of the GNU General Public + * License, version 2 along with the software. If not, see . + * + * As a special exception, you may use this file as part of a software library without + * restriction. Specifically, if other files instantiate templates or use macros or + * inline functions from this file, or you compile this file and link it with other + * files to produce an executable, this file does not by itself cause the resulting + * executable to be covered by the GNU General Public License. This exception does not + * however invalidate any other reasons why the executable file might be covered by the + * GNU General Public License. + * + * THE SOFTWARE IS DISTRIBUTED IN THE HOPE THAT IT WILL BE USEFUL, BUT WITHOUT ANY + * WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES + * OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT + * SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF + * OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + */ +/* Note: The values in this file are the default settings that are loaded + * into a virgin EEPROM, and can be changed using the config commands. + * After initial load the EEPROM values (or changed values) are used. + * + * System and hardware settings that you shouldn't need to change + * are in system.h Application settings that also shouldn't need + * to be changed are in tinyg.h + */ + +/***********************************************************************/ +/**** Xcarve Extended profile *******************************************/ +/***********************************************************************/ + +// ***> NOTE: The init message must be a single line with no CRs or LFs +#define INIT_MESSAGE "Initializing configs to Xcarve Extended 1000mm profile" + +//**** GLOBAL / GENERAL SETTINGS ****************************************************** + +// Machine configuration settings + +#define JUNCTION_INTEGRATION_TIME 0.75 // cornering - between 0.10 and 2.00 (higher is faster) +#define CHORDAL_TOLERANCE 0.01 // chordal tolerance for arcs (in mm) + +#define SOFT_LIMIT_ENABLE 0 // 0=off, 1=on +#define HARD_LIMIT_ENABLE 0 // 0=off, 1=on +#define SAFETY_INTERLOCK_ENABLE 1 // 0=off, 1=on + +#define SPINDLE_ENABLE_POLARITY 1 // 0=active low, 1=active high +#define SPINDLE_DIR_POLARITY 0 // 0=clockwise is low, 1=clockwise is high +#define SPINDLE_PAUSE_ON_HOLD true +#define SPINDLE_DWELL_TIME 1.0 + +#define COOLANT_MIST_POLARITY 1 // 0=active low, 1=active high +#define COOLANT_FLOOD_POLARITY 1 // 0=active low, 1=active high +#define COOLANT_PAUSE_ON_HOLD false + +// Communications and reporting settings + +#define COMM_MODE JSON_MODE // one of: TEXT_MODE, JSON_MODE +#define XIO_ENABLE_FLOW_CONTROL FLOW_CONTROL_RTS // FLOW_CONTROL_OFF, FLOW_CONTROL_RTS + +#define TEXT_VERBOSITY TV_VERBOSE // one of: TV_SILENT, TV_VERBOSE +#define JSON_VERBOSITY JV_MESSAGES // one of: JV_SILENT, JV_FOOTER, JV_CONFIGS, JV_MESSAGES, JV_LINENUM, JV_VERBOSE +#define QUEUE_REPORT_VERBOSITY QR_OFF // one of: QR_OFF, QR_SINGLE, QR_TRIPLE + +#define STATUS_REPORT_VERBOSITY SR_FILTERED // one of: SR_OFF, SR_FILTERED, SR_VERBOSE + +#define STATUS_REPORT_MIN_MS 100 // milliseconds - enforces a viable minimum +#define STATUS_REPORT_INTERVAL_MS 250 // milliseconds - set $SV=0 to disable + +//#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","bcr","feed","vel","unit","coor","dist","admo","frmo","momo","stat" +#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","bcr","feed","vel","momo","stat" + +// Alternate SRs that report in drawable units +//#define STATUS_REPORT_DEFAULTS "line","vel","mpox","mpoy","mpoz","mpoa","coor","ofsa","ofsx","ofsy","ofsz","dist","unit","stat","homz","homy","homx","momo" +//#define STATUS_REPORT_DEFAULTS "_ts1","_cs1","_es1","_xs1","_fe1","line","posx","posy","posz","vel","stat" + +// Gcode startup defaults +#define GCODE_DEFAULT_UNITS MILLIMETERS // MILLIMETERS or INCHES +#define GCODE_DEFAULT_PLANE CANON_PLANE_XY // CANON_PLANE_XY, CANON_PLANE_XZ, or CANON_PLANE_YZ +#define GCODE_DEFAULT_COORD_SYSTEM G54 // G54, G55, G56, G57, G58 or G59 +#define GCODE_DEFAULT_PATH_CONTROL PATH_CONTINUOUS +#define GCODE_DEFAULT_DISTANCE_MODE ABSOLUTE_DISTANCE_MODE + + +// *** motor settings ************************************************************************************ + +#define MOTOR_POWER_MODE MOTOR_POWERED_IN_CYCLE // default motor power mode (see cmMotorPowerMode in stepper.h) +#define MOTOR_POWER_TIMEOUT 20.00 // motor power timeout in seconds + +// *** motor settings *** + +/* Mapping for dual gantry setup */ +#define M1_MOTOR_MAP AXIS_X // 1ma +#define M1_STEP_ANGLE 1.8 // 1sa +#define M1_TRAVEL_PER_REV 36.54 // 1tr +#define M1_MICROSTEPS 32 // 1mi 1,2,4,8 +#define M1_POLARITY 0 // 1po 0=normal, 1=reversed +#define M1_POWER_MODE MOTOR_POWER_MODE // 1pm TRUE=low power idle enabled +#define M1_POWER_LEVEL 0.6 + +#define M1_TMC2130_TPWMTHRS 1200 // 1pth +#define M1_TMC2130_TCOOLTHRS 1000 // 1cth +#define M1_TMC2130_THIGH 10 // 1hth +#define M1_TMC2130_SGT 4 // 1sgt +#define M1_TMC2130_TBL 2 // 1tbl +#define M1_TMC2130_PWM_GRAD 1 // 1pgrd +#define M1_TMC2130_PWM_AMPL 200 // 1pamp +#define M1_TMC2130_HEND 0 // 1hend +#define M1_TMC2130_HSTRT 0 // 1hsrt +#define M1_TMC2130_SMIN 5 // 1smin +#define M1_TMC2130_SMAX 5 // 1smax +#define M1_TMC2130_SUP 2 // 1sup +#define M1_TMC2130_SDN 1 // 1sdn + + + +#define M2_MOTOR_MAP AXIS_Y +#define M2_STEP_ANGLE 1.8 +#define M2_TRAVEL_PER_REV 36.54 +#define M2_MICROSTEPS 32 +#define M2_POLARITY 1 +#define M2_POWER_MODE MOTOR_POWER_MODE +#define M2_POWER_LEVEL 0.6 + +#define M2_TMC2130_TPWMTHRS 1200 +#define M2_TMC2130_TCOOLTHRS 1000 +#define M2_TMC2130_THIGH 10 +#define M2_TMC2130_SGT 4 +#define M2_TMC2130_TBL 2 +#define M2_TMC2130_PWM_GRAD 1 +#define M2_TMC2130_PWM_AMPL 200 +#define M2_TMC2130_HEND 0 +#define M2_TMC2130_HSTRT 0 +#define M2_TMC2130_SMIN 5 +#define M2_TMC2130_SMAX 5 +#define M2_TMC2130_SUP 2 +#define M2_TMC2130_SDN 1 + +#define M3_MOTOR_MAP AXIS_Y +#define M3_STEP_ANGLE 1.8 +#define M3_TRAVEL_PER_REV 36.54 +#define M3_MICROSTEPS 32 +#define M3_POLARITY 0 +#define M3_POWER_MODE MOTOR_POWER_MODE +#define M3_POWER_LEVEL 0.6 + +#define M3_TMC2130_TPWMTHRS 300 +#define M3_TMC2130_TCOOLTHRS 200 +#define M3_TMC2130_THIGH 10 +#define M3_TMC2130_SGT 4 +#define M3_TMC2130_TBL 2 +#define M3_TMC2130_PWM_GRAD 1 +#define M3_TMC2130_PWM_AMPL 200 +#define M3_TMC2130_HEND 0 +#define M3_TMC2130_HSTRT 0 +#define M3_TMC2130_SMIN 5 +#define M3_TMC2130_SMAX 12 +#define M3_TMC2130_SUP 2 +#define M3_TMC2130_SDN 2 + +#define M4_MOTOR_MAP AXIS_Z +#define M4_STEP_ANGLE 1.8 +#define M4_TRAVEL_PER_REV 1.25 +#define M4_MICROSTEPS 32 +#define M4_POLARITY 0 +#define M4_POWER_MODE MOTOR_POWER_MODE +#define M4_POWER_LEVEL 0.5 + +#define M4_TMC2130_TPWMTHRS 180000 +#define M4_TMC2130_TCOOLTHRS 100000 +#define M4_TMC2130_THIGH 10 +#define M4_TMC2130_SGT 3 +#define M4_TMC2130_TBL 2 +#define M4_TMC2130_PWM_GRAD 15 +#define M4_TMC2130_PWM_AMPL 255 +#define M4_TMC2130_HEND 0 +#define M4_TMC2130_HSTRT 0 +#define M4_TMC2130_SMIN 5 +#define M4_TMC2130_SMAX 10 +#define M4_TMC2130_SUP 3 +#define M4_TMC2130_SDN 0 + +#define M5_MOTOR_MAP AXIS_B +#define M5_STEP_ANGLE 1.8 +#define M5_TRAVEL_PER_REV 40 +#define M5_MICROSTEPS 128 +#define M5_POLARITY 1 +#define M5_POWER_MODE MOTOR_DISABLED +#define M5_POWER_LEVEL 0.8 +#define M5_TMC2130_TPWMTHRS 1200 +#define M5_TMC2130_TCOOLTHRS 1000 +#define M5_TMC2130_THIGH 10 +#define M5_TMC2130_SGT 4 +#define M5_TMC2130_TBL 2 +#define M5_TMC2130_PWM_GRAD 1 +#define M5_TMC2130_PWM_AMPL 200 +#define M5_TMC2130_HEND 0 +#define M5_TMC2130_HSTRT 0 +#define M5_TMC2130_SMIN 5 +#define M5_TMC2130_SMAX 12 +#define M5_TMC2130_SUP 2 +#define M5_TMC2130_SDN 1 + +// *** axis settings ********************************************************************************** + + +#define X_AXIS_MODE AXIS_STANDARD // xam see canonical_machine.h cmAxisMode for valid values +#define X_VELOCITY_MAX 16000 // xvm G0 max velocity in mm/min +#define X_FEEDRATE_MAX X_VELOCITY_MAX // xfr G1 max feed rate in mm/min +#define X_TRAVEL_MIN 0 // xtn minimum travel - used by soft limits and homing +#define X_TRAVEL_MAX 1000 // xtm maximum travel - used by soft limits and homing +#define X_JERK_MAX 5000 // xjm yes, that's "5 billion" mm/(min^3) +#define X_JERK_HIGH_SPEED X_JERK_MAX // xjh +#define X_HOMING_INPUT 1 // xhi input used for homing or 0 to disable +#define X_HOMING_DIR 0 // xhd 0 to search to minimum, 1 to search to maximum +#define X_SEARCH_VELOCITY 3000 // xsv minus means move to minimum switch +#define X_LATCH_VELOCITY 100 // xlv mm/min +#define X_LATCH_BACKOFF 4 // xlb mm +#define X_ZERO_BACKOFF 0.5 // xzb mm + +#define Y_AXIS_MODE AXIS_STANDARD +#define Y_VELOCITY_MAX 16000 +#define Y_FEEDRATE_MAX Y_VELOCITY_MAX +#define Y_TRAVEL_MIN 0 +#define Y_TRAVEL_MAX 1000 +#define Y_JERK_MAX 5000 +#define Y_JERK_HIGH_SPEED Y_JERK_MAX +#define Y_HOMING_INPUT 3 +#define Y_HOMING_DIR 0 +#define Y_SEARCH_VELOCITY 3000 +#define Y_LATCH_VELOCITY 100 +#define Y_LATCH_BACKOFF 4 +#define Y_ZERO_BACKOFF 0.5 + +#define Z_AXIS_MODE AXIS_STANDARD +#define Z_VELOCITY_MAX 300 +#define Z_FEEDRATE_MAX Z_VELOCITY_MAX +#define Z_TRAVEL_MIN 0 +#define Z_TRAVEL_MAX 100 +#define Z_JERK_MAX 25 // 50,000,000 +#define Z_JERK_HIGH_SPEED Z_JERK_MAX +#define Z_HOMING_INPUT 5 +#define Z_HOMING_DIR 0 +#define Z_SEARCH_VELOCITY Z_VELOCITY_MAX +#define Z_LATCH_VELOCITY 100 +#define Z_LATCH_BACKOFF 4 +#define Z_ZERO_BACKOFF 0.5 + +//*** Input / output settings *** +/* + IO_MODE_DISABLED + IO_ACTIVE_LOW aka NORMALLY_OPEN + IO_ACTIVE_HIGH aka NORMALLY_CLOSED + + INPUT_ACTION_NONE + INPUT_ACTION_STOP + INPUT_ACTION_FAST_STOP + INPUT_ACTION_HALT + INPUT_ACTION_RESET + + INPUT_FUNCTION_NONE + INPUT_FUNCTION_LIMIT + INPUT_FUNCTION_INTERLOCK + INPUT_FUNCTION_SHUTDOWN + INPUT_FUNCTION_PANIC + */ +// Xmin on v9 board +#define DI1_MODE NORMALLY_CLOSED +//#define DI1_ACTION INPUT_ACTION_STOP +#define DI1_ACTION INPUT_ACTION_NONE +#define DI1_FUNCTION INPUT_FUNCTION_LIMIT + +// Xmax +#define DI2_MODE NORMALLY_CLOSED +//#define DI2_ACTION INPUT_ACTION_STOP +#define DI2_ACTION INPUT_ACTION_NONE +#define DI2_FUNCTION INPUT_FUNCTION_LIMIT + +// Ymin +#define DI3_MODE NORMALLY_CLOSED +//#define DI3_ACTION INPUT_ACTION_STOP +#define DI3_ACTION INPUT_ACTION_NONE +#define DI3_FUNCTION INPUT_FUNCTION_LIMIT + +// Ymax +#define DI4_MODE NORMALLY_CLOSED +//#define DI4_ACTION INPUT_ACTION_STOP +#define DI4_ACTION INPUT_ACTION_NONE +#define DI4_FUNCTION INPUT_FUNCTION_LIMIT + +// Zmin +#define DI5_MODE IO_ACTIVE_HIGH // Z probe +#define DI5_ACTION INPUT_ACTION_NONE +#define DI5_FUNCTION INPUT_FUNCTION_NONE + +// Zmax +#define DI6_MODE NORMALLY_CLOSED +//#define DI6_ACTION INPUT_ACTION_STOP +#define DI6_ACTION INPUT_ACTION_NONE +#define DI6_FUNCTION INPUT_FUNCTION_LIMIT + +// Amin +#define DI7_MODE IO_MODE_DISABLED +#define DI7_ACTION INPUT_ACTION_NONE +#define DI7_FUNCTION INPUT_FUNCTION_NONE + +// Amax +#define DI8_MODE IO_MODE_DISABLED +#define DI8_ACTION INPUT_ACTION_NONE +#define DI8_FUNCTION INPUT_FUNCTION_NONE + +// Hardware interlock input +#define DI9_MODE IO_MODE_DISABLED +#define DI9_ACTION INPUT_ACTION_NONE +#define DI9_FUNCTION INPUT_FUNCTION_NONE + +// *** PWM SPINDLE CONTROL *** + +#define P1_PWM_FREQUENCY 5000 // in Hz +#define P1_CW_SPEED_LO 3000 // in RPM (arbitrary units) +#define P1_CW_SPEED_HI 12000 +#define P1_CW_PHASE_LO 0.15 // phase [0..1] +#define P1_CW_PHASE_HI 0.81 +#define P1_CCW_SPEED_LO 0 +#define P1_CCW_SPEED_HI 0 +#define P1_CCW_PHASE_LO 0.1 +#define P1_CCW_PHASE_HI 0.1 +#define P1_PWM_PHASE_OFF 0.0 From e9328503e8e00a24eae7e9d164441862d3558394 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Mon, 14 Aug 2017 15:50:27 -0500 Subject: [PATCH 125/193] Refactor Temperature code, pulling the circuits out of the PT100 and Thermistor --- g2core/device/max31865/max31865.h | 43 +++-- g2core/settings/settings_Printrbot_Play.h | 38 ++-- g2core/settings/settings_Ultimaker_2_Plus.h | 56 +++--- g2core/temperature.cpp | 194 ++++++++++++-------- 4 files changed, 181 insertions(+), 150 deletions(-) diff --git a/g2core/device/max31865/max31865.h b/g2core/device/max31865/max31865.h index 5f4610406..92ab71b58 100644 --- a/g2core/device/max31865/max31865.h +++ b/g2core/device/max31865/max31865.h @@ -67,10 +67,15 @@ struct MAX31865 final { // Timer to keep track of when we need to do another periodic update Motate::Timeout _check_timer; + // The resulting value is relative to the pullup resistance + // To return the correct resistance, we need the pullup value + float _pullup_resistance; + // Constructor - this is the only time we directly use the SBIBus template MAX31865(SPIBus_t &spi_bus, const chipSelect_t &_cs, + float pullup_resistance = 430, // 430 is the value used on the Adafruit breakout bool is_three_pin = false, bool fifty_hz = true ) @@ -81,15 +86,18 @@ struct MAX31865 final { 400, // min_between_cs_delay_ns 400, // cs_to_sck_delay_ns 80 // between_word_delay_ns - )} + )}, + _pullup_resistance{pullup_resistance} { init(is_three_pin, fifty_hz); }; template - MAX31865(std::function &&_interrupt, + MAX31865(const Motate::PinOptions_t options, // completely ignored, but for compatibility with ADCPin + std::function &&_interrupt, SPIBus_t &spi_bus, const chipSelect_t &_cs, + float pullup_resistance = 430, // 430 is the value used on the Adafruit breakout bool is_three_pin = false, bool fifty_hz = true ) @@ -101,6 +109,7 @@ struct MAX31865 final { 400, // cs_to_sck_delay_ns 80 // between_word_delay_ns )}, + _pullup_resistance{pullup_resistance}, _interrupt_handler{std::move(_interrupt)} { init(is_three_pin, fifty_hz); @@ -175,12 +184,12 @@ struct MAX31865 final { uint8_t high; uint8_t low; } _rtd_value_raw; - float _rtd_value = -1; + int32_t _rtd_value = -1; bool _rtd_value_needs_read = false; void _postReadRTD() { bool fault_detected = _rtd_value_raw.low & 0x01; uint16_t rtd_value_int = (_rtd_value_raw.high << 7) | (_rtd_value_raw.low >> 1); - _rtd_value = (float)rtd_value_int / 32768.0; + _rtd_value = rtd_value_int; if (fault_detected) { _fault_status_needs_read = true; } @@ -387,12 +396,15 @@ struct MAX31865 final { } }; + // getRaw is to return the last sampled value int32_t getRaw() { - uint16_t rtd_value_int = (_rtd_value_raw.high << 7) | (_rtd_value_raw.low >> 1); - return rtd_value_int; + return _rtd_value; }; + + // getValue is supposed to request a new value, block, and then return the result + // PUNT - return the same as getRaw() int32_t getValue() { - return _rtd_value; + return getRaw(); }; int32_t getBottom() { return 0; @@ -414,23 +426,10 @@ struct MAX31865 final { { _vref = vref; - // uint16_t min_expected_int = (uint16_t)((min_expected/vref) * 32767.0) << 1; - // fault_low.high = (min_expected_int >> 8) & 0xff; - // fault_low.low = min_expected_int & 0xff; - // fault_low_needs_written = true; - // - // if (max_expected > 0) { - // uint16_t max_expected_int = (uint16_t)((max_expected/vref) * 32767.0) << 1; - // fault_high.high = (max_expected_int >> 8) & 0xff; - // fault_high.low = max_expected_int & 0xff; - // fault_high_needs_written = true; - // } - - // differential should always be false - // we can't control the resolution, so ignore ideal_steps too + // All of the rest are ignored, but here for compatibility of interface }; float getVoltage() { - return _rtd_value * _vref; + return ((getRaw()*_pullup_resistance)/32768.0) * _vref; }; operator float() { return getVoltage(); }; diff --git a/g2core/settings/settings_Printrbot_Play.h b/g2core/settings/settings_Printrbot_Play.h index cb66fcd20..0310fb270 100644 --- a/g2core/settings/settings_Printrbot_Play.h +++ b/g2core/settings/settings_Printrbot_Play.h @@ -307,37 +307,42 @@ //** Temperature Sensors ** -//#include "device/max31865/max31865.h" +#include "device/max31865/max31865.h" -//#define USING_A_MAX31865 1 +#define USING_A_MAX31865 1 #define HAS_TEMPERATURE_SENSOR_1 true #if HAS_TEMPERATURE_SENSOR_1 -// Must choose Thermistor or PT100 -#if 1 // 1 if a Thermistor, 0 if a PT100 - #define TEMPERATURE_SENSOR_1_TYPE Thermistor> +// #define TEMPERATURE_SENSOR_1_CIRCUIT_TYPE ADCCircuitSimplePullup +// #define TEMPERATURE_SENSOR_1_CIRCUIT_INIT { /*pullup_resistance:*/ 4700 } +// #define TEMPERATURE_SENSOR_1_TYPE Thermistor +// #define TEMPERATURE_SENSOR_1_INIT { \ +// /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ +// /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, &temperature_sensor_1_circuit \ +// } + + #define TEMPERATURE_SENSOR_1_CIRCUIT_TYPE ADCCircuitRawResistance + #define TEMPERATURE_SENSOR_1_CIRCUIT_INIT { } + #define TEMPERATURE_SENSOR_1_TYPE Thermistor> #define TEMPERATURE_SENSOR_1_INIT { \ - /*T1:*/ 25.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ - /*R1:*/ 99500.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 200 \ + /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ + /*R1:*/ 99500.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 10500.0 \ + /*MAX31865 config*/ spiBus, spiCSPinMux.getCS(5), 150000 \ } -#else - // #define TEMPERATURE_SENSOR_1_TYPE PT100> - // #define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 2000, /*inline_resistance*/0.0} - #define TEMPERATURE_SENSOR_1_TYPE PT100> - #define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 430, /*inline_resistance*/0, spiBus, spiCSPinMux.getCS(5)} -#endif // 0 or 1 + #endif // HAS_TEMPERATURE_SENSOR_1 #define EXTRUDER_1_OUTPUT_PIN kHeaterOutput1_PinNumber #define EXTRUDER_1_FAN_PIN kOutput5_PinNumber + #define HAS_TEMPERATURE_SENSOR_2 false #if HAS_TEMPERATURE_SENSOR_2 #if 1 // 1 if a Thermistor, 0 if a PT100 #define TEMPERATURE_SENSOR_2_TYPE Thermistor> #define TEMPERATURE_SENSOR_2_INIT { \ /*T1:*/ 25.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ - /*R1:*/ 99500.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 200 \ + /*R1:*/ 99500.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 10500.0 \ } #else #define TEMPERATURE_SENSOR_2_TYPE PT100> @@ -349,13 +354,14 @@ #define EXTRUDER_2_OUTPUT_PIN kHeaterOutput2_PinNumber -#define HAS_TEMPERATURE_SENSOR_3 true + +#define HAS_TEMPERATURE_SENSOR_3 false #if HAS_TEMPERATURE_SENSOR_3 #if 1 // 1 if a Thermistor, 0 if a PT100 #define TEMPERATURE_SENSOR_3_TYPE Thermistor> #define TEMPERATURE_SENSOR_3_INIT { \ /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ - /*R1:*/ 100000.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 200 \ + /*R1:*/ 99500.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 10500.0 \ } #else // #define TEMPERATURE_SENSOR_3_TYPE PT100> diff --git a/g2core/settings/settings_Ultimaker_2_Plus.h b/g2core/settings/settings_Ultimaker_2_Plus.h index f63961ff0..7bdf9621b 100644 --- a/g2core/settings/settings_Ultimaker_2_Plus.h +++ b/g2core/settings/settings_Ultimaker_2_Plus.h @@ -135,7 +135,7 @@ #define M1_TMC2130_HEND 0 // 1hend #define M1_TMC2130_HSTRT 0 // 1hsrt #define M1_TMC2130_SMIN 5 // 1smin -#define M1_TMC2130_SMAX 5 // 1smax +#define M1_TMC2130_SMAX 5 // 1smax #define M1_TMC2130_SUP 2 // 1sup #define M1_TMC2130_SDN 1 // 1sdn @@ -375,19 +375,15 @@ M100.1 ({{ajh:144000.0}}) #define HAS_TEMPERATURE_SENSOR_1 true #if HAS_TEMPERATURE_SENSOR_1 -// Must choose Thermistor or PT100 -#if 0 // 1 if a Thermistor, 0 if a PT100 - #define TEMPERATURE_SENSOR_1_TYPE Thermistor - #define TEMPERATURE_SENSOR_1_INIT { \ - /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ - /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ - } -#else + // #define TEMPERATURE_SENSOR_1_CIRCUIT_TYPE ADCCircuitDifferentialPullup + // #define TEMPERATURE_SENSOR_1_CIRCUIT_INIT { /*pullup_resistance:*/ 4700 } // #define TEMPERATURE_SENSOR_1_TYPE PT100> - // #define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 2000, /*inline_resistance*/0.0} - #define TEMPERATURE_SENSOR_1_TYPE PT100> - #define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 430, /*inline_resistance*/0, spiBus, spiCSPinMux.getCS(5)} -#endif // 0 or 1 + // #define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 2000, /*inline_resistance*/ 0.0, &temperature_sensor_1_circuit} + + #define TEMPERATURE_SENSOR_1_CIRCUIT_TYPE ADCCircuitRawResistance + #define TEMPERATURE_SENSOR_1_CIRCUIT_INIT { /*pullup_resistance:*/ 430 } + #define TEMPERATURE_SENSOR_1_TYPE PT100> + #define TEMPERATURE_SENSOR_1_INIT {&temperature_sensor_1_circuit, spiBus, spiCSPinMux.getCS(5)} #endif // HAS_TEMPERATURE_SENSOR_1 #define EXTRUDER_1_OUTPUT_PIN kHeaterOutput1_PinNumber @@ -395,37 +391,27 @@ M100.1 ({{ajh:144000.0}}) #define HAS_TEMPERATURE_SENSOR_2 false #if HAS_TEMPERATURE_SENSOR_2 -#if 0 // 1 if a Thermistor, 0 if a PT100 - #define TEMPERATURE_SENSOR_2_TYPE Thermistor - #define TEMPERATURE_SENSOR_2_INIT { \ - /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ - /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ - } -#else + #define TEMPERATURE_SENSOR_2_CIRCUIT_TYPE ADCCircuitDifferentialPullup + #define TEMPERATURE_SENSOR_2_CIRCUIT_INIT { /*pullup_resistance:*/ 200 } #define TEMPERATURE_SENSOR_2_TYPE PT100> - #define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 200, /*inline_resistance*/0.0} -// #define TEMPERATURE_SENSOR_2_TYPE PT100> -// #define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 430, /*inline_resistance*/0, spiBus, spiCSPinMux.getCS(5)} -#endif // 0 or 1 + #define TEMPERATURE_SENSOR_2_INIT {&temperature_sensor_2_circuit} + + // #define TEMPERATURE_SENSOR_2_CIRCUIT_TYPE ADCCircuitRawResistance + // #define TEMPERATURE_SENSOR_2_CIRCUIT_INIT { /*pullup_resistance:*/ 430 } + // #define TEMPERATURE_SENSOR_2_TYPE PT100> + // #define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 430, /*inline_resistance*/0, spiBus, spiCSPinMux.getCS(5)} #endif // HAS_TEMPERATURE_SENSOR_2 #define EXTRUDER_2_OUTPUT_PIN kHeaterOutput2_PinNumber #define HAS_TEMPERATURE_SENSOR_3 true #if HAS_TEMPERATURE_SENSOR_3 -#if 0 // 1 if a Thermistor, 0 if a PT100 - #define TEMPERATURE_SENSOR_3_TYPE Thermistor - #define TEMPERATURE_SENSOR_3_INIT { \ - /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ - /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ - } -#else // #define TEMPERATURE_SENSOR_3_TYPE PT100> // #define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 200, /*inline_resistance*/0.0} - #define TEMPERATURE_SENSOR_3_TYPE PT100> - #define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 430, /*inline_resistance*/0, spiBus, spiCSPinMux.getCS(6)} - -#endif // 0 or 1 + #define TEMPERATURE_SENSOR_3_CIRCUIT_TYPE ADCCircuitRawResistance + #define TEMPERATURE_SENSOR_3_CIRCUIT_INIT { /*pullup_resistance:*/ 430 } + #define TEMPERATURE_SENSOR_3_TYPE PT100> + #define TEMPERATURE_SENSOR_3_INIT {&temperature_sensor_3_circuit, spiBus, spiCSPinMux.getCS(6)} #endif // HAS_TEMPERATURE_SENSOR_3 #define BED_OUTPUT_PIN kHeaterOutput11_PinNumber diff --git a/g2core/temperature.cpp b/g2core/temperature.cpp index 63a9e3f8b..c669cc0b5 100755 --- a/g2core/temperature.cpp +++ b/g2core/temperature.cpp @@ -225,12 +225,66 @@ struct ValueHistory { }; +struct ADCCircuit +{ + virtual float get_resistance(const float voltage) const; + virtual float get_voltage(const float resistance) const; +}; + +struct ADCCircuitSimplePullup : ADCCircuit +{ + const float _pullup_resistance; + ADCCircuitSimplePullup(const float pullup_resistance) : _pullup_resistance{pullup_resistance} {}; + + float get_resistance(const float v) const override + { + return ((_pullup_resistance * v) / (kSystemVoltage - v)); + }; + + float get_voltage(const float r) const override + { + return r/(r+_pullup_resistance)*kSystemVoltage; + }; +}; + +struct ADCCircuitDifferentialPullup : ADCCircuit +{ + const float _pullup_resistance; + ADCCircuitDifferentialPullup(const float pullup_resistance) : _pullup_resistance{pullup_resistance} {}; + + float get_resistance(float v) const override + { + float v2 = v / kSystemVoltage; + return (v2 * 2.0 * _pullup_resistance)/(1.0 - v2); + }; + + float get_voltage(const float r) const override + { + return (kSystemVoltage * r)/(2.0 * _pullup_resistance + r); + }; +}; + +struct ADCCircuitRawResistance : ADCCircuit +{ + const float _vref; + ADCCircuitRawResistance(const float vref = kSystemVoltage) : _vref{vref} {}; + + float get_resistance(float v) const override + { + return v/_vref; + }; + + float get_voltage(const float r) const override + { + return r*_vref; + }; +}; + + template struct Thermistor { - const bool differential; - - float c1, c2, c3, pullup_resistance; - // We'll pull adc top value from the adc_pin.getTop() + float c1, c2, c3; + const ADCCircuit *circuit; ADC_t adc_pin; uint16_t raw_adc_value = 0; @@ -245,22 +299,22 @@ struct Thermistor { // http://assets.newport.com/webDocuments-EN/images/AN04_Thermistor_Calibration_IX.PDF // http://hydraraptor.blogspot.com/2012/11/more-accurate-thermistor-tables.html - Thermistor(const float temp_low, const float temp_med, const float temp_high, const float res_low, const float res_med, const float res_high, const float pullup_resistance_) - : differential{ adc_pin.is_differential }, pullup_resistance{ pullup_resistance_ }, - adc_pin {adc_pin.is_differential ? kDifferentialPair : kNormal, [&]{this->adc_has_new_value();} } - { - setup(temp_low, temp_med, temp_high, res_low, res_med, res_high); - adc_pin.setInterrupts(kPinInterruptOnChange|kInterruptPriorityLow); - adc_pin.setVoltageRange(kSystemVoltage, - 0, //get_voltage_of_temp(min_temp), - kSystemVoltage, //get_voltage_of_temp(max_temp), - 1000000.0); - }; +// Thermistor(const float temp_low, const float temp_med, const float temp_high, const float res_low, const float res_med, const float res_high, const ADCCircuit *_circuit) +// : circuit{_circuit} +// adc_pin {kNormal, [&]{this->adc_has_new_value();} } +// { +// setup(temp_low, temp_med, temp_high, res_low, res_med, res_high); +// adc_pin.setInterrupts(kPinInterruptOnChange|kInterruptPriorityLow); +// adc_pin.setVoltageRange(kSystemVoltage, +// 0, //get_voltage_of_temp(min_temp), +// kSystemVoltage, //get_voltage_of_temp(max_temp), +// 1000000.0); +// }; template - Thermistor(const float temp_low, const float temp_med, const float temp_high, const float res_low, const float res_med, const float res_high, const float pullup_resistance_, Ts&&... additional_values) - : differential{ adc_pin.is_differential }, pullup_resistance{ pullup_resistance_ }, - adc_pin{adc_pin.is_differential ? kDifferentialPair : kNormal, [&]{this->adc_has_new_value();}, additional_values...} + Thermistor(const float temp_low, const float temp_med, const float temp_high, const float res_low, const float res_med, const float res_high, const ADCCircuit *_circuit, Ts&&... additional_values) + : circuit{_circuit}, + adc_pin{kNormal, [&]{this->adc_has_new_value();}, additional_values...} { setup(temp_low, temp_med, temp_high, res_low, res_med, res_high); adc_pin.setInterrupts(kPinInterruptOnChange|kInterruptPriorityLow); @@ -312,22 +366,13 @@ struct Thermistor { }; float get_resistance() { - float r; raw_adc_voltage = history.value(); if (isnan(raw_adc_voltage)) { return -1; } - if (differential) { - float v = raw_adc_voltage / kSystemVoltage; - r = (v * 2.0 * pullup_resistance)/(1.0 - v);// - inline_resistance; - } - else { - float v = raw_adc_voltage; - r = ((pullup_resistance * v) / (kSystemVoltage - v));// - inline_resistance; - } - return r; + return circuit->get_resistance(raw_adc_voltage); }; // float get_resistance() { @@ -362,10 +407,7 @@ struct Thermistor { template struct PT100 { - const float pullup_resistance; - const float inline_resistance; - const bool differential; - bool gives_raw_resistance = false; + const ADCCircuit *circuit; ADC_t adc_pin; float raw_adc_voltage = 0.0; @@ -376,27 +418,21 @@ struct PT100 { typedef PT100 type; - PT100(const float pullup_resistance_, const float inline_resistance_) - : pullup_resistance{ pullup_resistance_ }, - inline_resistance{ inline_resistance_ }, - differential{adc_pin.is_differential}, - gives_raw_resistance{false}, - adc_pin{ADC_t::is_differential ? kDifferentialPair : kNormal, [&]{this->adc_has_new_value();} } - { - adc_pin.setInterrupts(kPinInterruptOnChange|kInterruptPriorityLow); - adc_pin.setVoltageRange(kSystemVoltage, - get_voltage_of_temp(min_temp), - get_voltage_of_temp(max_temp), - 6400.0); - }; +// PT100(const ADCCircuit *_circuit) +// : circuit{_circuit}, +// adc_pin{ADC_t::is_differential ? kDifferentialPair : kNormal, [&]{this->adc_has_new_value();} } +// { +// adc_pin.setInterrupts(kPinInterruptOnChange|kInterruptPriorityLow); +// adc_pin.setVoltageRange(kSystemVoltage, +// get_voltage_of_temp(min_temp), +// get_voltage_of_temp(max_temp), +// 6400.0); +// }; template - PT100(const float pullup_resistance_, const float inline_resistance_, Ts&&... additional_values) - : pullup_resistance{ pullup_resistance_ }, - inline_resistance{ inline_resistance_ }, - differential{false}, - gives_raw_resistance{true}, - adc_pin{[&]{this->adc_has_new_value();}, additional_values...} + PT100(const ADCCircuit *_circuit, Ts&&... additional_values) + : circuit{_circuit}, + adc_pin{kNormal, [&]{this->adc_has_new_value();}, additional_values...} { adc_pin.setInterrupts(kPinInterruptOnChange|kInterruptPriorityLow); adc_pin.setVoltageRange(kSystemVoltage, @@ -407,16 +443,13 @@ struct PT100 { constexpr float get_resistance_of_temp(float t) { // R = 100(1 + A*T + B*T^2); A = 3.9083*10^-3; B = -5.775*10^-7 - return 100 * (1 + 0.0039083*t + -0.0000005775*t*t) + inline_resistance; + return 100 * (1 + 0.0039083*t + -0.0000005775*t*t); }; constexpr float get_voltage_of_temp(float t) { float r = get_resistance_of_temp(t); - if (differential) { - return (kSystemVoltage * r)/(2.0 * pullup_resistance + r); - } - return r/(r+pullup_resistance)*kSystemVoltage; + return circuit->get_voltage(r); }; float temperature_exact() { @@ -430,27 +463,37 @@ struct PT100 { }; float get_resistance() { - float r; raw_adc_voltage = history.value(); if (isnan(raw_adc_voltage)) { return -1; } - if (gives_raw_resistance) { - r = raw_adc_voltage; - } - else if (differential) { - float v = raw_adc_voltage / kSystemVoltage; - r = (v * 2.0 * pullup_resistance)/(1.0 - v) - inline_resistance; - } - else { - float v = raw_adc_voltage; - r = ((pullup_resistance * v) / (kSystemVoltage - v)) - inline_resistance; - } - return r; + return circuit->get_resistance(raw_adc_voltage); }; +// float get_resistance() { +// float r; +// raw_adc_voltage = history.value(); +// +// if (isnan(raw_adc_voltage)) { +// return -1; +// } +// +// if (gives_raw_resistance) { +// r = raw_adc_voltage; +// } +// else if (differential) { +// float v = raw_adc_voltage / kSystemVoltage; +// r = (v * 2.0 * pullup_resistance)/(1.0 - v) - inline_resistance; +// } +// else { +// float v = raw_adc_voltage; +// r = ((pullup_resistance * v) / (kSystemVoltage - v)) - inline_resistance; +// } +// return r; +// }; + uint16_t get_raw_value() { return raw_adc_value; }; @@ -466,14 +509,8 @@ struct PT100 { // Call back function from the ADC to tell it that the ADC has a new sample... void adc_has_new_value() { - if (gives_raw_resistance) { - raw_adc_value = adc_pin.getRaw(); - raw_adc_voltage = (raw_adc_value*pullup_resistance)/32768; - history.add_sample(raw_adc_voltage); - } else { - float v = fabs(adc_pin.getVoltage()); - history.add_sample(v); - } + float v = fabs(adc_pin.getVoltage()); + history.add_sample(v); }; }; @@ -482,6 +519,7 @@ struct PT100 { #if HAS_TEMPERATURE_SENSOR_1 // Extruder 1 +TEMPERATURE_SENSOR_1_CIRCUIT_TYPE temperature_sensor_1_circuit TEMPERATURE_SENSOR_1_CIRCUIT_INIT; TEMPERATURE_SENSOR_1_TYPE temperature_sensor_1 TEMPERATURE_SENSOR_1_INIT; #else TemperatureSensor temperature_sensor_1; @@ -490,6 +528,7 @@ TemperatureSensor temperature_sensor_1; // Extruder 2 #if HAS_TEMPERATURE_SENSOR_2 // Extruder 2 +TEMPERATURE_SENSOR_2_CIRCUIT_TYPE temperature_sensor_2_circuit TEMPERATURE_SENSOR_2_CIRCUIT_INIT; TEMPERATURE_SENSOR_2_TYPE temperature_sensor_2 TEMPERATURE_SENSOR_2_INIT; #else TemperatureSensor temperature_sensor_2; @@ -497,6 +536,7 @@ TemperatureSensor temperature_sensor_2; #if HAS_TEMPERATURE_SENSOR_3 // Heated bed +TEMPERATURE_SENSOR_3_CIRCUIT_TYPE temperature_sensor_3_circuit TEMPERATURE_SENSOR_3_CIRCUIT_INIT; TEMPERATURE_SENSOR_3_TYPE temperature_sensor_3 TEMPERATURE_SENSOR_3_INIT; #else TemperatureSensor temperature_sensor_3; From 3f7fc88401a8f2cfa0fac5e88964530c2604d988 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Wed, 13 Sep 2017 18:54:49 -0500 Subject: [PATCH 126/193] Fix for inaccuracies that are caught by encoder corrections --- g2core/stepper.cpp | 12 ++++++------ g2core/stepper.h | 13 ++++++------- 2 files changed, 12 insertions(+), 13 deletions(-) diff --git a/g2core/stepper.cpp b/g2core/stepper.cpp index 4035fc495..cd141ee3c 100644 --- a/g2core/stepper.cpp +++ b/g2core/stepper.cpp @@ -158,7 +158,7 @@ void stepper_reset() for (uint8_t motor=0; motor Date: Sat, 16 Sep 2017 11:44:06 -0400 Subject: [PATCH 127/193] Added some missing setting files --- g2core/settings/settings_ender.h | 2 +- g2core/settings/settings_xcarve_extended.h | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/g2core/settings/settings_ender.h b/g2core/settings/settings_ender.h index 782ef196a..59433e7c5 100644 --- a/g2core/settings/settings_ender.h +++ b/g2core/settings/settings_ender.h @@ -150,7 +150,7 @@ #define M3_MICROSTEPS 32 #define M3_POLARITY 1 #define M3_POWER_MODE MOTOR_ALWAYS_POWERED -#define M3_POWER_LEVEL 0.5 +#define M3_POWER_LEVEL 0.55482 #define M3_TMC2130_TPWMTHRS 300 #define M3_TMC2130_TCOOLTHRS 200 #define M3_TMC2130_THIGH 10 diff --git a/g2core/settings/settings_xcarve_extended.h b/g2core/settings/settings_xcarve_extended.h index 3efa8f090..f61822be4 100644 --- a/g2core/settings/settings_xcarve_extended.h +++ b/g2core/settings/settings_xcarve_extended.h @@ -212,7 +212,7 @@ #define X_AXIS_MODE AXIS_STANDARD // xam see canonical_machine.h cmAxisMode for valid values -#define X_VELOCITY_MAX 16000 // xvm G0 max velocity in mm/min +#define X_VELOCITY_MAX 800 // xvm G0 max velocity in mm/min #define X_FEEDRATE_MAX X_VELOCITY_MAX // xfr G1 max feed rate in mm/min #define X_TRAVEL_MIN 0 // xtn minimum travel - used by soft limits and homing #define X_TRAVEL_MAX 1000 // xtm maximum travel - used by soft limits and homing @@ -226,7 +226,7 @@ #define X_ZERO_BACKOFF 0.5 // xzb mm #define Y_AXIS_MODE AXIS_STANDARD -#define Y_VELOCITY_MAX 16000 +#define Y_VELOCITY_MAX 800 #define Y_FEEDRATE_MAX Y_VELOCITY_MAX #define Y_TRAVEL_MIN 0 #define Y_TRAVEL_MAX 1000 From 10412b345be2b7c95f1c406a10c1fd800168dc96 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Fri, 27 Oct 2017 13:46:59 -0500 Subject: [PATCH 128/193] Better fault handling in max31865 --- g2core/device/max31865/max31865.h | 13 +++++++++++-- 1 file changed, 11 insertions(+), 2 deletions(-) diff --git a/g2core/device/max31865/max31865.h b/g2core/device/max31865/max31865.h index 92ab71b58..c4e16ae2b 100644 --- a/g2core/device/max31865/max31865.h +++ b/g2core/device/max31865/max31865.h @@ -234,7 +234,9 @@ struct MAX31865 final { } _fault_status; bool _fault_status_needs_read = false; void _postReadFaultStatus() { - /* here is where we would call alarm or something!! */ + if (_interrupt_handler) { + _interrupt_handler(); + } }; void _startNextReadWrite() @@ -398,6 +400,9 @@ struct MAX31865 final { // getRaw is to return the last sampled value int32_t getRaw() { + if (_fault_status.value) { + return -_fault_status.value; + } return _rtd_value; }; @@ -429,7 +434,11 @@ struct MAX31865 final { // All of the rest are ignored, but here for compatibility of interface }; float getVoltage() { - return ((getRaw()*_pullup_resistance)/32768.0) * _vref; + float r = getRaw(); + if (r < 0) { + return r*1000.0; + } + return ((r*_pullup_resistance)/32768.0) * _vref; }; operator float() { return getVoltage(); }; From 4e482baa7f8f2ebd78b862b30788f656d9f26c53 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Fri, 27 Oct 2017 13:47:59 -0500 Subject: [PATCH 129/193] Make temperature reading more tolerant --- g2core/temperature.cpp | 16 +++++++++++++++- 1 file changed, 15 insertions(+), 1 deletion(-) diff --git a/g2core/temperature.cpp b/g2core/temperature.cpp index c669cc0b5..d97a91b94 100755 --- a/g2core/temperature.cpp +++ b/g2core/temperature.cpp @@ -459,7 +459,13 @@ struct PT100 { // from https://www.maximintegrated.com/en/app-notes/index.mvp/id/3450 // run through wolfram as: // solve R = 100(1 + A*T + B*T^2); A = 3.9083*10^-3; B = -5.775*10^-7 for T - return 3383.81 - (0.287154*sqrt(159861899.0 - 210000.0*r)); + float t = 3383.81 - (0.287154*sqrt(159861899.0 - 210000.0*r)); + + if (t > max_temp) { + return -1; + } + + return t; }; float get_resistance() { @@ -509,7 +515,15 @@ struct PT100 { // Call back function from the ADC to tell it that the ADC has a new sample... void adc_has_new_value() { + raw_adc_value = adc_pin.getRaw(); float v = fabs(adc_pin.getVoltage()); +// if (v < 0) { +// char buffer[128]; +// char *str = buffer; +// str += sprintf(str, "Heater sensor failure. Reading was: %f", v); +// cm_alarm(STAT_TEMPERATURE_CONTROL_ERROR, buffer); +// return; +// } history.add_sample(v); }; }; From 554de467b7a33124191c19a4e1d5826e5ec4b1ab Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Fri, 27 Oct 2017 13:48:09 -0500 Subject: [PATCH 130/193] Update Motate reference --- Motate | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Motate b/Motate index c24acaba9..afe8b3a18 160000 --- a/Motate +++ b/Motate @@ -1 +1 @@ -Subproject commit c24acaba902ec2ac09d0917e87f664624b70ae19 +Subproject commit afe8b3a18736f6ec4e8bf0b1e58b1543c435c4a8 From 594c74d3d522860471340ba5ffa0c42f6d17f3e3 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Fri, 27 Oct 2017 13:48:32 -0500 Subject: [PATCH 131/193] Adjust default setings for PrintrBot Play and UM2 (testing) --- g2core/settings/settings_Printrbot_Play.h | 4 +- g2core/settings/settings_Ultimaker_2_Plus.h | 42 +++++++++++---------- 2 files changed, 25 insertions(+), 21 deletions(-) diff --git a/g2core/settings/settings_Printrbot_Play.h b/g2core/settings/settings_Printrbot_Play.h index 0310fb270..274cc9f87 100644 --- a/g2core/settings/settings_Printrbot_Play.h +++ b/g2core/settings/settings_Printrbot_Play.h @@ -322,11 +322,11 @@ // } #define TEMPERATURE_SENSOR_1_CIRCUIT_TYPE ADCCircuitRawResistance - #define TEMPERATURE_SENSOR_1_CIRCUIT_INIT { } + #define TEMPERATURE_SENSOR_1_CIRCUIT_INIT { /*pullup_resistance:*/ 430 } #define TEMPERATURE_SENSOR_1_TYPE Thermistor> #define TEMPERATURE_SENSOR_1_INIT { \ /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ - /*R1:*/ 99500.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 10500.0 \ + /*R1:*/ 99500.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, &temperature_sensor_1_circuit \ /*MAX31865 config*/ spiBus, spiCSPinMux.getCS(5), 150000 \ } diff --git a/g2core/settings/settings_Ultimaker_2_Plus.h b/g2core/settings/settings_Ultimaker_2_Plus.h index 7bdf9621b..d82b6c4fa 100644 --- a/g2core/settings/settings_Ultimaker_2_Plus.h +++ b/g2core/settings/settings_Ultimaker_2_Plus.h @@ -84,9 +84,11 @@ // Defaults for PID tuning //#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","he1t","he1st","he1at","he1op","pid1p","pid1i","pid1d","feed","vel","unit","path","stat" -// Defaults for thermistor tuning -#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","he1t","he1st","he1at","he1op","he3t","he3st","he3at","he3op","feed","vel","unit","path","stat","1ts","1sgr","1csa","2ts","2sgr","2csa","3ts","3sgr","3csa","4ts","4sgr","4csa" -//#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","he1t","he1st","he1at","he1tr","he1tv","he1op","he2t","he2st","he2at","he2tr","he2tv","he2op","he3t","he3st","he3at","he3tr","he3tv","he3op","feed","vel","unit","path","stat","_xs1","_xs2","_xs3","_xs4" +// Defaults for Trinamic tuning +// #define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","he1t","he1st","he1at","he1op","he3t","he3st","he3at","he3op","feed","vel","unit","path","stat","1ts","1sgr","1csa","2ts","2sgr","2csa","3ts","3sgr","3csa","4ts","4sgr","4csa" + +// Defaults for thermistor tuning: cut out: ,"he2t","he2st","he2at","he2tr","he2tv","he2op", +#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","he1t","he1st","he1at","he1tr","he1tv","he1op","he3t","he3st","he3at","he3tr","he3tv","he3op","feed","vel","unit","path","stat","_xs1","_xs2","_xs3","_xs4","_fe1","_fe2","_fe3","_fe4" // Gcode startup defaults #define GCODE_DEFAULT_UNITS MILLIMETERS // MILLIMETERS or INCHES #define GCODE_DEFAULT_PLANE CANON_PLANE_XY // CANON_PLANE_XY, CANON_PLANE_XZ, or CANON_PLANE_YZ @@ -375,15 +377,15 @@ M100.1 ({{ajh:144000.0}}) #define HAS_TEMPERATURE_SENSOR_1 true #if HAS_TEMPERATURE_SENSOR_1 - // #define TEMPERATURE_SENSOR_1_CIRCUIT_TYPE ADCCircuitDifferentialPullup - // #define TEMPERATURE_SENSOR_1_CIRCUIT_INIT { /*pullup_resistance:*/ 4700 } - // #define TEMPERATURE_SENSOR_1_TYPE PT100> - // #define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 2000, /*inline_resistance*/ 0.0, &temperature_sensor_1_circuit} - - #define TEMPERATURE_SENSOR_1_CIRCUIT_TYPE ADCCircuitRawResistance - #define TEMPERATURE_SENSOR_1_CIRCUIT_INIT { /*pullup_resistance:*/ 430 } - #define TEMPERATURE_SENSOR_1_TYPE PT100> - #define TEMPERATURE_SENSOR_1_INIT {&temperature_sensor_1_circuit, spiBus, spiCSPinMux.getCS(5)} + #define TEMPERATURE_SENSOR_1_CIRCUIT_TYPE ADCCircuitDifferentialPullup + #define TEMPERATURE_SENSOR_1_CIRCUIT_INIT { /*pullup_resistance:*/ 200 } + #define TEMPERATURE_SENSOR_1_TYPE PT100> + #define TEMPERATURE_SENSOR_1_INIT {&temperature_sensor_1_circuit} + +// #define TEMPERATURE_SENSOR_1_CIRCUIT_TYPE ADCCircuitRawResistance +// #define TEMPERATURE_SENSOR_1_CIRCUIT_INIT { } +// #define TEMPERATURE_SENSOR_1_TYPE PT100> +// #define TEMPERATURE_SENSOR_1_INIT {&temperature_sensor_1_circuit, spiBus, spiCSPinMux.getCS(5), /*pullup_resistance:*/ 430.0} #endif // HAS_TEMPERATURE_SENSOR_1 #define EXTRUDER_1_OUTPUT_PIN kHeaterOutput1_PinNumber @@ -404,14 +406,16 @@ M100.1 ({{ajh:144000.0}}) #define EXTRUDER_2_OUTPUT_PIN kHeaterOutput2_PinNumber -#define HAS_TEMPERATURE_SENSOR_3 true +#define HAS_TEMPERATURE_SENSOR_3 false #if HAS_TEMPERATURE_SENSOR_3 - // #define TEMPERATURE_SENSOR_3_TYPE PT100> - // #define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 200, /*inline_resistance*/0.0} - #define TEMPERATURE_SENSOR_3_CIRCUIT_TYPE ADCCircuitRawResistance - #define TEMPERATURE_SENSOR_3_CIRCUIT_INIT { /*pullup_resistance:*/ 430 } - #define TEMPERATURE_SENSOR_3_TYPE PT100> - #define TEMPERATURE_SENSOR_3_INIT {&temperature_sensor_3_circuit, spiBus, spiCSPinMux.getCS(6)} + #define TEMPERATURE_SENSOR_3_CIRCUIT_TYPE ADCCircuitDifferentialPullup + #define TEMPERATURE_SENSOR_3_CIRCUIT_INIT { /*pullup_resistance:*/ 200 } + #define TEMPERATURE_SENSOR_3_TYPE PT100> + #define TEMPERATURE_SENSOR_3_INIT {&temperature_sensor_3_circuit} +// #define TEMPERATURE_SENSOR_3_CIRCUIT_TYPE ADCCircuitRawResistance +// #define TEMPERATURE_SENSOR_3_CIRCUIT_INIT { } +// #define TEMPERATURE_SENSOR_3_TYPE PT100> +// #define TEMPERATURE_SENSOR_3_INIT {&temperature_sensor_3_circuit, spiBus, spiCSPinMux.getCS(6), /*pullup_resistance:*/ 430.0} #endif // HAS_TEMPERATURE_SENSOR_3 #define BED_OUTPUT_PIN kHeaterOutput11_PinNumber From 39035a1eec06936e3f55c43e0df1912f6213af2b Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Fri, 27 Oct 2017 13:52:34 -0500 Subject: [PATCH 132/193] Attempted fix for #298 (reading nested JSON fail) --- g2core/json_parser.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/g2core/json_parser.cpp b/g2core/json_parser.cpp index 3c48d084f..531df60a9 100644 --- a/g2core/json_parser.cpp +++ b/g2core/json_parser.cpp @@ -116,7 +116,9 @@ void json_parse_for_exec(char *str, bool execute) static stat_t _json_parser_execute(nvObj_t *nv) { do { - if (nv->valuetype == TYPE_NULL) { // means GET the value + if (nv->valuetype == TYPE_PARENT) { + // anything? + } else if (nv->valuetype == TYPE_NULL) { // means GET the value ritorno(nv_get(nv)); // ritorno returns w/status on any errors if (nv->valuetype == TYPE_PARENT) { // This will be true if you read a group. Exit now return (STAT_OK); From d6ee30f5a8ea3da437be75cccc034bdaebeb5a8a Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Fri, 17 Nov 2017 09:41:01 -0600 Subject: [PATCH 133/193] Fix temperature readings, adjusting Ultimaker2+ settings, and make MAX31865 more fault tolerant. --- g2core/device/max31865/max31865.h | 49 ++++++++++++--------- g2core/settings/settings_Ultimaker_2_Plus.h | 39 ++++++++-------- g2core/temperature.cpp | 25 ++++++++--- 3 files changed, 67 insertions(+), 46 deletions(-) diff --git a/g2core/device/max31865/max31865.h b/g2core/device/max31865/max31865.h index c4e16ae2b..9908860f0 100644 --- a/g2core/device/max31865/max31865.h +++ b/g2core/device/max31865/max31865.h @@ -94,7 +94,7 @@ struct MAX31865 final { template MAX31865(const Motate::PinOptions_t options, // completely ignored, but for compatibility with ADCPin - std::function &&_interrupt, + std::function &&_interrupt, SPIBus_t &spi_bus, const chipSelect_t &_cs, float pullup_resistance = 430, // 430 is the value used on the Adafruit breakout @@ -194,7 +194,7 @@ struct MAX31865 final { _fault_status_needs_read = true; } if (_interrupt_handler) { - _interrupt_handler(); + _interrupt_handler(fault_detected); } _state = NEEDS_SAMPLED; }; @@ -235,7 +235,7 @@ struct MAX31865 final { bool _fault_status_needs_read = false; void _postReadFaultStatus() { if (_interrupt_handler) { - _interrupt_handler(); + _interrupt_handler(_fault_status.value != 0); } }; @@ -339,8 +339,7 @@ struct MAX31865 final { // interface to make this a drop-in replacement (after init) for an ADCPin - float _vref = 3.3; - std::function _interrupt_handler; + std::function _interrupt_handler; void startSampling() { @@ -411,25 +410,25 @@ struct MAX31865 final { int32_t getValue() { return getRaw(); }; - int32_t getBottom() { - return 0; - }; - float getBottomVoltage() { - return 0; - }; - int32_t getTop() { - return 32767; - }; - float getTopVoltage() { - return _vref; - }; +// int32_t getBottom() { +// return 0; +// }; +// float getBottomVoltage() { +// return 0; +// }; +// int32_t getTop() { +// return 32767; +// }; +// float getTopVoltage() { +// return _vref; +// }; void setVoltageRange(const float vref, const float min_expected = 0, const float max_expected = -1, const float ideal_steps = 1) { - _vref = vref; +// _vref = vref; // All of the rest are ignored, but here for compatibility of interface }; @@ -438,19 +437,27 @@ struct MAX31865 final { if (r < 0) { return r*1000.0; } - return ((r*_pullup_resistance)/32768.0) * _vref; + return ((r*_pullup_resistance)/32768.0); }; operator float() { return getVoltage(); }; + float getResistance() { + float r = getRaw(); + if (r < 0) { + return r*1000.0; + } + return (r*_pullup_resistance)/32768.0; + } + void setInterrupts(const uint32_t interrupts) { // ignore this -- it's too dangerous to accidentally change the SPI interrupts }; // We can only support interrupt inferface option 2: a function with a closure or function pointer - void setInterruptHandler(std::function &&handler) { + void setInterruptHandler(std::function &&handler) { _interrupt_handler = std::move(handler); }; - void setInterruptHandler(const std::function &handler) { + void setInterruptHandler(const std::function &handler) { _interrupt_handler = handler; }; diff --git a/g2core/settings/settings_Ultimaker_2_Plus.h b/g2core/settings/settings_Ultimaker_2_Plus.h index d82b6c4fa..56b6f88a6 100644 --- a/g2core/settings/settings_Ultimaker_2_Plus.h +++ b/g2core/settings/settings_Ultimaker_2_Plus.h @@ -231,7 +231,7 @@ // *** axis settings ********************************************************************************** #define X_AXIS_MODE AXIS_STANDARD // xam see canonical_machine.h cmAxisMode for valid values -#define X_VELOCITY_MAX 8700 // xvm G0 max velocity in mm/min +#define X_VELOCITY_MAX 8700 // xvm G0 max velocity in mm/min #define X_FEEDRATE_MAX X_VELOCITY_MAX // xfr G1 max feed rate in mm/min #define X_TRAVEL_MIN 0 // xtn minimum travel - used by soft limits and homing #define X_TRAVEL_MAX 230 // xtm travel between switches or crashes @@ -377,15 +377,15 @@ M100.1 ({{ajh:144000.0}}) #define HAS_TEMPERATURE_SENSOR_1 true #if HAS_TEMPERATURE_SENSOR_1 - #define TEMPERATURE_SENSOR_1_CIRCUIT_TYPE ADCCircuitDifferentialPullup - #define TEMPERATURE_SENSOR_1_CIRCUIT_INIT { /*pullup_resistance:*/ 200 } - #define TEMPERATURE_SENSOR_1_TYPE PT100> - #define TEMPERATURE_SENSOR_1_INIT {&temperature_sensor_1_circuit} - -// #define TEMPERATURE_SENSOR_1_CIRCUIT_TYPE ADCCircuitRawResistance -// #define TEMPERATURE_SENSOR_1_CIRCUIT_INIT { } -// #define TEMPERATURE_SENSOR_1_TYPE PT100> -// #define TEMPERATURE_SENSOR_1_INIT {&temperature_sensor_1_circuit, spiBus, spiCSPinMux.getCS(5), /*pullup_resistance:*/ 430.0} +// #define TEMPERATURE_SENSOR_1_CIRCUIT_TYPE ADCCircuitDifferentialPullup +// #define TEMPERATURE_SENSOR_1_CIRCUIT_INIT { /*pullup_resistance:*/ 200 } +// #define TEMPERATURE_SENSOR_1_TYPE PT100> +// #define TEMPERATURE_SENSOR_1_INIT {&temperature_sensor_1_circuit} + + #define TEMPERATURE_SENSOR_1_CIRCUIT_TYPE ADCCircuitRawResistance + #define TEMPERATURE_SENSOR_1_CIRCUIT_INIT { } + #define TEMPERATURE_SENSOR_1_TYPE PT100> + #define TEMPERATURE_SENSOR_1_INIT {&temperature_sensor_1_circuit, spiBus, spiCSPinMux.getCS(5), /*pullup_resistance:*/ 430.0f} #endif // HAS_TEMPERATURE_SENSOR_1 #define EXTRUDER_1_OUTPUT_PIN kHeaterOutput1_PinNumber @@ -406,16 +406,17 @@ M100.1 ({{ajh:144000.0}}) #define EXTRUDER_2_OUTPUT_PIN kHeaterOutput2_PinNumber -#define HAS_TEMPERATURE_SENSOR_3 false +#define HAS_TEMPERATURE_SENSOR_3 true #if HAS_TEMPERATURE_SENSOR_3 - #define TEMPERATURE_SENSOR_3_CIRCUIT_TYPE ADCCircuitDifferentialPullup - #define TEMPERATURE_SENSOR_3_CIRCUIT_INIT { /*pullup_resistance:*/ 200 } - #define TEMPERATURE_SENSOR_3_TYPE PT100> - #define TEMPERATURE_SENSOR_3_INIT {&temperature_sensor_3_circuit} -// #define TEMPERATURE_SENSOR_3_CIRCUIT_TYPE ADCCircuitRawResistance -// #define TEMPERATURE_SENSOR_3_CIRCUIT_INIT { } -// #define TEMPERATURE_SENSOR_3_TYPE PT100> -// #define TEMPERATURE_SENSOR_3_INIT {&temperature_sensor_3_circuit, spiBus, spiCSPinMux.getCS(6), /*pullup_resistance:*/ 430.0} +// #define TEMPERATURE_SENSOR_3_CIRCUIT_TYPE ADCCircuitDifferentialPullup +// #define TEMPERATURE_SENSOR_3_CIRCUIT_INIT { /*pullup_resistance:*/ 200 } +// #define TEMPERATURE_SENSOR_3_TYPE PT100> +// #define TEMPERATURE_SENSOR_3_INIT {&temperature_sensor_3_circuit} + + #define TEMPERATURE_SENSOR_3_CIRCUIT_TYPE ADCCircuitRawResistance + #define TEMPERATURE_SENSOR_3_CIRCUIT_INIT { } + #define TEMPERATURE_SENSOR_3_TYPE PT100> + #define TEMPERATURE_SENSOR_3_INIT {&temperature_sensor_3_circuit, spiBus, spiCSPinMux.getCS(6), /*pullup_resistance:*/ 430.0f} #endif // HAS_TEMPERATURE_SENSOR_3 #define BED_OUTPUT_PIN kHeaterOutput11_PinNumber diff --git a/g2core/temperature.cpp b/g2core/temperature.cpp index d97a91b94..cc588029d 100755 --- a/g2core/temperature.cpp +++ b/g2core/temperature.cpp @@ -266,17 +266,16 @@ struct ADCCircuitDifferentialPullup : ADCCircuit struct ADCCircuitRawResistance : ADCCircuit { - const float _vref; - ADCCircuitRawResistance(const float vref = kSystemVoltage) : _vref{vref} {}; + ADCCircuitRawResistance() {}; float get_resistance(float v) const override { - return v/_vref; + return v; }; float get_voltage(const float r) const override { - return r*_vref; + return r; }; }; @@ -413,6 +412,9 @@ struct PT100 { float raw_adc_voltage = 0.0; int32_t raw_adc_value = 0; + bool new_sample_since_read = false; + uint8_t reads_without_sample = 0; + const float variance_max = 1.1; ValueHistory<20> history {variance_max}; @@ -432,7 +434,7 @@ struct PT100 { template PT100(const ADCCircuit *_circuit, Ts&&... additional_values) : circuit{_circuit}, - adc_pin{kNormal, [&]{this->adc_has_new_value();}, additional_values...} + adc_pin{kNormal, [&](bool e){this->adc_has_new_value(e);}, additional_values...} { adc_pin.setInterrupts(kPinInterruptOnChange|kInterruptPriorityLow); adc_pin.setVoltageRange(kSystemVoltage, @@ -453,6 +455,16 @@ struct PT100 { }; float temperature_exact() { + if (!new_sample_since_read) { + reads_without_sample++; + if (reads_without_sample > 10) { + cm_alarm(STAT_TEMPERATURE_CONTROL_ERROR, "Sensor read failed 10 times."); + } + } else { + reads_without_sample = 0; + } + new_sample_since_read = false; + float r = get_resistance(); if (r < 0.0) { return -1; } @@ -514,7 +526,7 @@ struct PT100 { }; // Call back function from the ADC to tell it that the ADC has a new sample... - void adc_has_new_value() { + void adc_has_new_value(bool error = false) { raw_adc_value = adc_pin.getRaw(); float v = fabs(adc_pin.getVoltage()); // if (v < 0) { @@ -525,6 +537,7 @@ struct PT100 { // return; // } history.add_sample(v); + new_sample_since_read = true; }; }; From 96ed945ae308d7b9ee3ebfcde9eedfc322f64472 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Fri, 17 Nov 2017 09:41:52 -0600 Subject: [PATCH 134/193] Xcode Project updates --- g2core/g2core.xcodeproj/project.pbxproj | 14 +++++++++++++- .../xcshareddata/xcschemes/G2 G2V9k.xcscheme | 4 +++- .../xcschemes/G2 V9 Shapeoko Dual-Y.xcscheme | 4 +++- .../xcschemes/G2 gQuadratic AxiDrawv3.xcscheme | 4 +++- .../xcschemes/G2 gQuadratic Test.xcscheme | 4 +++- .../xcschemes/G2 gQuintic PrintrbotPlus.xcscheme | 4 +++- .../xcshareddata/xcschemes/G2 gShield.xcscheme | 4 +++- .../G2 printrboardG2v3 PrintrbotPlus.xcscheme | 4 +++- .../xcshareddata/xcschemes/G2 sbv300.xcscheme | 4 +++- .../xcshareddata/xcschemes/G2Core.xcscheme | 4 +++- .../xcshareddata/xcschemes/index.xcscheme | 4 +++- 11 files changed, 43 insertions(+), 11 deletions(-) diff --git a/g2core/g2core.xcodeproj/project.pbxproj b/g2core/g2core.xcodeproj/project.pbxproj index 56400b461..289068333 100644 --- a/g2core/g2core.xcodeproj/project.pbxproj +++ b/g2core/g2core.xcodeproj/project.pbxproj @@ -412,7 +412,7 @@ D45710B8170532AC00EA19A8 /* Project object */ = { isa = PBXProject; attributes = { - LastUpgradeCheck = 0800; + LastUpgradeCheck = 0910; ORGANIZATIONNAME = "Rob Giseburt"; }; buildConfigurationList = D45710BB170532AC00EA19A8 /* Build configuration list for PBXProject "g2core" */; @@ -555,12 +555,18 @@ D45710BD170532AC00EA19A8 /* Debug */ = { isa = XCBuildConfiguration; buildSettings = { + CLANG_WARN_BLOCK_CAPTURE_AUTORELEASING = YES; CLANG_WARN_BOOL_CONVERSION = YES; + CLANG_WARN_COMMA = YES; CLANG_WARN_CONSTANT_CONVERSION = YES; CLANG_WARN_EMPTY_BODY = YES; CLANG_WARN_ENUM_CONVERSION = YES; CLANG_WARN_INFINITE_RECURSION = YES; CLANG_WARN_INT_CONVERSION = YES; + CLANG_WARN_NON_LITERAL_NULL_CONVERSION = YES; + CLANG_WARN_OBJC_LITERAL_CONVERSION = YES; + CLANG_WARN_RANGE_LOOP_ANALYSIS = YES; + CLANG_WARN_STRICT_PROTOTYPES = YES; CLANG_WARN_SUSPICIOUS_MOVE = YES; CLANG_WARN_UNREACHABLE_CODE = YES; CLANG_WARN__DUPLICATE_METHOD_MATCH = YES; @@ -580,12 +586,18 @@ D45710BE170532AC00EA19A8 /* Release */ = { isa = XCBuildConfiguration; buildSettings = { + CLANG_WARN_BLOCK_CAPTURE_AUTORELEASING = YES; CLANG_WARN_BOOL_CONVERSION = YES; + CLANG_WARN_COMMA = YES; CLANG_WARN_CONSTANT_CONVERSION = YES; CLANG_WARN_EMPTY_BODY = YES; CLANG_WARN_ENUM_CONVERSION = YES; CLANG_WARN_INFINITE_RECURSION = YES; CLANG_WARN_INT_CONVERSION = YES; + CLANG_WARN_NON_LITERAL_NULL_CONVERSION = YES; + CLANG_WARN_OBJC_LITERAL_CONVERSION = YES; + CLANG_WARN_RANGE_LOOP_ANALYSIS = YES; + CLANG_WARN_STRICT_PROTOTYPES = YES; CLANG_WARN_SUSPICIOUS_MOVE = YES; CLANG_WARN_UNREACHABLE_CODE = YES; CLANG_WARN__DUPLICATE_METHOD_MATCH = YES; diff --git a/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 G2V9k.xcscheme b/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 G2V9k.xcscheme index 0f8f4cb39..c3f76d4e9 100644 --- a/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 G2V9k.xcscheme +++ b/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 G2V9k.xcscheme @@ -1,6 +1,6 @@ @@ -36,6 +37,7 @@ buildConfiguration = "Debug" selectedDebuggerIdentifier = "Xcode.DebuggerFoundation.Debugger.LLDB" selectedLauncherIdentifier = "Xcode.DebuggerFoundation.Launcher.LLDB" + language = "" launchStyle = "0" useCustomWorkingDirectory = "NO" ignoresPersistentStateOnLaunch = "NO" diff --git a/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 V9 Shapeoko Dual-Y.xcscheme b/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 V9 Shapeoko Dual-Y.xcscheme index a9133c2bb..af3019c33 100644 --- a/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 V9 Shapeoko Dual-Y.xcscheme +++ b/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 V9 Shapeoko Dual-Y.xcscheme @@ -1,6 +1,6 @@ @@ -36,6 +37,7 @@ buildConfiguration = "Debug" selectedDebuggerIdentifier = "Xcode.DebuggerFoundation.Debugger.LLDB" selectedLauncherIdentifier = "Xcode.DebuggerFoundation.Launcher.LLDB" + language = "" launchStyle = "0" useCustomWorkingDirectory = "NO" ignoresPersistentStateOnLaunch = "NO" diff --git a/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 gQuadratic AxiDrawv3.xcscheme b/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 gQuadratic AxiDrawv3.xcscheme index e21407543..d0032cf1f 100644 --- a/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 gQuadratic AxiDrawv3.xcscheme +++ b/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 gQuadratic AxiDrawv3.xcscheme @@ -1,6 +1,6 @@ @@ -36,6 +37,7 @@ buildConfiguration = "Debug" selectedDebuggerIdentifier = "Xcode.DebuggerFoundation.Debugger.LLDB" selectedLauncherIdentifier = "Xcode.DebuggerFoundation.Launcher.LLDB" + language = "" launchStyle = "0" useCustomWorkingDirectory = "NO" ignoresPersistentStateOnLaunch = "NO" diff --git a/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 gQuadratic Test.xcscheme b/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 gQuadratic Test.xcscheme index 78ca53850..c2ddd148f 100644 --- a/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 gQuadratic Test.xcscheme +++ b/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 gQuadratic Test.xcscheme @@ -1,6 +1,6 @@ @@ -36,6 +37,7 @@ buildConfiguration = "Debug" selectedDebuggerIdentifier = "Xcode.DebuggerFoundation.Debugger.LLDB" selectedLauncherIdentifier = "Xcode.DebuggerFoundation.Launcher.LLDB" + language = "" launchStyle = "0" useCustomWorkingDirectory = "NO" ignoresPersistentStateOnLaunch = "NO" diff --git a/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 gQuintic PrintrbotPlus.xcscheme b/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 gQuintic PrintrbotPlus.xcscheme index 4eab75365..a2808eaad 100644 --- a/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 gQuintic PrintrbotPlus.xcscheme +++ b/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 gQuintic PrintrbotPlus.xcscheme @@ -1,6 +1,6 @@ @@ -36,6 +37,7 @@ buildConfiguration = "Debug" selectedDebuggerIdentifier = "Xcode.DebuggerFoundation.Debugger.LLDB" selectedLauncherIdentifier = "Xcode.DebuggerFoundation.Launcher.LLDB" + language = "" launchStyle = "0" useCustomWorkingDirectory = "NO" ignoresPersistentStateOnLaunch = "NO" diff --git a/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 gShield.xcscheme b/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 gShield.xcscheme index 8c5e2fb9c..6242a617f 100644 --- a/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 gShield.xcscheme +++ b/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 gShield.xcscheme @@ -1,6 +1,6 @@ @@ -36,6 +37,7 @@ buildConfiguration = "Debug" selectedDebuggerIdentifier = "Xcode.DebuggerFoundation.Debugger.LLDB" selectedLauncherIdentifier = "Xcode.DebuggerFoundation.Launcher.LLDB" + language = "" launchStyle = "0" useCustomWorkingDirectory = "NO" ignoresPersistentStateOnLaunch = "NO" diff --git a/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 printrboardG2v3 PrintrbotPlus.xcscheme b/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 printrboardG2v3 PrintrbotPlus.xcscheme index ba6de3796..51891f575 100644 --- a/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 printrboardG2v3 PrintrbotPlus.xcscheme +++ b/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 printrboardG2v3 PrintrbotPlus.xcscheme @@ -1,6 +1,6 @@ @@ -36,6 +37,7 @@ buildConfiguration = "Debug" selectedDebuggerIdentifier = "Xcode.DebuggerFoundation.Debugger.LLDB" selectedLauncherIdentifier = "Xcode.DebuggerFoundation.Launcher.LLDB" + language = "" launchStyle = "0" useCustomWorkingDirectory = "NO" ignoresPersistentStateOnLaunch = "NO" diff --git a/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 sbv300.xcscheme b/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 sbv300.xcscheme index f20e56e5a..e15287b9b 100644 --- a/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 sbv300.xcscheme +++ b/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 sbv300.xcscheme @@ -1,6 +1,6 @@ @@ -36,6 +37,7 @@ buildConfiguration = "Debug" selectedDebuggerIdentifier = "Xcode.DebuggerFoundation.Debugger.LLDB" selectedLauncherIdentifier = "Xcode.DebuggerFoundation.Launcher.LLDB" + language = "" launchStyle = "0" useCustomWorkingDirectory = "NO" ignoresPersistentStateOnLaunch = "NO" diff --git a/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2Core.xcscheme b/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2Core.xcscheme index 09d12304c..30d886f18 100644 --- a/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2Core.xcscheme +++ b/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2Core.xcscheme @@ -1,6 +1,6 @@ @@ -115,6 +116,7 @@ buildConfiguration = "Debug" selectedDebuggerIdentifier = "Xcode.DebuggerFoundation.Debugger.LLDB" selectedLauncherIdentifier = "Xcode.DebuggerFoundation.Launcher.LLDB" + language = "" launchStyle = "1" useCustomWorkingDirectory = "NO" ignoresPersistentStateOnLaunch = "NO" diff --git a/g2core/g2core.xcodeproj/xcshareddata/xcschemes/index.xcscheme b/g2core/g2core.xcodeproj/xcshareddata/xcschemes/index.xcscheme index a9c0972e9..7869e1967 100644 --- a/g2core/g2core.xcodeproj/xcshareddata/xcschemes/index.xcscheme +++ b/g2core/g2core.xcodeproj/xcshareddata/xcschemes/index.xcscheme @@ -1,6 +1,6 @@ @@ -73,6 +74,7 @@ buildConfiguration = "Debug" selectedDebuggerIdentifier = "Xcode.DebuggerFoundation.Debugger.LLDB" selectedLauncherIdentifier = "Xcode.DebuggerFoundation.Launcher.LLDB" + language = "" launchStyle = "0" useCustomWorkingDirectory = "NO" ignoresPersistentStateOnLaunch = "NO" From cb80e7b164d763d027d577a8805180df5e3f66d8 Mon Sep 17 00:00:00 2001 From: Alden Hart Date: Wed, 22 Nov 2017 08:36:56 -0500 Subject: [PATCH 135/193] committing anyway --- Motate | 2 +- g2core.atsln | 16 +++++++++------- 2 files changed, 10 insertions(+), 8 deletions(-) diff --git a/Motate b/Motate index c24acaba9..41e5b92a9 160000 --- a/Motate +++ b/Motate @@ -1 +1 @@ -Subproject commit c24acaba902ec2ac09d0917e87f664624b70ae19 +Subproject commit 41e5b92a98de4b268d1804bf6eadf3333298fc75 diff --git a/g2core.atsln b/g2core.atsln index bd2054536..fbe1501b8 100644 --- a/g2core.atsln +++ b/g2core.atsln @@ -1,6 +1,6 @@ Microsoft Visual Studio Solution File, Format Version 12.00 # Atmel Studio Solution File, Format Version 11.00 -VisualStudioVersion = 14.0.25420.1 +VisualStudioVersion = 14.0.23107.0 MinimumVisualStudioVersion = 10.0.40219.1 Project("{E66E83B9-2572-4076-B26E-6BE79FF3018A}") = "g2core", "g2core\g2core.cppproj", "{44EA8FEC-55D7-4149-8A78-A574FC26BF51}" EndProject @@ -49,8 +49,8 @@ Global {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.PrintrbotSimple1608-printrboardG2v3|ARM.Build.0 = PrintrbotSimple1608-printrboardG2v3|ARM {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.ProbotixV90|ARM.ActiveCfg = ProbotixV90|ARM {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.ProbotixV90|ARM.Build.0 = ProbotixV90|ARM - {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.Quintic-Ender|ARM.ActiveCfg = Quintic|ARM - {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.Quintic-Ender|ARM.Build.0 = Quintic|ARM + {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.Quintic-Ender|ARM.ActiveCfg = qQuintic on AxiDraw v3|ARM + {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.Quintic-Ender|ARM.Build.0 = qQuintic on AxiDraw v3|ARM {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.sbv300|ARM.ActiveCfg = sbv300|ARM {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.sbv300|ARM.Build.0 = sbv300|ARM {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.Shapeoko2|ARM.ActiveCfg = Shapeoko2|ARM @@ -66,8 +66,8 @@ Global {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.TestV9|ARM.Build.0 = TestV9|ARM {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.Ultimakerv9k|ARM.ActiveCfg = Ultimakerv9k|ARM {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.Ultimakerv9k|ARM.Build.0 = Ultimakerv9k|ARM - {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.xcarve-extended|ARM.ActiveCfg = xcarve-extended|ARM - {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.xcarve-extended|ARM.Build.0 = xcarve-extended|ARM + {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.xcarve-extended|ARM.ActiveCfg = PrintrbotPlay-v3|ARM + {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.xcarve-extended|ARM.Build.0 = PrintrbotPlay-v3|ARM {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.Zen7x12|ARM.ActiveCfg = Zen7x12|ARM {44EA8FEC-55D7-4149-8A78-A574FC26BF51}.Zen7x12|ARM.Build.0 = Zen7x12|ARM {D7779B24-5CD6-4A1B-893C-2CAE8CF7A3A0}.G2v9k|ARM.ActiveCfg = Stub|ARM @@ -79,7 +79,8 @@ Global {D7779B24-5CD6-4A1B-893C-2CAE8CF7A3A0}.PrintrbotSimple1403-printrboardG2v3|ARM.ActiveCfg = Stub|ARM {D7779B24-5CD6-4A1B-893C-2CAE8CF7A3A0}.PrintrbotSimple1608-printrboardG2v3|ARM.ActiveCfg = Stub|ARM {D7779B24-5CD6-4A1B-893C-2CAE8CF7A3A0}.ProbotixV90|ARM.ActiveCfg = Stub|ARM - {D7779B24-5CD6-4A1B-893C-2CAE8CF7A3A0}.Quintic-Ender|ARM.ActiveCfg = Quintic|ARM + {D7779B24-5CD6-4A1B-893C-2CAE8CF7A3A0}.Quintic-Ender|ARM.ActiveCfg = Stub|ARM + {D7779B24-5CD6-4A1B-893C-2CAE8CF7A3A0}.Quintic-Ender|ARM.Build.0 = Stub|ARM {D7779B24-5CD6-4A1B-893C-2CAE8CF7A3A0}.sbv300|ARM.ActiveCfg = Stub|ARM {D7779B24-5CD6-4A1B-893C-2CAE8CF7A3A0}.Shapeoko2|ARM.ActiveCfg = Stub|ARM {D7779B24-5CD6-4A1B-893C-2CAE8CF7A3A0}.shopbotShield|ARM.ActiveCfg = Stub|ARM @@ -88,7 +89,8 @@ Global {D7779B24-5CD6-4A1B-893C-2CAE8CF7A3A0}.TestQuintic|ARM.ActiveCfg = Stub|ARM {D7779B24-5CD6-4A1B-893C-2CAE8CF7A3A0}.TestV9|ARM.ActiveCfg = Stub|ARM {D7779B24-5CD6-4A1B-893C-2CAE8CF7A3A0}.Ultimakerv9k|ARM.ActiveCfg = Stub|ARM - {D7779B24-5CD6-4A1B-893C-2CAE8CF7A3A0}.xcarve-extended|ARM.ActiveCfg = xcarve-extended|ARM + {D7779B24-5CD6-4A1B-893C-2CAE8CF7A3A0}.xcarve-extended|ARM.ActiveCfg = Stub|ARM + {D7779B24-5CD6-4A1B-893C-2CAE8CF7A3A0}.xcarve-extended|ARM.Build.0 = Stub|ARM {D7779B24-5CD6-4A1B-893C-2CAE8CF7A3A0}.Zen7x12|ARM.ActiveCfg = Stub|ARM EndGlobalSection GlobalSection(SolutionProperties) = preSolution From db136762399284149fc6125a9e58cc7101ca0831 Mon Sep 17 00:00:00 2001 From: Alden Hart Date: Wed, 22 Nov 2017 09:21:35 -0500 Subject: [PATCH 136/193] Committing Motate switched to sams70-port --- Motate | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Motate b/Motate index 41e5b92a9..bf4f2fb3d 160000 --- a/Motate +++ b/Motate @@ -1 +1 @@ -Subproject commit 41e5b92a98de4b268d1804bf6eadf3333298fc75 +Subproject commit bf4f2fb3dcd710abfd8aa2c2cdcc56128dd7ddb1 From 6d790eaeba03b3e9fc4b0a0e0e067f1ae5ab0c97 Mon Sep 17 00:00:00 2001 From: Alden Hart Date: Thu, 23 Nov 2017 10:48:13 -0500 Subject: [PATCH 137/193] Update Motate link --- Motate | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Motate b/Motate index bf4f2fb3d..c24acaba9 160000 --- a/Motate +++ b/Motate @@ -1 +1 @@ -Subproject commit bf4f2fb3dcd710abfd8aa2c2cdcc56128dd7ddb1 +Subproject commit c24acaba902ec2ac09d0917e87f664624b70ae19 From 295436b24dd6728f5281ddb9c83b9fd0f15d2269 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Mon, 27 Nov 2017 13:34:00 -0600 Subject: [PATCH 138/193] Minor changes (comments, etc) --- g2core/cycle_homing.cpp | 2 +- g2core/json_parser.h | 6 +++--- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/g2core/cycle_homing.cpp b/g2core/cycle_homing.cpp index 1c13a3f16..1f0051764 100644 --- a/g2core/cycle_homing.cpp +++ b/g2core/cycle_homing.cpp @@ -523,4 +523,4 @@ static int8_t _get_next_axis(int8_t axis) { return (-1); // done #endif // (HOMING_AXES <= 4) -} \ No newline at end of file +} diff --git a/g2core/json_parser.h b/g2core/json_parser.h index 4bef7817c..9b0e7e1bd 100644 --- a/g2core/json_parser.h +++ b/g2core/json_parser.h @@ -48,9 +48,9 @@ typedef enum { JV_CONFIGS, // [3] returns footer, messages, config commands JV_LINENUM, // [4] returns footer, messages, config commands, gcode line numbers if present JV_VERBOSE, // [5] returns footer, messages, config commands, gcode blocks - JV_EXCEPTIONS, // [6] returns only on messages, configs, and non-zero status - JV_STATUS, // [7] returns status and any messages in abbreviated format - JV_STATUS_COUNT, // [8] returns status, count and messages in abbreviated format + JV_EXCEPTIONS, // (unused) [6] returns only on messages, configs, and non-zero status + JV_STATUS, // (unused) [7] returns status and any messages in abbreviated format + JV_STATUS_COUNT, // (unused) [8] returns status, count and messages in abbreviated format JV_MAX_VALUE } jsonVerbosity; From 6f1f27b5810719104d2ecb2497b907af58816336 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Mon, 27 Nov 2017 13:37:38 -0600 Subject: [PATCH 139/193] Update Motate reference --- Motate | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Motate b/Motate index afe8b3a18..76fc94edc 160000 --- a/Motate +++ b/Motate @@ -1 +1 @@ -Subproject commit afe8b3a18736f6ec4e8bf0b1e58b1543c435c4a8 +Subproject commit 76fc94edcab42d03f713e08786dea935ee9a560e From 896b0b619a66f740d222f6114d9693b78030dbca Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Tue, 28 Nov 2017 11:15:32 -0600 Subject: [PATCH 140/193] Refactor how Trinamic TMC2130 JSON controls are inserted in configArray. Added node script to generate the code consistently. --- Resources/generate_motors_cfgArray.js | 38 ++ g2core/config.cpp | 2 +- g2core/config_app.cpp | 496 +++++++++----------------- g2core/device/trinamic/tmc2130.h | 42 +++ 4 files changed, 256 insertions(+), 322 deletions(-) create mode 100755 Resources/generate_motors_cfgArray.js diff --git a/Resources/generate_motors_cfgArray.js b/Resources/generate_motors_cfgArray.js new file mode 100755 index 000000000..d41aee68b --- /dev/null +++ b/Resources/generate_motors_cfgArray.js @@ -0,0 +1,38 @@ +#!/usr/bin/env node + +// Run this with no arguments, and get the motor code suitable for use in config_app.cpp + +for (n=1; n<=6; n++) { + console.log(` +#if (MOTORS >= ${n}) + { "${n}","${n}ma", _fip, 0, st_print_ma, get_ui8, st_set_ma, (float *)&st_cfg.mot[MOTOR_${n}].motor_map, M${n}_MOTOR_MAP }, + { "${n}","${n}sa", _fip, 3, st_print_sa, get_flt, st_set_sa, (float *)&st_cfg.mot[MOTOR_${n}].step_angle, M${n}_STEP_ANGLE }, + { "${n}","${n}tr", _fipc, 4, st_print_tr, get_flt, st_set_tr, (float *)&st_cfg.mot[MOTOR_${n}].travel_rev, M${n}_TRAVEL_PER_REV }, + { "${n}","${n}mi", _fip, 0, st_print_mi, get_int, st_set_mi, (float *)&st_cfg.mot[MOTOR_${n}].microsteps, M${n}_MICROSTEPS }, + { "${n}","${n}su", _fipi, 5, st_print_su, st_get_su,st_set_su, (float *)&st_cfg.mot[MOTOR_${n}].steps_per_unit, M${n}_STEPS_PER_UNIT }, + { "${n}","${n}po", _fip, 0, st_print_po, get_ui8, set_01, (float *)&st_cfg.mot[MOTOR_${n}].polarity, M${n}_POLARITY }, + { "${n}","${n}pm", _fip, 0, st_print_pm, st_get_pm,st_set_pm, (float *)&cs.null, M${n}_POWER_MODE }, + { "${n}","${n}pl", _fip, 3, st_print_pl, get_flt, st_set_pl, (float *)&st_cfg.mot[MOTOR_${n}].power_level, M${n}_POWER_LEVEL }, +// { "${n}","${n}pi", _fip, 3, st_print_pi, get_flt, st_set_pi, (float *)&st_cfg.mot[MOTOR_${n}].power_idle, M${n}_POWER_IDLE }, +// { "${n}","${n}mt", _fip, 2, st_print_mt, get_flt, st_set_mt, (float *)&st_cfg.mot[MOTOR_${n}].motor_timeout, M${n}_MOTOR_TIMEOUT }, +#ifdef MOTOR_${n}_IS_TRINAMIC + { "${n}","${n}ts", _f0, 0, tx_print_nul, motor_${n}.get_ts_fn, set_ro, (float *)&motor_${n}, 0 }, + { "${n}","${n}pth", _fip, 0, tx_print_nul, motor_${n}.get_pth_fn, motor_${n}.set_pth_fn, (float *)&motor_${n}, M${n}_TMC2130_TPWMTHRS }, + { "${n}","${n}cth", _fip, 0, tx_print_nul, motor_${n}.get_cth_fn, motor_${n}.set_cth_fn, (float *)&motor_${n}, M${n}_TMC2130_TCOOLTHRS }, + { "${n}","${n}hth", _fip, 0, tx_print_nul, motor_${n}.get_hth_fn, motor_${n}.set_hth_fn, (float *)&motor_${n}, M${n}_TMC2130_THIGH }, + { "${n}","${n}sgt", _fip, 0, tx_print_nul, motor_${n}.get_sgt_fn, motor_${n}.set_sgt_fn, (float *)&motor_${n}, M${n}_TMC2130_SGT }, + { "${n}","${n}sgr", _f0, 0, tx_print_nul, motor_${n}.get_sgr_fn, set_ro, (float *)&motor_${n}, 0 }, + { "${n}","${n}csa", _f0, 0, tx_print_nul, motor_${n}.get_csa_fn, set_ro, (float *)&motor_${n}, 0 }, + { "${n}","${n}sgs", _f0, 0, tx_print_nul, motor_${n}.get_sgs_fn, set_ro, (float *)&motor_${n}, 0 }, + { "${n}","${n}tbl", _fip, 0, tx_print_nul, motor_${n}.get_tbl_fn, motor_${n}.set_tbl_fn, (float *)&motor_${n}, M${n}_TMC2130_TBL }, + { "${n}","${n}pgrd",_fip, 0, tx_print_nul, motor_${n}.get_pgrd_fn,motor_${n}.set_pgrd_fn, (float *)&motor_${n}, M${n}_TMC2130_PWM_GRAD }, + { "${n}","${n}pamp",_fip, 0, tx_print_nul, motor_${n}.get_pamp_fn,motor_${n}.set_pamp_fn, (float *)&motor_${n}, M${n}_TMC2130_PWM_AMPL }, + { "${n}","${n}hend",_fip, 0, tx_print_nul, motor_${n}.get_hend_fn,motor_${n}.set_hend_fn, (float *)&motor_${n}, M${n}_TMC2130_HEND }, + { "${n}","${n}hsrt",_fip, 0, tx_print_nul, motor_${n}.get_hsrt_fn,motor_${n}.set_hsrt_fn, (float *)&motor_${n}, M${n}_TMC2130_HSTRT }, + { "${n}","${n}smin",_fip, 0, tx_print_nul, motor_${n}.get_smin_fn,motor_${n}.set_smin_fn, (float *)&motor_${n}, M${n}_TMC2130_SMIN }, + { "${n}","${n}smax",_fip, 0, tx_print_nul, motor_${n}.get_smax_fn,motor_${n}.set_smax_fn, (float *)&motor_${n}, M${n}_TMC2130_SMAX }, + { "${n}","${n}sup", _fip, 0, tx_print_nul, motor_${n}.get_sup_fn, motor_${n}.set_sup_fn, (float *)&motor_${n}, M${n}_TMC2130_SUP }, + { "${n}","${n}sdn", _fip, 0, tx_print_nul, motor_${n}.get_sdn_fn, motor_${n}.set_sdn_fn, (float *)&motor_${n}, M${n}_TMC2130_SDN }, +#endif +#endif`); +} diff --git a/g2core/config.cpp b/g2core/config.cpp index 61c9e3d46..596d34fb3 100644 --- a/g2core/config.cpp +++ b/g2core/config.cpp @@ -83,7 +83,7 @@ void nv_print(nvObj_t *nv) if (nv->index >= nv_index_max()) { return; } - ((fptrCmd)GET_TABLE_WORD(print))(nv); + ((fptrPrint)GET_TABLE_WORD(print))(nv); } stat_t nv_persist(nvObj_t *nv) diff --git a/g2core/config_app.cpp b/g2core/config_app.cpp index 27cbaf515..e5adbd800 100644 --- a/g2core/config_app.cpp +++ b/g2core/config_app.cpp @@ -198,347 +198,197 @@ const cfgItem_t cfgArray[] = { #endif // Motor parameters - { "1","1ma",_fip, 0, st_print_ma, get_ui8, st_set_ma, (float *)&st_cfg.mot[MOTOR_1].motor_map, M1_MOTOR_MAP }, - { "1","1sa",_fip, 3, st_print_sa, get_flt, st_set_sa, (float *)&st_cfg.mot[MOTOR_1].step_angle, M1_STEP_ANGLE }, - { "1","1tr",_fipc,4, st_print_tr, get_flt, st_set_tr, (float *)&st_cfg.mot[MOTOR_1].travel_rev, M1_TRAVEL_PER_REV }, - { "1","1mi",_fip, 0, st_print_mi, get_int, st_set_mi, (float *)&st_cfg.mot[MOTOR_1].microsteps, M1_MICROSTEPS }, - { "1","1su",_fipi,5, st_print_su, st_get_su,st_set_su, (float *)&st_cfg.mot[MOTOR_1].steps_per_unit, M1_STEPS_PER_UNIT }, - { "1","1po",_fip, 0, st_print_po, get_ui8, set_01, (float *)&st_cfg.mot[MOTOR_1].polarity, M1_POLARITY }, - { "1","1pm",_fip, 0, st_print_pm, st_get_pm,st_set_pm, (float *)&cs.null, M1_POWER_MODE }, - { "1","1pl",_fip, 3, st_print_pl, get_flt, st_set_pl, (float *)&st_cfg.mot[MOTOR_1].power_level, M1_POWER_LEVEL }, -// { "1","1pi",_fip, 3, st_print_pi, get_flt, st_set_pi, (float *)&st_cfg.mot[MOTOR_1].power_idle, M1_POWER_IDLE }, -// { "1","1mt",_fip, 2, st_print_mt, get_flt, st_set_mt, (float *)&st_cfg.mot[MOTOR_1].motor_timeout, M1_MOTOR_TIMEOUT }, + // generated with ${PROJECT_ROOT}/Resources/generate_motors_cfgArray.js +#if (MOTORS >= 1) + { "1","1ma", _fip, 0, st_print_ma, get_ui8, st_set_ma, (float *)&st_cfg.mot[MOTOR_1].motor_map, M1_MOTOR_MAP }, + { "1","1sa", _fip, 3, st_print_sa, get_flt, st_set_sa, (float *)&st_cfg.mot[MOTOR_1].step_angle, M1_STEP_ANGLE }, + { "1","1tr", _fipc, 4, st_print_tr, get_flt, st_set_tr, (float *)&st_cfg.mot[MOTOR_1].travel_rev, M1_TRAVEL_PER_REV }, + { "1","1mi", _fip, 0, st_print_mi, get_int, st_set_mi, (float *)&st_cfg.mot[MOTOR_1].microsteps, M1_MICROSTEPS }, + { "1","1su", _fipi, 5, st_print_su, st_get_su,st_set_su, (float *)&st_cfg.mot[MOTOR_1].steps_per_unit, M1_STEPS_PER_UNIT }, + { "1","1po", _fip, 0, st_print_po, get_ui8, set_01, (float *)&st_cfg.mot[MOTOR_1].polarity, M1_POLARITY }, + { "1","1pm", _fip, 0, st_print_pm, st_get_pm,st_set_pm, (float *)&cs.null, M1_POWER_MODE }, + { "1","1pl", _fip, 3, st_print_pl, get_flt, st_set_pl, (float *)&st_cfg.mot[MOTOR_1].power_level, M1_POWER_LEVEL }, + // { "1","1pi", _fip, 3, st_print_pi, get_flt, st_set_pi, (float *)&st_cfg.mot[MOTOR_1].power_idle, M1_POWER_IDLE }, + // { "1","1mt", _fip, 2, st_print_mt, get_flt, st_set_mt, (float *)&st_cfg.mot[MOTOR_1].motor_timeout, M1_MOTOR_TIMEOUT }, #ifdef MOTOR_1_IS_TRINAMIC - { "1","1ts",_f0, 0, tx_print_nul, - [](nvObj_t *nv){return motor_1.get_ts(nv); }, - set_ro, (float *)&cs.null, 0 }, - { "1","1pth",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_1.get_pth(nv);}, - [](nvObj_t *nv){return motor_1.set_pth(nv);}, (float *)&cs.null, M1_TMC2130_TPWMTHRS }, - { "1","1cth",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_1.get_cth(nv);}, - [](nvObj_t *nv){return motor_1.set_cth(nv);}, (float *)&cs.null, M1_TMC2130_TCOOLTHRS }, - { "1","1hth",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_1.get_hth(nv);}, - [](nvObj_t *nv){return motor_1.set_hth(nv);}, (float *)&cs.null, M1_TMC2130_THIGH }, - { "1","1sgt",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_1.get_sgt(nv);}, - [](nvObj_t *nv){return motor_1.set_sgt(nv);}, (float *)&cs.null, M1_TMC2130_SGT }, - { "1","1sgr",_f0, 0, tx_print_nul, - [](nvObj_t *nv){return motor_1.get_sgr(nv);}, - set_ro, (float *)&cs.null, 0 }, - { "1","1csa",_f0, 0, tx_print_nul, - [](nvObj_t *nv){return motor_1.get_csa(nv);}, - set_ro, (float *)&cs.null, 0 }, - { "1","1sgs",_f0, 0, tx_print_nul, - [](nvObj_t *nv){return motor_1.get_sgs(nv);}, - set_ro, (float *)&cs.null, 0 }, - { "1","1tbl",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_1.get_tbl(nv);}, - [](nvObj_t *nv){return motor_1.set_tbl(nv);}, (float *)&cs.null, M1_TMC2130_TBL }, - { "1","1pgrd",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_1.get_pgrd(nv);}, - [](nvObj_t *nv){return motor_1.set_pgrd(nv);}, (float *)&cs.null, M1_TMC2130_PWM_GRAD }, - { "1","1pamp",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_1.get_pamp(nv);}, - [](nvObj_t *nv){return motor_1.set_pamp(nv);}, (float *)&cs.null, M1_TMC2130_PWM_AMPL }, - { "1","1hend",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_1.get_hend(nv);}, - [](nvObj_t *nv){return motor_1.set_hend(nv);}, (float *)&cs.null, M1_TMC2130_HEND }, - { "1","1hsrt",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_1.get_hsrt(nv);}, - [](nvObj_t *nv){return motor_1.set_hsrt(nv);}, (float *)&cs.null, M1_TMC2130_HSTRT }, - { "1","1smin",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_1.get_smin(nv);}, - [](nvObj_t *nv){return motor_1.set_smin(nv);}, (float *)&cs.null, M1_TMC2130_SMIN }, - { "1","1smax",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_1.get_smax(nv);}, - [](nvObj_t *nv){return motor_1.set_smax(nv);}, (float *)&cs.null, M1_TMC2130_SMAX }, - { "1","1sup",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_1.get_sup(nv);}, - [](nvObj_t *nv){return motor_1.set_sup(nv);}, (float *)&cs.null, M1_TMC2130_SUP }, - { "1","1sdn",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_1.get_sdn(nv);}, - [](nvObj_t *nv){return motor_1.set_sdn(nv);}, (float *)&cs.null, M1_TMC2130_SDN }, + { "1","1ts", _f0, 0, tx_print_nul, motor_1.get_ts_fn, set_ro, (float *)&motor_1, 0 }, + { "1","1pth", _fip, 0, tx_print_nul, motor_1.get_pth_fn, motor_1.set_pth_fn, (float *)&motor_1, M1_TMC2130_TPWMTHRS }, + { "1","1cth", _fip, 0, tx_print_nul, motor_1.get_cth_fn, motor_1.set_cth_fn, (float *)&motor_1, M1_TMC2130_TCOOLTHRS }, + { "1","1hth", _fip, 0, tx_print_nul, motor_1.get_hth_fn, motor_1.set_hth_fn, (float *)&motor_1, M1_TMC2130_THIGH }, + { "1","1sgt", _fip, 0, tx_print_nul, motor_1.get_sgt_fn, motor_1.set_sgt_fn, (float *)&motor_1, M1_TMC2130_SGT }, + { "1","1sgr", _f0, 0, tx_print_nul, motor_1.get_sgr_fn, set_ro, (float *)&motor_1, 0 }, + { "1","1csa", _f0, 0, tx_print_nul, motor_1.get_csa_fn, set_ro, (float *)&motor_1, 0 }, + { "1","1sgs", _f0, 0, tx_print_nul, motor_1.get_sgs_fn, set_ro, (float *)&motor_1, 0 }, + { "1","1tbl", _fip, 0, tx_print_nul, motor_1.get_tbl_fn, motor_1.set_tbl_fn, (float *)&motor_1, M1_TMC2130_TBL }, + { "1","1pgrd",_fip, 0, tx_print_nul, motor_1.get_pgrd_fn,motor_1.set_pgrd_fn, (float *)&motor_1, M1_TMC2130_PWM_GRAD }, + { "1","1pamp",_fip, 0, tx_print_nul, motor_1.get_pamp_fn,motor_1.set_pamp_fn, (float *)&motor_1, M1_TMC2130_PWM_AMPL }, + { "1","1hend",_fip, 0, tx_print_nul, motor_1.get_hend_fn,motor_1.set_hend_fn, (float *)&motor_1, M1_TMC2130_HEND }, + { "1","1hsrt",_fip, 0, tx_print_nul, motor_1.get_hsrt_fn,motor_1.set_hsrt_fn, (float *)&motor_1, M1_TMC2130_HSTRT }, + { "1","1smin",_fip, 0, tx_print_nul, motor_1.get_smin_fn,motor_1.set_smin_fn, (float *)&motor_1, M1_TMC2130_SMIN }, + { "1","1smax",_fip, 0, tx_print_nul, motor_1.get_smax_fn,motor_1.set_smax_fn, (float *)&motor_1, M1_TMC2130_SMAX }, + { "1","1sup", _fip, 0, tx_print_nul, motor_1.get_sup_fn, motor_1.set_sup_fn, (float *)&motor_1, M1_TMC2130_SUP }, + { "1","1sdn", _fip, 0, tx_print_nul, motor_1.get_sdn_fn, motor_1.set_sdn_fn, (float *)&motor_1, M1_TMC2130_SDN }, +#endif #endif #if (MOTORS >= 2) - { "2","2ma",_fip, 0, st_print_ma, get_ui8, st_set_ma, (float *)&st_cfg.mot[MOTOR_2].motor_map, M2_MOTOR_MAP }, - { "2","2sa",_fip, 3, st_print_sa, get_flt, st_set_sa, (float *)&st_cfg.mot[MOTOR_2].step_angle, M2_STEP_ANGLE }, - { "2","2tr",_fipc,4, st_print_tr, get_flt, st_set_tr, (float *)&st_cfg.mot[MOTOR_2].travel_rev, M2_TRAVEL_PER_REV }, - { "2","2mi",_fip, 0, st_print_mi, get_int, st_set_mi, (float *)&st_cfg.mot[MOTOR_2].microsteps, M2_MICROSTEPS }, - { "2","2su",_fipi,5, st_print_su, st_get_su,st_set_su, (float *)&st_cfg.mot[MOTOR_2].steps_per_unit, M2_STEPS_PER_UNIT }, - { "2","2po",_fip, 0, st_print_po, get_ui8, set_01, (float *)&st_cfg.mot[MOTOR_2].polarity, M2_POLARITY }, - { "2","2pm",_fip, 0, st_print_pm, st_get_pm,st_set_pm, (float *)&cs.null, M2_POWER_MODE }, - { "2","2pl",_fip, 3, st_print_pl, get_flt, st_set_pl, (float *)&st_cfg.mot[MOTOR_2].power_level, M2_POWER_LEVEL}, -// { "2","2pi",_fip, 3, st_print_pi, get_flt, st_set_pi, (float *)&st_cfg.mot[MOTOR_2].power_idle, M2_POWER_IDLE }, -// { "2","2mt",_fip, 2, st_print_mt, get_flt, st_set_mt, (float *)&st_cfg.mot[MOTOR_2].motor_timeout, M2_MOTOR_TIMEOUT }, + { "2","2ma", _fip, 0, st_print_ma, get_ui8, st_set_ma, (float *)&st_cfg.mot[MOTOR_2].motor_map, M2_MOTOR_MAP }, + { "2","2sa", _fip, 3, st_print_sa, get_flt, st_set_sa, (float *)&st_cfg.mot[MOTOR_2].step_angle, M2_STEP_ANGLE }, + { "2","2tr", _fipc, 4, st_print_tr, get_flt, st_set_tr, (float *)&st_cfg.mot[MOTOR_2].travel_rev, M2_TRAVEL_PER_REV }, + { "2","2mi", _fip, 0, st_print_mi, get_int, st_set_mi, (float *)&st_cfg.mot[MOTOR_2].microsteps, M2_MICROSTEPS }, + { "2","2su", _fipi, 5, st_print_su, st_get_su,st_set_su, (float *)&st_cfg.mot[MOTOR_2].steps_per_unit, M2_STEPS_PER_UNIT }, + { "2","2po", _fip, 0, st_print_po, get_ui8, set_01, (float *)&st_cfg.mot[MOTOR_2].polarity, M2_POLARITY }, + { "2","2pm", _fip, 0, st_print_pm, st_get_pm,st_set_pm, (float *)&cs.null, M2_POWER_MODE }, + { "2","2pl", _fip, 3, st_print_pl, get_flt, st_set_pl, (float *)&st_cfg.mot[MOTOR_2].power_level, M2_POWER_LEVEL }, + // { "2","2pi", _fip, 3, st_print_pi, get_flt, st_set_pi, (float *)&st_cfg.mot[MOTOR_2].power_idle, M2_POWER_IDLE }, + // { "2","2mt", _fip, 2, st_print_mt, get_flt, st_set_mt, (float *)&st_cfg.mot[MOTOR_2].motor_timeout, M2_MOTOR_TIMEOUT }, #ifdef MOTOR_2_IS_TRINAMIC - { "2","2ts",_f0, 0, tx_print_nul, - [](nvObj_t *nv){return motor_2.get_ts(nv); }, - set_ro, (float *)&cs.null, 0 }, - { "2","2pth",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_2.get_pth(nv);}, - [](nvObj_t *nv){return motor_2.set_pth(nv);}, (float *)&cs.null, M2_TMC2130_TPWMTHRS }, - { "2","2cth",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_2.get_cth(nv);}, - [](nvObj_t *nv){return motor_2.set_cth(nv);}, (float *)&cs.null, M2_TMC2130_TCOOLTHRS }, - { "2","2hth",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_2.get_hth(nv);}, - [](nvObj_t *nv){return motor_2.set_hth(nv);}, (float *)&cs.null, M2_TMC2130_THIGH }, - { "2","2sgt",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_2.get_sgt(nv);}, - [](nvObj_t *nv){return motor_2.set_sgt(nv);}, (float *)&cs.null, M2_TMC2130_SGT }, - { "2","2sgr",_f0, 0, tx_print_nul, - [](nvObj_t *nv){return motor_2.get_sgr(nv);}, - set_ro, (float *)&cs.null, 0 }, - { "2","2csa",_f0, 0, tx_print_nul, - [](nvObj_t *nv){return motor_2.get_csa(nv);}, - set_ro, (float *)&cs.null, 0 }, - { "2","2sgs",_f0, 0, tx_print_nul, - [](nvObj_t *nv){return motor_2.get_sgs(nv);}, - set_ro, (float *)&cs.null, 0 }, - { "2","2tbl",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_2.get_tbl(nv);}, - [](nvObj_t *nv){return motor_2.set_tbl(nv);}, (float *)&cs.null, M2_TMC2130_TBL }, - { "2","2pgrd",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_2.get_pgrd(nv);}, - [](nvObj_t *nv){return motor_2.set_pgrd(nv);}, (float *)&cs.null, M2_TMC2130_PWM_GRAD }, - { "1","2pamp",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_2.get_pamp(nv);}, - [](nvObj_t *nv){return motor_2.set_pamp(nv);}, (float *)&cs.null, M2_TMC2130_PWM_AMPL }, - { "2","2hend",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_2.get_hend(nv);}, - [](nvObj_t *nv){return motor_2.set_hend(nv);}, (float *)&cs.null, M2_TMC2130_HEND }, - { "2","2hsrt",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_2.get_hsrt(nv);}, - [](nvObj_t *nv){return motor_2.set_hsrt(nv);}, (float *)&cs.null, M2_TMC2130_HSTRT }, - { "2","2smin",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_2.get_smin(nv);}, - [](nvObj_t *nv){return motor_2.set_smin(nv);}, (float *)&cs.null, M2_TMC2130_SMIN }, - { "2","2smax",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_2.get_smax(nv);}, - [](nvObj_t *nv){return motor_2.set_smax(nv);}, (float *)&cs.null, M2_TMC2130_SMAX }, - { "2","2sup",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_2.get_sup(nv);}, - [](nvObj_t *nv){return motor_2.set_sup(nv);}, (float *)&cs.null, M2_TMC2130_SUP }, - { "2","2sdn",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_2.get_sdn(nv);}, - [](nvObj_t *nv){return motor_2.set_sdn(nv);}, (float *)&cs.null, M2_TMC2130_SDN }, + { "2","2ts", _f0, 0, tx_print_nul, motor_2.get_ts_fn, set_ro, (float *)&motor_2, 0 }, + { "2","2pth", _fip, 0, tx_print_nul, motor_2.get_pth_fn, motor_2.set_pth_fn, (float *)&motor_2, M2_TMC2130_TPWMTHRS }, + { "2","2cth", _fip, 0, tx_print_nul, motor_2.get_cth_fn, motor_2.set_cth_fn, (float *)&motor_2, M2_TMC2130_TCOOLTHRS }, + { "2","2hth", _fip, 0, tx_print_nul, motor_2.get_hth_fn, motor_2.set_hth_fn, (float *)&motor_2, M2_TMC2130_THIGH }, + { "2","2sgt", _fip, 0, tx_print_nul, motor_2.get_sgt_fn, motor_2.set_sgt_fn, (float *)&motor_2, M2_TMC2130_SGT }, + { "2","2sgr", _f0, 0, tx_print_nul, motor_2.get_sgr_fn, set_ro, (float *)&motor_2, 0 }, + { "2","2csa", _f0, 0, tx_print_nul, motor_2.get_csa_fn, set_ro, (float *)&motor_2, 0 }, + { "2","2sgs", _f0, 0, tx_print_nul, motor_2.get_sgs_fn, set_ro, (float *)&motor_2, 0 }, + { "2","2tbl", _fip, 0, tx_print_nul, motor_2.get_tbl_fn, motor_2.set_tbl_fn, (float *)&motor_2, M2_TMC2130_TBL }, + { "2","2pgrd",_fip, 0, tx_print_nul, motor_2.get_pgrd_fn,motor_2.set_pgrd_fn, (float *)&motor_2, M2_TMC2130_PWM_GRAD }, + { "2","2pamp",_fip, 0, tx_print_nul, motor_2.get_pamp_fn,motor_2.set_pamp_fn, (float *)&motor_2, M2_TMC2130_PWM_AMPL }, + { "2","2hend",_fip, 0, tx_print_nul, motor_2.get_hend_fn,motor_2.set_hend_fn, (float *)&motor_2, M2_TMC2130_HEND }, + { "2","2hsrt",_fip, 0, tx_print_nul, motor_2.get_hsrt_fn,motor_2.set_hsrt_fn, (float *)&motor_2, M2_TMC2130_HSTRT }, + { "2","2smin",_fip, 0, tx_print_nul, motor_2.get_smin_fn,motor_2.set_smin_fn, (float *)&motor_2, M2_TMC2130_SMIN }, + { "2","2smax",_fip, 0, tx_print_nul, motor_2.get_smax_fn,motor_2.set_smax_fn, (float *)&motor_2, M2_TMC2130_SMAX }, + { "2","2sup", _fip, 0, tx_print_nul, motor_2.get_sup_fn, motor_2.set_sup_fn, (float *)&motor_2, M2_TMC2130_SUP }, + { "2","2sdn", _fip, 0, tx_print_nul, motor_2.get_sdn_fn, motor_2.set_sdn_fn, (float *)&motor_2, M2_TMC2130_SDN }, #endif #endif + #if (MOTORS >= 3) - { "3","3ma",_fip, 0, st_print_ma, get_ui8, st_set_ma, (float *)&st_cfg.mot[MOTOR_3].motor_map, M3_MOTOR_MAP }, - { "3","3sa",_fip, 3, st_print_sa, get_flt, st_set_sa, (float *)&st_cfg.mot[MOTOR_3].step_angle, M3_STEP_ANGLE }, - { "3","3tr",_fipc,4, st_print_tr, get_flt, st_set_tr, (float *)&st_cfg.mot[MOTOR_3].travel_rev, M3_TRAVEL_PER_REV }, - { "3","3mi",_fip, 0, st_print_mi, get_int, st_set_mi, (float *)&st_cfg.mot[MOTOR_3].microsteps, M3_MICROSTEPS }, - { "3","3su",_fipi,5, st_print_su, st_get_su,st_set_su, (float *)&st_cfg.mot[MOTOR_3].steps_per_unit, M3_STEPS_PER_UNIT }, - { "3","3po",_fip, 0, st_print_po, get_ui8, set_01, (float *)&st_cfg.mot[MOTOR_3].polarity, M3_POLARITY }, - { "3","3pm",_fip, 0, st_print_pm, st_get_pm,st_set_pm, (float *)&cs.null, M3_POWER_MODE }, - { "3","3pl",_fip, 3, st_print_pl, get_flt, st_set_pl, (float *)&st_cfg.mot[MOTOR_3].power_level, M3_POWER_LEVEL }, -// { "3","3pi",_fip, 3, st_print_pi, get_flt, st_set_pi, (float *)&st_cfg.mot[MOTOR_3].power_idle, M3_POWER_IDLE }, -// { "3","3mt",_fip, 2, st_print_mt, get_flt, st_set_mt, (float *)&st_cfg.mot[MOTOR_3].motor_timeout, M3_MOTOR_TIMEOUT }, + { "3","3ma", _fip, 0, st_print_ma, get_ui8, st_set_ma, (float *)&st_cfg.mot[MOTOR_3].motor_map, M3_MOTOR_MAP }, + { "3","3sa", _fip, 3, st_print_sa, get_flt, st_set_sa, (float *)&st_cfg.mot[MOTOR_3].step_angle, M3_STEP_ANGLE }, + { "3","3tr", _fipc, 4, st_print_tr, get_flt, st_set_tr, (float *)&st_cfg.mot[MOTOR_3].travel_rev, M3_TRAVEL_PER_REV }, + { "3","3mi", _fip, 0, st_print_mi, get_int, st_set_mi, (float *)&st_cfg.mot[MOTOR_3].microsteps, M3_MICROSTEPS }, + { "3","3su", _fipi, 5, st_print_su, st_get_su,st_set_su, (float *)&st_cfg.mot[MOTOR_3].steps_per_unit, M3_STEPS_PER_UNIT }, + { "3","3po", _fip, 0, st_print_po, get_ui8, set_01, (float *)&st_cfg.mot[MOTOR_3].polarity, M3_POLARITY }, + { "3","3pm", _fip, 0, st_print_pm, st_get_pm,st_set_pm, (float *)&cs.null, M3_POWER_MODE }, + { "3","3pl", _fip, 3, st_print_pl, get_flt, st_set_pl, (float *)&st_cfg.mot[MOTOR_3].power_level, M3_POWER_LEVEL }, + // { "3","3pi", _fip, 3, st_print_pi, get_flt, st_set_pi, (float *)&st_cfg.mot[MOTOR_3].power_idle, M3_POWER_IDLE }, + // { "3","3mt", _fip, 2, st_print_mt, get_flt, st_set_mt, (float *)&st_cfg.mot[MOTOR_3].motor_timeout, M3_MOTOR_TIMEOUT }, #ifdef MOTOR_3_IS_TRINAMIC - { "3","3ts",_f0, 0, tx_print_nul, - [](nvObj_t *nv){return motor_3.get_ts(nv); }, - set_ro, (float *)&cs.null, 0 }, - { "3","3pth",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_3.get_pth(nv);}, - [](nvObj_t *nv){return motor_3.set_pth(nv);}, (float *)&cs.null, M3_TMC2130_TPWMTHRS }, - { "3","3cth",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_3.get_cth(nv);}, - [](nvObj_t *nv){return motor_3.set_cth(nv);}, (float *)&cs.null, M3_TMC2130_TCOOLTHRS }, - { "3","3hth",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_3.get_hth(nv);}, - [](nvObj_t *nv){return motor_3.set_hth(nv);}, (float *)&cs.null, M3_TMC2130_THIGH }, - { "3","3sgt",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_3.get_sgt(nv);}, - [](nvObj_t *nv){return motor_3.set_sgt(nv);}, (float *)&cs.null, M3_TMC2130_SGT }, - { "3","3sgr",_f0, 0, tx_print_nul, - [](nvObj_t *nv){return motor_3.get_sgr(nv);}, - set_ro, (float *)&cs.null, 0 }, - { "3","3csa",_f0, 0, tx_print_nul, - [](nvObj_t *nv){return motor_3.get_csa(nv);}, - set_ro, (float *)&cs.null, 0 }, - { "3","3sgs",_f0, 0, tx_print_nul, - [](nvObj_t *nv){return motor_3.get_sgs(nv);}, - set_ro, (float *)&cs.null, 0 }, - { "3","3tbl",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_3.get_tbl(nv);}, - [](nvObj_t *nv){return motor_3.set_tbl(nv);}, (float *)&cs.null, M3_TMC2130_TBL }, - { "3","3pgrd",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_3.get_pgrd(nv);}, - [](nvObj_t *nv){return motor_3.set_pgrd(nv);}, (float *)&cs.null, M3_TMC2130_PWM_GRAD }, - { "1","3pamp",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_3.get_pamp(nv);}, - [](nvObj_t *nv){return motor_3.set_pamp(nv);}, (float *)&cs.null, M3_TMC2130_PWM_AMPL }, - { "3","3hend",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_3.get_hend(nv);}, - [](nvObj_t *nv){return motor_3.set_hend(nv);}, (float *)&cs.null, M3_TMC2130_HEND }, - { "3","3hsrt",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_3.get_hsrt(nv);}, - [](nvObj_t *nv){return motor_3.set_hsrt(nv);}, (float *)&cs.null, M3_TMC2130_HSTRT }, - { "3","3smin",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_3.get_smin(nv);}, - [](nvObj_t *nv){return motor_3.set_smin(nv);}, (float *)&cs.null, M3_TMC2130_SMIN }, - { "3","3smax",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_3.get_smax(nv);}, - [](nvObj_t *nv){return motor_3.set_smax(nv);}, (float *)&cs.null, M3_TMC2130_SMAX }, - { "3","3sup",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_3.get_sup(nv);}, - [](nvObj_t *nv){return motor_3.set_sup(nv);}, (float *)&cs.null, M3_TMC2130_SUP }, - { "3","3sdn",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_3.get_sdn(nv);}, - [](nvObj_t *nv){return motor_3.set_sdn(nv);}, (float *)&cs.null, M3_TMC2130_SDN }, + { "3","3ts", _f0, 0, tx_print_nul, motor_3.get_ts_fn, set_ro, (float *)&motor_3, 0 }, + { "3","3pth", _fip, 0, tx_print_nul, motor_3.get_pth_fn, motor_3.set_pth_fn, (float *)&motor_3, M3_TMC2130_TPWMTHRS }, + { "3","3cth", _fip, 0, tx_print_nul, motor_3.get_cth_fn, motor_3.set_cth_fn, (float *)&motor_3, M3_TMC2130_TCOOLTHRS }, + { "3","3hth", _fip, 0, tx_print_nul, motor_3.get_hth_fn, motor_3.set_hth_fn, (float *)&motor_3, M3_TMC2130_THIGH }, + { "3","3sgt", _fip, 0, tx_print_nul, motor_3.get_sgt_fn, motor_3.set_sgt_fn, (float *)&motor_3, M3_TMC2130_SGT }, + { "3","3sgr", _f0, 0, tx_print_nul, motor_3.get_sgr_fn, set_ro, (float *)&motor_3, 0 }, + { "3","3csa", _f0, 0, tx_print_nul, motor_3.get_csa_fn, set_ro, (float *)&motor_3, 0 }, + { "3","3sgs", _f0, 0, tx_print_nul, motor_3.get_sgs_fn, set_ro, (float *)&motor_3, 0 }, + { "3","3tbl", _fip, 0, tx_print_nul, motor_3.get_tbl_fn, motor_3.set_tbl_fn, (float *)&motor_3, M3_TMC2130_TBL }, + { "3","3pgrd",_fip, 0, tx_print_nul, motor_3.get_pgrd_fn,motor_3.set_pgrd_fn, (float *)&motor_3, M3_TMC2130_PWM_GRAD }, + { "3","3pamp",_fip, 0, tx_print_nul, motor_3.get_pamp_fn,motor_3.set_pamp_fn, (float *)&motor_3, M3_TMC2130_PWM_AMPL }, + { "3","3hend",_fip, 0, tx_print_nul, motor_3.get_hend_fn,motor_3.set_hend_fn, (float *)&motor_3, M3_TMC2130_HEND }, + { "3","3hsrt",_fip, 0, tx_print_nul, motor_3.get_hsrt_fn,motor_3.set_hsrt_fn, (float *)&motor_3, M3_TMC2130_HSTRT }, + { "3","3smin",_fip, 0, tx_print_nul, motor_3.get_smin_fn,motor_3.set_smin_fn, (float *)&motor_3, M3_TMC2130_SMIN }, + { "3","3smax",_fip, 0, tx_print_nul, motor_3.get_smax_fn,motor_3.set_smax_fn, (float *)&motor_3, M3_TMC2130_SMAX }, + { "3","3sup", _fip, 0, tx_print_nul, motor_3.get_sup_fn, motor_3.set_sup_fn, (float *)&motor_3, M3_TMC2130_SUP }, + { "3","3sdn", _fip, 0, tx_print_nul, motor_3.get_sdn_fn, motor_3.set_sdn_fn, (float *)&motor_3, M3_TMC2130_SDN }, #endif #endif + #if (MOTORS >= 4) - { "4","4ma",_fip, 0, st_print_ma, get_ui8, st_set_ma, (float *)&st_cfg.mot[MOTOR_4].motor_map, M4_MOTOR_MAP }, - { "4","4sa",_fip, 3, st_print_sa, get_flt, st_set_sa, (float *)&st_cfg.mot[MOTOR_4].step_angle, M4_STEP_ANGLE }, - { "4","4tr",_fipc,4, st_print_tr, get_flt, st_set_tr, (float *)&st_cfg.mot[MOTOR_4].travel_rev, M4_TRAVEL_PER_REV }, - { "4","4mi",_fip, 0, st_print_mi, get_int, st_set_mi, (float *)&st_cfg.mot[MOTOR_4].microsteps, M4_MICROSTEPS }, - { "4","4su",_fipi,5, st_print_su, st_get_su,st_set_su, (float *)&st_cfg.mot[MOTOR_4].steps_per_unit, M4_STEPS_PER_UNIT }, - { "4","4po",_fip, 0, st_print_po, get_ui8, set_01, (float *)&st_cfg.mot[MOTOR_4].polarity, M4_POLARITY }, - { "4","4pm",_fip, 0, st_print_pm, st_get_pm,st_set_pm, (float *)&cs.null, M4_POWER_MODE }, - { "4","4pl",_fip, 3, st_print_pl, get_flt, st_set_pl, (float *)&st_cfg.mot[MOTOR_4].power_level, M4_POWER_LEVEL }, -// { "4","4pi",_fip, 3, st_print_pi, get_flt, st_set_pi, (float *)&st_cfg.mot[MOTOR_4].power_idle, M4_POWER_IDLE }, -// { "4","4mt",_fip, 2, st_print_mt, get_flt, st_set_mt, (float *)&st_cfg.mot[MOTOR_4].motor_timeout, M4_MOTOR_TIMEOUT }, + { "4","4ma", _fip, 0, st_print_ma, get_ui8, st_set_ma, (float *)&st_cfg.mot[MOTOR_4].motor_map, M4_MOTOR_MAP }, + { "4","4sa", _fip, 3, st_print_sa, get_flt, st_set_sa, (float *)&st_cfg.mot[MOTOR_4].step_angle, M4_STEP_ANGLE }, + { "4","4tr", _fipc, 4, st_print_tr, get_flt, st_set_tr, (float *)&st_cfg.mot[MOTOR_4].travel_rev, M4_TRAVEL_PER_REV }, + { "4","4mi", _fip, 0, st_print_mi, get_int, st_set_mi, (float *)&st_cfg.mot[MOTOR_4].microsteps, M4_MICROSTEPS }, + { "4","4su", _fipi, 5, st_print_su, st_get_su,st_set_su, (float *)&st_cfg.mot[MOTOR_4].steps_per_unit, M4_STEPS_PER_UNIT }, + { "4","4po", _fip, 0, st_print_po, get_ui8, set_01, (float *)&st_cfg.mot[MOTOR_4].polarity, M4_POLARITY }, + { "4","4pm", _fip, 0, st_print_pm, st_get_pm,st_set_pm, (float *)&cs.null, M4_POWER_MODE }, + { "4","4pl", _fip, 3, st_print_pl, get_flt, st_set_pl, (float *)&st_cfg.mot[MOTOR_4].power_level, M4_POWER_LEVEL }, + // { "4","4pi", _fip, 3, st_print_pi, get_flt, st_set_pi, (float *)&st_cfg.mot[MOTOR_4].power_idle, M4_POWER_IDLE }, + // { "4","4mt", _fip, 2, st_print_mt, get_flt, st_set_mt, (float *)&st_cfg.mot[MOTOR_4].motor_timeout, M4_MOTOR_TIMEOUT }, #ifdef MOTOR_4_IS_TRINAMIC - { "4","4ts",_f0, 0, tx_print_nul, - [](nvObj_t *nv){return motor_4.get_ts(nv); }, - set_ro, (float *)&cs.null, 0 }, - { "4","4pth",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_4.get_pth(nv);}, - [](nvObj_t *nv){return motor_4.set_pth(nv);}, (float *)&cs.null, M4_TMC2130_TPWMTHRS }, - { "4","4cth",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_4.get_cth(nv);}, - [](nvObj_t *nv){return motor_4.set_cth(nv);}, (float *)&cs.null, M4_TMC2130_TCOOLTHRS }, - { "4","4hth",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_4.get_hth(nv);}, - [](nvObj_t *nv){return motor_4.set_hth(nv);}, (float *)&cs.null, M4_TMC2130_THIGH }, - { "4","4sgt",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_4.get_sgt(nv);}, - [](nvObj_t *nv){return motor_4.set_sgt(nv);}, (float *)&cs.null, M4_TMC2130_SGT }, - { "4","4sgr",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_4.get_sgr(nv);}, - set_ro, (float *)&cs.null, 0 }, - { "4","4csa",_f0, 0, tx_print_nul, - [](nvObj_t *nv){return motor_4.get_csa(nv);}, - set_ro, (float *)&cs.null, 0 }, - { "4","4sgs",_f0, 0, tx_print_nul, - [](nvObj_t *nv){return motor_4.get_sgs(nv);}, - set_ro, (float *)&cs.null, 0 }, - { "4","4tbl",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_4.get_tbl(nv);}, - [](nvObj_t *nv){return motor_4.set_tbl(nv);}, (float *)&cs.null, M4_TMC2130_TBL }, - { "4","4pgrd",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_4.get_pgrd(nv);}, - [](nvObj_t *nv){return motor_4.set_pgrd(nv);}, (float *)&cs.null, M4_TMC2130_PWM_GRAD }, - { "1","4pamp",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_4.get_pamp(nv);}, - [](nvObj_t *nv){return motor_4.set_pamp(nv);}, (float *)&cs.null, M4_TMC2130_PWM_AMPL }, - { "4","4hend",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_4.get_hend(nv);}, - [](nvObj_t *nv){return motor_4.set_hend(nv);}, (float *)&cs.null, M4_TMC2130_HEND }, - { "4","4hsrt",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_4.get_hsrt(nv);}, - [](nvObj_t *nv){return motor_4.set_hsrt(nv);}, (float *)&cs.null, M4_TMC2130_HSTRT }, - { "4","4hend",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_4.get_hend(nv);}, - [](nvObj_t *nv){return motor_4.set_hend(nv);}, (float *)&cs.null, M4_TMC2130_HEND }, - { "4","4hsrt",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_4.get_hsrt(nv);}, - [](nvObj_t *nv){return motor_4.set_hsrt(nv);}, (float *)&cs.null, M4_TMC2130_HSTRT }, - { "4","4smin",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_4.get_smin(nv);}, - [](nvObj_t *nv){return motor_4.set_smin(nv);}, (float *)&cs.null, M4_TMC2130_SMIN }, - { "4","4smax",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_4.get_smax(nv);}, - [](nvObj_t *nv){return motor_4.set_smax(nv);}, (float *)&cs.null, M4_TMC2130_SMAX }, - { "4","4sup",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_4.get_sup(nv);}, - [](nvObj_t *nv){return motor_4.set_sup(nv);}, (float *)&cs.null, M4_TMC2130_SUP }, - { "4","4sdn",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_4.get_sdn(nv);}, - [](nvObj_t *nv){return motor_4.set_sdn(nv);}, (float *)&cs.null, M4_TMC2130_SDN }, + { "4","4ts", _f0, 0, tx_print_nul, motor_4.get_ts_fn, set_ro, (float *)&motor_4, 0 }, + { "4","4pth", _fip, 0, tx_print_nul, motor_4.get_pth_fn, motor_4.set_pth_fn, (float *)&motor_4, M4_TMC2130_TPWMTHRS }, + { "4","4cth", _fip, 0, tx_print_nul, motor_4.get_cth_fn, motor_4.set_cth_fn, (float *)&motor_4, M4_TMC2130_TCOOLTHRS }, + { "4","4hth", _fip, 0, tx_print_nul, motor_4.get_hth_fn, motor_4.set_hth_fn, (float *)&motor_4, M4_TMC2130_THIGH }, + { "4","4sgt", _fip, 0, tx_print_nul, motor_4.get_sgt_fn, motor_4.set_sgt_fn, (float *)&motor_4, M4_TMC2130_SGT }, + { "4","4sgr", _f0, 0, tx_print_nul, motor_4.get_sgr_fn, set_ro, (float *)&motor_4, 0 }, + { "4","4csa", _f0, 0, tx_print_nul, motor_4.get_csa_fn, set_ro, (float *)&motor_4, 0 }, + { "4","4sgs", _f0, 0, tx_print_nul, motor_4.get_sgs_fn, set_ro, (float *)&motor_4, 0 }, + { "4","4tbl", _fip, 0, tx_print_nul, motor_4.get_tbl_fn, motor_4.set_tbl_fn, (float *)&motor_4, M4_TMC2130_TBL }, + { "4","4pgrd",_fip, 0, tx_print_nul, motor_4.get_pgrd_fn,motor_4.set_pgrd_fn, (float *)&motor_4, M4_TMC2130_PWM_GRAD }, + { "4","4pamp",_fip, 0, tx_print_nul, motor_4.get_pamp_fn,motor_4.set_pamp_fn, (float *)&motor_4, M4_TMC2130_PWM_AMPL }, + { "4","4hend",_fip, 0, tx_print_nul, motor_4.get_hend_fn,motor_4.set_hend_fn, (float *)&motor_4, M4_TMC2130_HEND }, + { "4","4hsrt",_fip, 0, tx_print_nul, motor_4.get_hsrt_fn,motor_4.set_hsrt_fn, (float *)&motor_4, M4_TMC2130_HSTRT }, + { "4","4smin",_fip, 0, tx_print_nul, motor_4.get_smin_fn,motor_4.set_smin_fn, (float *)&motor_4, M4_TMC2130_SMIN }, + { "4","4smax",_fip, 0, tx_print_nul, motor_4.get_smax_fn,motor_4.set_smax_fn, (float *)&motor_4, M4_TMC2130_SMAX }, + { "4","4sup", _fip, 0, tx_print_nul, motor_4.get_sup_fn, motor_4.set_sup_fn, (float *)&motor_4, M4_TMC2130_SUP }, + { "4","4sdn", _fip, 0, tx_print_nul, motor_4.get_sdn_fn, motor_4.set_sdn_fn, (float *)&motor_4, M4_TMC2130_SDN }, #endif #endif + #if (MOTORS >= 5) - { "5","5ma",_fip, 0, st_print_ma, get_ui8, st_set_ma, (float *)&st_cfg.mot[MOTOR_5].motor_map, M5_MOTOR_MAP }, - { "5","5sa",_fip, 3, st_print_sa, get_flt, st_set_sa, (float *)&st_cfg.mot[MOTOR_5].step_angle, M5_STEP_ANGLE }, - { "5","5tr",_fipc,4, st_print_tr, get_flt, st_set_tr, (float *)&st_cfg.mot[MOTOR_5].travel_rev, M5_TRAVEL_PER_REV }, - { "5","5mi",_fip, 0, st_print_mi, get_int, st_set_mi, (float *)&st_cfg.mot[MOTOR_5].microsteps, M5_MICROSTEPS }, - { "5","5su",_fipi,5, st_print_su, st_get_su,st_set_su, (float *)&st_cfg.mot[MOTOR_5].steps_per_unit, M5_STEPS_PER_UNIT }, - { "5","5po",_fip, 0, st_print_po, get_ui8, set_01, (float *)&st_cfg.mot[MOTOR_5].polarity, M5_POLARITY }, - { "5","5pm",_fip, 0, st_print_pm, st_get_pm,st_set_pm, (float *)&cs.null, M5_POWER_MODE }, - { "5","5pl",_fip, 3, st_print_pl, get_flt, st_set_pl, (float *)&st_cfg.mot[MOTOR_5].power_level, M5_POWER_LEVEL }, -// { "5","5pi",_fip, 3, st_print_pi, get_flt, st_set_pi, (float *)&st_cfg.mot[MOTOR_5].power_idle, M5_POWER_IDLE }, -// { "5","5mt",_fip, 2, st_print_mt, get_flt, st_set_mt, (float *)&st_cfg.mot[MOTOR_5].motor_timeout, M5_MOTOR_TIMEOUT }, + { "5","5ma", _fip, 0, st_print_ma, get_ui8, st_set_ma, (float *)&st_cfg.mot[MOTOR_5].motor_map, M5_MOTOR_MAP }, + { "5","5sa", _fip, 3, st_print_sa, get_flt, st_set_sa, (float *)&st_cfg.mot[MOTOR_5].step_angle, M5_STEP_ANGLE }, + { "5","5tr", _fipc, 4, st_print_tr, get_flt, st_set_tr, (float *)&st_cfg.mot[MOTOR_5].travel_rev, M5_TRAVEL_PER_REV }, + { "5","5mi", _fip, 0, st_print_mi, get_int, st_set_mi, (float *)&st_cfg.mot[MOTOR_5].microsteps, M5_MICROSTEPS }, + { "5","5su", _fipi, 5, st_print_su, st_get_su,st_set_su, (float *)&st_cfg.mot[MOTOR_5].steps_per_unit, M5_STEPS_PER_UNIT }, + { "5","5po", _fip, 0, st_print_po, get_ui8, set_01, (float *)&st_cfg.mot[MOTOR_5].polarity, M5_POLARITY }, + { "5","5pm", _fip, 0, st_print_pm, st_get_pm,st_set_pm, (float *)&cs.null, M5_POWER_MODE }, + { "5","5pl", _fip, 3, st_print_pl, get_flt, st_set_pl, (float *)&st_cfg.mot[MOTOR_5].power_level, M5_POWER_LEVEL }, + // { "5","5pi", _fip, 3, st_print_pi, get_flt, st_set_pi, (float *)&st_cfg.mot[MOTOR_5].power_idle, M5_POWER_IDLE }, + // { "5","5mt", _fip, 2, st_print_mt, get_flt, st_set_mt, (float *)&st_cfg.mot[MOTOR_5].motor_timeout, M5_MOTOR_TIMEOUT }, #ifdef MOTOR_5_IS_TRINAMIC - { "5","5ts",_f0, 0, tx_print_nul, - [](nvObj_t *nv){return motor_5.get_ts(nv); }, - set_ro, (float *)&cs.null, 0 }, - { "5","5pth",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_5.get_pth(nv);}, - [](nvObj_t *nv){return motor_5.set_pth(nv);}, (float *)&cs.null, M5_TMC2130_TPWMTHRS }, - { "5","5cth",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_5.get_cth(nv);}, - [](nvObj_t *nv){return motor_5.set_cth(nv);}, (float *)&cs.null, M5_TMC2130_TCOOLTHRS }, - { "5","5hth",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_5.get_hth(nv);}, - [](nvObj_t *nv){return motor_5.set_hth(nv);}, (float *)&cs.null, M5_TMC2130_THIGH }, - { "5","5sgt",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_5.get_sgt(nv);}, - [](nvObj_t *nv){return motor_5.set_sgt(nv);}, (float *)&cs.null, M5_TMC2130_SGT }, - { "5","5sgr",_f0, 0, tx_print_nul, - [](nvObj_t *nv){return motor_5.get_sgr(nv);}, - set_ro, (float *)&cs.null, 0 }, - { "5","5csa",_f0, 0, tx_print_nul, - [](nvObj_t *nv){return motor_5.get_csa(nv);}, - set_ro, (float *)&cs.null, 0 }, - { "5","5sgs",_f0, 0, tx_print_nul, - [](nvObj_t *nv){return motor_5.get_sgs(nv);}, - set_ro, (float *)&cs.null, 0 }, - { "5","5tbl",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_5.get_tbl(nv);}, - [](nvObj_t *nv){return motor_5.set_tbl(nv);}, (float *)&cs.null, M5_TMC2130_TBL }, - { "5","5pgrd",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_5.get_pgrd(nv);}, - [](nvObj_t *nv){return motor_5.set_pgrd(nv);}, (float *)&cs.null, M5_TMC2130_PWM_GRAD }, - { "5","5pamp",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_5.get_pamp(nv);}, - [](nvObj_t *nv){return motor_5.set_pamp(nv);}, (float *)&cs.null, M5_TMC2130_PWM_AMPL }, - { "5","5hend",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_5.get_hend(nv);}, - [](nvObj_t *nv){return motor_5.set_hend(nv);}, (float *)&cs.null, M5_TMC2130_HEND }, - { "5","5hsrt",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_5.get_hsrt(nv);}, - [](nvObj_t *nv){return motor_5.set_hsrt(nv);}, (float *)&cs.null, M5_TMC2130_HSTRT }, - { "5","5smin",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_5.get_smin(nv);}, - [](nvObj_t *nv){return motor_5.set_smin(nv);}, (float *)&cs.null, M5_TMC2130_SMIN }, - { "5","5smax",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_5.get_smax(nv);}, - [](nvObj_t *nv){return motor_5.set_smax(nv);}, (float *)&cs.null, M5_TMC2130_SMAX }, - { "5","5sup",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_5.get_sup(nv);}, - [](nvObj_t *nv){return motor_5.set_sup(nv);}, (float *)&cs.null, M5_TMC2130_SUP }, - { "5","5sdn",_fip, 0, tx_print_nul, - [](nvObj_t *nv){return motor_5.get_sdn(nv);}, - [](nvObj_t *nv){return motor_5.set_sdn(nv);}, (float *)&cs.null, M5_TMC2130_SDN }, + { "5","5ts", _f0, 0, tx_print_nul, motor_5.get_ts_fn, set_ro, (float *)&motor_5, 0 }, + { "5","5pth", _fip, 0, tx_print_nul, motor_5.get_pth_fn, motor_5.set_pth_fn, (float *)&motor_5, M5_TMC2130_TPWMTHRS }, + { "5","5cth", _fip, 0, tx_print_nul, motor_5.get_cth_fn, motor_5.set_cth_fn, (float *)&motor_5, M5_TMC2130_TCOOLTHRS }, + { "5","5hth", _fip, 0, tx_print_nul, motor_5.get_hth_fn, motor_5.set_hth_fn, (float *)&motor_5, M5_TMC2130_THIGH }, + { "5","5sgt", _fip, 0, tx_print_nul, motor_5.get_sgt_fn, motor_5.set_sgt_fn, (float *)&motor_5, M5_TMC2130_SGT }, + { "5","5sgr", _f0, 0, tx_print_nul, motor_5.get_sgr_fn, set_ro, (float *)&motor_5, 0 }, + { "5","5csa", _f0, 0, tx_print_nul, motor_5.get_csa_fn, set_ro, (float *)&motor_5, 0 }, + { "5","5sgs", _f0, 0, tx_print_nul, motor_5.get_sgs_fn, set_ro, (float *)&motor_5, 0 }, + { "5","5tbl", _fip, 0, tx_print_nul, motor_5.get_tbl_fn, motor_5.set_tbl_fn, (float *)&motor_5, M5_TMC2130_TBL }, + { "5","5pgrd",_fip, 0, tx_print_nul, motor_5.get_pgrd_fn,motor_5.set_pgrd_fn, (float *)&motor_5, M5_TMC2130_PWM_GRAD }, + { "5","5pamp",_fip, 0, tx_print_nul, motor_5.get_pamp_fn,motor_5.set_pamp_fn, (float *)&motor_5, M5_TMC2130_PWM_AMPL }, + { "5","5hend",_fip, 0, tx_print_nul, motor_5.get_hend_fn,motor_5.set_hend_fn, (float *)&motor_5, M5_TMC2130_HEND }, + { "5","5hsrt",_fip, 0, tx_print_nul, motor_5.get_hsrt_fn,motor_5.set_hsrt_fn, (float *)&motor_5, M5_TMC2130_HSTRT }, + { "5","5smin",_fip, 0, tx_print_nul, motor_5.get_smin_fn,motor_5.set_smin_fn, (float *)&motor_5, M5_TMC2130_SMIN }, + { "5","5smax",_fip, 0, tx_print_nul, motor_5.get_smax_fn,motor_5.set_smax_fn, (float *)&motor_5, M5_TMC2130_SMAX }, + { "5","5sup", _fip, 0, tx_print_nul, motor_5.get_sup_fn, motor_5.set_sup_fn, (float *)&motor_5, M5_TMC2130_SUP }, + { "5","5sdn", _fip, 0, tx_print_nul, motor_5.get_sdn_fn, motor_5.set_sdn_fn, (float *)&motor_5, M5_TMC2130_SDN }, #endif #endif + #if (MOTORS >= 6) - { "6","6ma",_fip, 0, st_print_ma, get_ui8, st_set_ma, (float *)&st_cfg.mot[MOTOR_6].motor_map, M6_MOTOR_MAP }, - { "6","6sa",_fip, 3, st_print_sa, get_flt, st_set_sa, (float *)&st_cfg.mot[MOTOR_6].step_angle, M6_STEP_ANGLE }, - { "6","6tr",_fipc,4, st_print_tr, get_flt, st_set_tr, (float *)&st_cfg.mot[MOTOR_6].travel_rev, M6_TRAVEL_PER_REV }, - { "6","6mi",_fip, 0, st_print_mi, get_int, st_set_mi, (float *)&st_cfg.mot[MOTOR_6].microsteps, M6_MICROSTEPS }, - { "6","6su",_fipi,5, st_print_su, st_get_su,st_set_su, (float *)&st_cfg.mot[MOTOR_6].steps_per_unit, M6_STEPS_PER_UNIT }, - { "6","6po",_fip, 0, st_print_po, get_ui8, set_01, (float *)&st_cfg.mot[MOTOR_6].polarity, M6_POLARITY }, - { "6","6pm",_fip, 0, st_print_pm, st_get_pm,st_set_pm, (float *)&cs.null, M6_POWER_MODE }, - { "6","6pl",_fip, 3, st_print_pl, get_flt, st_set_pl, (float *)&st_cfg.mot[MOTOR_6].power_level, M6_POWER_LEVEL }, -// { "6","6pi",_fip, 3, st_print_pi, get_flt, st_set_pi, (float *)&st_cfg.mot[MOTOR_6].power_idle, M6_POWER_IDLE }, -// { "6","6mt",_fip, 2, st_print_mt, get_flt, st_set_mt, (float *)&st_cfg.mot[MOTOR_6].motor_timeout, M6_MOTOR_TIMEOUT }, + { "6","6ma", _fip, 0, st_print_ma, get_ui8, st_set_ma, (float *)&st_cfg.mot[MOTOR_6].motor_map, M6_MOTOR_MAP }, + { "6","6sa", _fip, 3, st_print_sa, get_flt, st_set_sa, (float *)&st_cfg.mot[MOTOR_6].step_angle, M6_STEP_ANGLE }, + { "6","6tr", _fipc, 4, st_print_tr, get_flt, st_set_tr, (float *)&st_cfg.mot[MOTOR_6].travel_rev, M6_TRAVEL_PER_REV }, + { "6","6mi", _fip, 0, st_print_mi, get_int, st_set_mi, (float *)&st_cfg.mot[MOTOR_6].microsteps, M6_MICROSTEPS }, + { "6","6su", _fipi, 5, st_print_su, st_get_su,st_set_su, (float *)&st_cfg.mot[MOTOR_6].steps_per_unit, M6_STEPS_PER_UNIT }, + { "6","6po", _fip, 0, st_print_po, get_ui8, set_01, (float *)&st_cfg.mot[MOTOR_6].polarity, M6_POLARITY }, + { "6","6pm", _fip, 0, st_print_pm, st_get_pm,st_set_pm, (float *)&cs.null, M6_POWER_MODE }, + { "6","6pl", _fip, 3, st_print_pl, get_flt, st_set_pl, (float *)&st_cfg.mot[MOTOR_6].power_level, M6_POWER_LEVEL }, + // { "6","6pi", _fip, 3, st_print_pi, get_flt, st_set_pi, (float *)&st_cfg.mot[MOTOR_6].power_idle, M6_POWER_IDLE }, + // { "6","6mt", _fip, 2, st_print_mt, get_flt, st_set_mt, (float *)&st_cfg.mot[MOTOR_6].motor_timeout, M6_MOTOR_TIMEOUT }, +#ifdef MOTOR_6_IS_TRINAMIC + { "6","6ts", _f0, 0, tx_print_nul, motor_6.get_ts_fn, set_ro, (float *)&motor_6, 0 }, + { "6","6pth", _fip, 0, tx_print_nul, motor_6.get_pth_fn, motor_6.set_pth_fn, (float *)&motor_6, M6_TMC2130_TPWMTHRS }, + { "6","6cth", _fip, 0, tx_print_nul, motor_6.get_cth_fn, motor_6.set_cth_fn, (float *)&motor_6, M6_TMC2130_TCOOLTHRS }, + { "6","6hth", _fip, 0, tx_print_nul, motor_6.get_hth_fn, motor_6.set_hth_fn, (float *)&motor_6, M6_TMC2130_THIGH }, + { "6","6sgt", _fip, 0, tx_print_nul, motor_6.get_sgt_fn, motor_6.set_sgt_fn, (float *)&motor_6, M6_TMC2130_SGT }, + { "6","6sgr", _f0, 0, tx_print_nul, motor_6.get_sgr_fn, set_ro, (float *)&motor_6, 0 }, + { "6","6csa", _f0, 0, tx_print_nul, motor_6.get_csa_fn, set_ro, (float *)&motor_6, 0 }, + { "6","6sgs", _f0, 0, tx_print_nul, motor_6.get_sgs_fn, set_ro, (float *)&motor_6, 0 }, + { "6","6tbl", _fip, 0, tx_print_nul, motor_6.get_tbl_fn, motor_6.set_tbl_fn, (float *)&motor_6, M6_TMC2130_TBL }, + { "6","6pgrd",_fip, 0, tx_print_nul, motor_6.get_pgrd_fn,motor_6.set_pgrd_fn, (float *)&motor_6, M6_TMC2130_PWM_GRAD }, + { "6","6pamp",_fip, 0, tx_print_nul, motor_6.get_pamp_fn,motor_6.set_pamp_fn, (float *)&motor_6, M6_TMC2130_PWM_AMPL }, + { "6","6hend",_fip, 0, tx_print_nul, motor_6.get_hend_fn,motor_6.set_hend_fn, (float *)&motor_6, M6_TMC2130_HEND }, + { "6","6hsrt",_fip, 0, tx_print_nul, motor_6.get_hsrt_fn,motor_6.set_hsrt_fn, (float *)&motor_6, M6_TMC2130_HSTRT }, + { "6","6smin",_fip, 0, tx_print_nul, motor_6.get_smin_fn,motor_6.set_smin_fn, (float *)&motor_6, M6_TMC2130_SMIN }, + { "6","6smax",_fip, 0, tx_print_nul, motor_6.get_smax_fn,motor_6.set_smax_fn, (float *)&motor_6, M6_TMC2130_SMAX }, + { "6","6sup", _fip, 0, tx_print_nul, motor_6.get_sup_fn, motor_6.set_sup_fn, (float *)&motor_6, M6_TMC2130_SUP }, + { "6","6sdn", _fip, 0, tx_print_nul, motor_6.get_sdn_fn, motor_6.set_sdn_fn, (float *)&motor_6, M6_TMC2130_SDN }, +#endif #endif // Axis parameters @@ -592,6 +442,10 @@ const cfgItem_t cfgArray[] = { { "a","ajm",_fip, 0, cm_print_jm, get_flt, cm_set_jm, (float *)&cm.a[AXIS_A].jerk_max, A_JERK_MAX }, { "a","ajh",_fip, 0, cm_print_jh, get_flt, cm_set_jh, (float *)&cm.a[AXIS_A].jerk_high, A_JERK_HIGH_SPEED }, { "a","ara",_fipc, 3, cm_print_ra, get_flt, set_flt, (float *)&cm.a[AXIS_A].radius, A_RADIUS}, + { "a","asf",_fipc, 3, cm_print_sf, get_flt, set_flt, (float *)&cm.a[AXIS_A].spring_offset_factor, A_SPRING_OFFSET_FACTOR}, + { "a","asm",_fipc, 3, cm_print_sm, get_flt, set_flt, (float *)&cm.a[AXIS_A].spring_offset_max, A_SPRING_OFFSET_MAX}, + { "a","arf",_fipc, 3, cm_print_sf, get_flt, set_flt, (float *)&cm.a[AXIS_A].spring_retraction_factor,A_SPRING_RETRACTION_FACTOR}, + { "a","aso", _f0, 3, cm_print_so, cm_get_so, set_ro, (float *)&cs.null, 0 }, { "a","ahi",_fip, 0, cm_print_hi, get_ui8, cm_set_hi, (float *)&cm.a[AXIS_A].homing_input, A_HOMING_INPUT }, { "a","ahd",_fip, 0, cm_print_hd, get_ui8, set_01, (float *)&cm.a[AXIS_A].homing_dir, A_HOMING_DIRECTION }, { "a","asv",_fip, 0, cm_print_sv, get_flt, set_fltp, (float *)&cm.a[AXIS_A].search_velocity,A_SEARCH_VELOCITY }, diff --git a/g2core/device/trinamic/tmc2130.h b/g2core/device/trinamic/tmc2130.h index 0b78bbadc..3dd701009 100644 --- a/g2core/device/trinamic/tmc2130.h +++ b/g2core/device/trinamic/tmc2130.h @@ -26,6 +26,10 @@ * OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ +#include "controller.h" +#include "json_parser.h" // for nv, etc +#include "text_parser.h" // for txt_* commands + #include "stepper.h" #include "MotateSPI.h" @@ -47,6 +51,8 @@ template struct Trinamic2130 final : Stepper { + typedef Trinamic2130 type; + // Pins that are directly managed OutputPin _step; OutputPin _dir; @@ -693,6 +699,12 @@ struct Trinamic2130 final : Stepper { } }; + // helper to create functions that retrieve the object from the cfgArray[...].target + // and call the correct function of that target + template + static stat_t get_fn(nvObj_t *nv) { + return (reinterpret_cast(cfgArray[nv->index].target)->*T)(nv); + }; // NV interface helpers stat_t get_ts(nvObj_t *nv) { @@ -700,6 +712,7 @@ struct Trinamic2130 final : Stepper { nv->valuetype = TYPE_INT; return STAT_OK; }; + static stat_t get_ts_fn(nvObj_t *nv) { return get_fn<&type::get_ts>(nv); }; // no set stat_t get_pth(nvObj_t *nv) { @@ -707,6 +720,7 @@ struct Trinamic2130 final : Stepper { nv->valuetype = TYPE_INT; return STAT_OK; }; + static stat_t get_pth_fn(nvObj_t *nv) { return get_fn<&type::get_pth>(nv); }; stat_t set_pth(nvObj_t *nv) { int32_t v = nv->value; if (v < 0) { @@ -721,12 +735,14 @@ struct Trinamic2130 final : Stepper { TPWMTHRS_needs_written = true; return STAT_OK; }; + static stat_t set_pth_fn(nvObj_t *nv) { return get_fn<&type::set_pth>(nv); }; stat_t get_cth(nvObj_t *nv) { nv->value = TCOOLTHRS.value; nv->valuetype = TYPE_INT; return STAT_OK; }; + static stat_t get_cth_fn(nvObj_t *nv) { return get_fn<&type::get_cth>(nv); }; stat_t set_cth(nvObj_t *nv) { int32_t v = nv->value; if (v < 0) { @@ -741,12 +757,14 @@ struct Trinamic2130 final : Stepper { TCOOLTHRS_needs_written = true; return STAT_OK; }; + static stat_t set_cth_fn(nvObj_t *nv) { return get_fn<&type::set_cth>(nv); }; stat_t get_hth(nvObj_t *nv) { nv->value = THIGH.value; nv->valuetype = TYPE_INT; return STAT_OK; }; + static stat_t get_hth_fn(nvObj_t *nv) { return get_fn<&type::get_hth>(nv); }; stat_t set_hth(nvObj_t *nv) { int32_t v = nv->value; if (v < 0) { @@ -761,6 +779,7 @@ struct Trinamic2130 final : Stepper { THIGH_needs_written = true; return STAT_OK; }; + static stat_t set_hth_fn(nvObj_t *nv) { return get_fn<&type::set_hth>(nv); }; stat_t get_sgt(nvObj_t *nv) { int32_t v = COOLCONF.sgt; @@ -768,6 +787,7 @@ struct Trinamic2130 final : Stepper { nv->valuetype = TYPE_INT; return STAT_OK; }; + static stat_t get_sgt_fn(nvObj_t *nv) { return get_fn<&type::get_sgt>(nv); }; stat_t set_sgt(nvObj_t *nv) { int32_t v = nv->value; if (v < -64) { @@ -782,12 +802,14 @@ struct Trinamic2130 final : Stepper { COOLCONF_needs_written = true; return STAT_OK; }; + static stat_t set_sgt_fn(nvObj_t *nv) { return get_fn<&type::set_sgt>(nv); }; stat_t get_csa(nvObj_t *nv) { nv->value = DRV_STATUS.CS_ACTUAL; nv->valuetype = TYPE_INT; return STAT_OK; }; + static stat_t get_csa_fn(nvObj_t *nv) { return get_fn<&type::get_csa>(nv); }; // no set stat_t get_sgr(nvObj_t *nv) { @@ -795,6 +817,7 @@ struct Trinamic2130 final : Stepper { nv->valuetype = TYPE_INT; return STAT_OK; }; + static stat_t get_sgr_fn(nvObj_t *nv) { return get_fn<&type::get_sgr>(nv); }; // no set stat_t get_sgs(nvObj_t *nv) { @@ -802,6 +825,7 @@ struct Trinamic2130 final : Stepper { nv->valuetype = TYPE_BOOL; return STAT_OK; }; + static stat_t get_sgs_fn(nvObj_t *nv) { return get_fn<&type::get_sgs>(nv); }; // no set @@ -810,6 +834,7 @@ struct Trinamic2130 final : Stepper { nv->valuetype = TYPE_INT; return STAT_OK; }; + static stat_t get_tbl_fn(nvObj_t *nv) { return get_fn<&type::get_tbl>(nv); }; stat_t set_tbl(nvObj_t *nv) { int32_t v = nv->value; if (v < 0) { @@ -824,12 +849,14 @@ struct Trinamic2130 final : Stepper { CHOPCONF_needs_written = true; return STAT_OK; }; + static stat_t set_tbl_fn(nvObj_t *nv) { return get_fn<&type::set_tbl>(nv); }; stat_t get_pgrd(nvObj_t *nv) { nv->value = PWMCONF.PWM_GRAD; nv->valuetype = TYPE_INT; return STAT_OK; }; + static stat_t get_pgrd_fn(nvObj_t *nv) { return get_fn<&type::get_pgrd>(nv); }; stat_t set_pgrd(nvObj_t *nv) { int32_t v = nv->value; if (v < 0) { @@ -844,12 +871,14 @@ struct Trinamic2130 final : Stepper { PWMCONF_needs_written = true; return STAT_OK; }; + static stat_t set_pgrd_fn(nvObj_t *nv) { return get_fn<&type::set_pgrd>(nv); }; stat_t get_pamp(nvObj_t *nv) { nv->value = PWMCONF.PWM_AMPL; nv->valuetype = TYPE_INT; return STAT_OK; }; + static stat_t get_pamp_fn(nvObj_t *nv) { return get_fn<&type::get_pamp>(nv); }; stat_t set_pamp(nvObj_t *nv) { int32_t v = nv->value; if (v < 0) { @@ -864,12 +893,14 @@ struct Trinamic2130 final : Stepper { PWMCONF_needs_written = true; return STAT_OK; }; + static stat_t set_pamp_fn(nvObj_t *nv) { return get_fn<&type::set_pamp>(nv); }; stat_t get_hend(nvObj_t *nv) { nv->value = CHOPCONF.HEND_OFFSET; nv->valuetype = TYPE_INT; return STAT_OK; }; + static stat_t get_hend_fn(nvObj_t *nv) { return get_fn<&type::get_hend>(nv); }; stat_t set_hend(nvObj_t *nv) { int32_t v = nv->value; if (v < 0) { @@ -884,12 +915,14 @@ struct Trinamic2130 final : Stepper { CHOPCONF_needs_written = true; return STAT_OK; }; + static stat_t set_hend_fn(nvObj_t *nv) { return get_fn<&type::set_hend>(nv); }; stat_t get_hsrt(nvObj_t *nv) { nv->value = CHOPCONF.HSTRT_TFD012; nv->valuetype = TYPE_INT; return STAT_OK; }; + static stat_t get_hsrt_fn(nvObj_t *nv) { return get_fn<&type::get_hsrt>(nv); }; stat_t set_hsrt(nvObj_t *nv) { int32_t v = nv->value; if (v < 0) { @@ -904,12 +937,14 @@ struct Trinamic2130 final : Stepper { CHOPCONF_needs_written = true; return STAT_OK; }; + static stat_t set_hsrt_fn(nvObj_t *nv) { return get_fn<&type::set_hsrt>(nv); }; stat_t get_smin(nvObj_t *nv) { nv->value = COOLCONF.semin; nv->valuetype = TYPE_INT; return STAT_OK; }; + static stat_t get_smin_fn(nvObj_t *nv) { return get_fn<&type::get_smin>(nv); }; stat_t set_smin(nvObj_t *nv) { int32_t v = nv->value; if (v < 0) { @@ -924,12 +959,14 @@ struct Trinamic2130 final : Stepper { COOLCONF_needs_written = true; return STAT_OK; }; + static stat_t set_smin_fn(nvObj_t *nv) { return get_fn<&type::set_smin>(nv); }; stat_t get_smax(nvObj_t *nv) { nv->value = COOLCONF.semax; nv->valuetype = TYPE_INT; return STAT_OK; }; + static stat_t get_smax_fn(nvObj_t *nv) { return get_fn<&type::get_smax>(nv); }; stat_t set_smax(nvObj_t *nv) { int32_t v = nv->value; if (v < 0) { @@ -944,12 +981,14 @@ struct Trinamic2130 final : Stepper { COOLCONF_needs_written = true; return STAT_OK; }; + static stat_t set_smax_fn(nvObj_t *nv) { return get_fn<&type::set_smax>(nv); }; stat_t get_sup(nvObj_t *nv) { nv->value = COOLCONF.seup; nv->valuetype = TYPE_INT; return STAT_OK; }; + static stat_t get_sup_fn(nvObj_t *nv) { return get_fn<&type::get_sup>(nv); }; stat_t set_sup(nvObj_t *nv) { int32_t v = nv->value; if (v < 0) { @@ -964,12 +1003,14 @@ struct Trinamic2130 final : Stepper { COOLCONF_needs_written = true; return STAT_OK; }; + static stat_t set_sup_fn(nvObj_t *nv) { return get_fn<&type::set_sup>(nv); }; stat_t get_sdn(nvObj_t *nv) { nv->value = COOLCONF.sedn; nv->valuetype = TYPE_INT; return STAT_OK; }; + static stat_t get_sdn_fn(nvObj_t *nv) { return get_fn<&type::get_sdn>(nv); }; stat_t set_sdn(nvObj_t *nv) { int32_t v = nv->value; if (v < 0) { @@ -984,5 +1025,6 @@ struct Trinamic2130 final : Stepper { COOLCONF_needs_written = true; return STAT_OK; }; + static stat_t set_sdn_fn(nvObj_t *nv) { return get_fn<&type::set_sdn>(nv); }; }; From c9b4e4a91aa10c5324b7abd9696e310100b8bc49 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Fri, 1 Dec 2017 12:42:46 -0600 Subject: [PATCH 141/193] Added TMC2130 settings to settings_default.h --- Resources/generate_motors_default_config.js | 50 ++++ g2core/settings/settings_default.h | 243 ++++++++++++++++++++ 2 files changed, 293 insertions(+) create mode 100755 Resources/generate_motors_default_config.js diff --git a/Resources/generate_motors_default_config.js b/Resources/generate_motors_default_config.js new file mode 100755 index 000000000..2d98a45da --- /dev/null +++ b/Resources/generate_motors_default_config.js @@ -0,0 +1,50 @@ +#!/usr/bin/env node + +// Run this with no arguments, and get the motor code suitable for use in config_app.cpp + +console.log('// START Generated with ${PROJECT_ROOT}/Resources/generate_motors_default_config.js'); +for (n=1; n<=6; n++) { + console.log( +`#ifndef M${n}_TMC2130_TPWMTHRS + #define M${n}_TMC2130_TPWMTHRS 1200 // ${n}pth +#endif +#ifndef M${n}_TMC2130_TCOOLTHRS + #define M${n}_TMC2130_TCOOLTHRS 1000 // ${n}cth +#endif +#ifndef M${n}_TMC2130_THIGH + #define M${n}_TMC2130_THIGH 10 // ${n}hth +#endif +#ifndef M${n}_TMC2130_SGT + #define M${n}_TMC2130_SGT 4 // ${n}sgt +#endif +#ifndef M${n}_TMC2130_TBL + #define M${n}_TMC2130_TBL 2 // ${n}tbl +#endif +#ifndef M${n}_TMC2130_PWM_GRAD + #define M${n}_TMC2130_PWM_GRAD 1 // ${n}pgrd +#endif +#ifndef M${n}_TMC2130_PWM_AMPL + #define M${n}_TMC2130_PWM_AMPL 200 // ${n}pamp +#endif +#ifndef M${n}_TMC2130_HEND + #define M${n}_TMC2130_HEND 0 // ${n}hend +#endif +#ifndef M${n}_TMC2130_HSTRT + #define M${n}_TMC2130_HSTRT 0 // ${n}hsrt +#endif +#ifndef M${n}_TMC2130_SMIN + #define M${n}_TMC2130_SMIN 5 // ${n}smin +#endif +#ifndef M${n}_TMC2130_SMAX + #define M${n}_TMC2130_SMAX 5 // ${n}smax +#endif +#ifndef M${n}_TMC2130_SUP + #define M${n}_TMC2130_SUP 2 // ${n}sup +#endif +#ifndef M${n}_TMC2130_SDN + #define M${n}_TMC2130_SDN 1 // ${n}sdn +#endif +` +); +} +console.log('// END Generated'); diff --git a/g2core/settings/settings_default.h b/g2core/settings/settings_default.h index 1316d84af..86a8212d6 100644 --- a/g2core/settings/settings_default.h +++ b/g2core/settings/settings_default.h @@ -372,6 +372,249 @@ #define M6_POWER_LEVEL 0.0 #endif +// TMC2130 config defaults +// START Generated with ${PROJECT_ROOT}/Resources/generate_motors_default_config.js +#ifndef M1_TMC2130_TPWMTHRS +#define M1_TMC2130_TPWMTHRS 1200 // 1pth +#endif +#ifndef M1_TMC2130_TCOOLTHRS +#define M1_TMC2130_TCOOLTHRS 1000 // 1cth +#endif +#ifndef M1_TMC2130_THIGH +#define M1_TMC2130_THIGH 10 // 1hth +#endif +#ifndef M1_TMC2130_SGT +#define M1_TMC2130_SGT 4 // 1sgt +#endif +#ifndef M1_TMC2130_TBL +#define M1_TMC2130_TBL 2 // 1tbl +#endif +#ifndef M1_TMC2130_PWM_GRAD +#define M1_TMC2130_PWM_GRAD 1 // 1pgrd +#endif +#ifndef M1_TMC2130_PWM_AMPL +#define M1_TMC2130_PWM_AMPL 200 // 1pamp +#endif +#ifndef M1_TMC2130_HEND +#define M1_TMC2130_HEND 0 // 1hend +#endif +#ifndef M1_TMC2130_HSTRT +#define M1_TMC2130_HSTRT 0 // 1hsrt +#endif +#ifndef M1_TMC2130_SMIN +#define M1_TMC2130_SMIN 5 // 1smin +#endif +#ifndef M1_TMC2130_SMAX +#define M1_TMC2130_SMAX 5 // 1smax +#endif +#ifndef M1_TMC2130_SUP +#define M1_TMC2130_SUP 2 // 1sup +#endif +#ifndef M1_TMC2130_SDN +#define M1_TMC2130_SDN 1 // 1sdn +#endif + +#ifndef M2_TMC2130_TPWMTHRS +#define M2_TMC2130_TPWMTHRS 1200 // 2pth +#endif +#ifndef M2_TMC2130_TCOOLTHRS +#define M2_TMC2130_TCOOLTHRS 1000 // 2cth +#endif +#ifndef M2_TMC2130_THIGH +#define M2_TMC2130_THIGH 10 // 2hth +#endif +#ifndef M2_TMC2130_SGT +#define M2_TMC2130_SGT 4 // 2sgt +#endif +#ifndef M2_TMC2130_TBL +#define M2_TMC2130_TBL 2 // 2tbl +#endif +#ifndef M2_TMC2130_PWM_GRAD +#define M2_TMC2130_PWM_GRAD 1 // 2pgrd +#endif +#ifndef M2_TMC2130_PWM_AMPL +#define M2_TMC2130_PWM_AMPL 200 // 2pamp +#endif +#ifndef M2_TMC2130_HEND +#define M2_TMC2130_HEND 0 // 2hend +#endif +#ifndef M2_TMC2130_HSTRT +#define M2_TMC2130_HSTRT 0 // 2hsrt +#endif +#ifndef M2_TMC2130_SMIN +#define M2_TMC2130_SMIN 5 // 2smin +#endif +#ifndef M2_TMC2130_SMAX +#define M2_TMC2130_SMAX 5 // 2smax +#endif +#ifndef M2_TMC2130_SUP +#define M2_TMC2130_SUP 2 // 2sup +#endif +#ifndef M2_TMC2130_SDN +#define M2_TMC2130_SDN 1 // 2sdn +#endif + +#ifndef M3_TMC2130_TPWMTHRS +#define M3_TMC2130_TPWMTHRS 1200 // 3pth +#endif +#ifndef M3_TMC2130_TCOOLTHRS +#define M3_TMC2130_TCOOLTHRS 1000 // 3cth +#endif +#ifndef M3_TMC2130_THIGH +#define M3_TMC2130_THIGH 10 // 3hth +#endif +#ifndef M3_TMC2130_SGT +#define M3_TMC2130_SGT 4 // 3sgt +#endif +#ifndef M3_TMC2130_TBL +#define M3_TMC2130_TBL 2 // 3tbl +#endif +#ifndef M3_TMC2130_PWM_GRAD +#define M3_TMC2130_PWM_GRAD 1 // 3pgrd +#endif +#ifndef M3_TMC2130_PWM_AMPL +#define M3_TMC2130_PWM_AMPL 200 // 3pamp +#endif +#ifndef M3_TMC2130_HEND +#define M3_TMC2130_HEND 0 // 3hend +#endif +#ifndef M3_TMC2130_HSTRT +#define M3_TMC2130_HSTRT 0 // 3hsrt +#endif +#ifndef M3_TMC2130_SMIN +#define M3_TMC2130_SMIN 5 // 3smin +#endif +#ifndef M3_TMC2130_SMAX +#define M3_TMC2130_SMAX 5 // 3smax +#endif +#ifndef M3_TMC2130_SUP +#define M3_TMC2130_SUP 2 // 3sup +#endif +#ifndef M3_TMC2130_SDN +#define M3_TMC2130_SDN 1 // 3sdn +#endif + +#ifndef M4_TMC2130_TPWMTHRS +#define M4_TMC2130_TPWMTHRS 1200 // 4pth +#endif +#ifndef M4_TMC2130_TCOOLTHRS +#define M4_TMC2130_TCOOLTHRS 1000 // 4cth +#endif +#ifndef M4_TMC2130_THIGH +#define M4_TMC2130_THIGH 10 // 4hth +#endif +#ifndef M4_TMC2130_SGT +#define M4_TMC2130_SGT 4 // 4sgt +#endif +#ifndef M4_TMC2130_TBL +#define M4_TMC2130_TBL 2 // 4tbl +#endif +#ifndef M4_TMC2130_PWM_GRAD +#define M4_TMC2130_PWM_GRAD 1 // 4pgrd +#endif +#ifndef M4_TMC2130_PWM_AMPL +#define M4_TMC2130_PWM_AMPL 200 // 4pamp +#endif +#ifndef M4_TMC2130_HEND +#define M4_TMC2130_HEND 0 // 4hend +#endif +#ifndef M4_TMC2130_HSTRT +#define M4_TMC2130_HSTRT 0 // 4hsrt +#endif +#ifndef M4_TMC2130_SMIN +#define M4_TMC2130_SMIN 5 // 4smin +#endif +#ifndef M4_TMC2130_SMAX +#define M4_TMC2130_SMAX 5 // 4smax +#endif +#ifndef M4_TMC2130_SUP +#define M4_TMC2130_SUP 2 // 4sup +#endif +#ifndef M4_TMC2130_SDN +#define M4_TMC2130_SDN 1 // 4sdn +#endif + +#ifndef M5_TMC2130_TPWMTHRS +#define M5_TMC2130_TPWMTHRS 1200 // 5pth +#endif +#ifndef M5_TMC2130_TCOOLTHRS +#define M5_TMC2130_TCOOLTHRS 1000 // 5cth +#endif +#ifndef M5_TMC2130_THIGH +#define M5_TMC2130_THIGH 10 // 5hth +#endif +#ifndef M5_TMC2130_SGT +#define M5_TMC2130_SGT 4 // 5sgt +#endif +#ifndef M5_TMC2130_TBL +#define M5_TMC2130_TBL 2 // 5tbl +#endif +#ifndef M5_TMC2130_PWM_GRAD +#define M5_TMC2130_PWM_GRAD 1 // 5pgrd +#endif +#ifndef M5_TMC2130_PWM_AMPL +#define M5_TMC2130_PWM_AMPL 200 // 5pamp +#endif +#ifndef M5_TMC2130_HEND +#define M5_TMC2130_HEND 0 // 5hend +#endif +#ifndef M5_TMC2130_HSTRT +#define M5_TMC2130_HSTRT 0 // 5hsrt +#endif +#ifndef M5_TMC2130_SMIN +#define M5_TMC2130_SMIN 5 // 5smin +#endif +#ifndef M5_TMC2130_SMAX +#define M5_TMC2130_SMAX 5 // 5smax +#endif +#ifndef M5_TMC2130_SUP +#define M5_TMC2130_SUP 2 // 5sup +#endif +#ifndef M5_TMC2130_SDN +#define M5_TMC2130_SDN 1 // 5sdn +#endif + +#ifndef M6_TMC2130_TPWMTHRS +#define M6_TMC2130_TPWMTHRS 1200 // 6pth +#endif +#ifndef M6_TMC2130_TCOOLTHRS +#define M6_TMC2130_TCOOLTHRS 1000 // 6cth +#endif +#ifndef M6_TMC2130_THIGH +#define M6_TMC2130_THIGH 10 // 6hth +#endif +#ifndef M6_TMC2130_SGT +#define M6_TMC2130_SGT 4 // 6sgt +#endif +#ifndef M6_TMC2130_TBL +#define M6_TMC2130_TBL 2 // 6tbl +#endif +#ifndef M6_TMC2130_PWM_GRAD +#define M6_TMC2130_PWM_GRAD 1 // 6pgrd +#endif +#ifndef M6_TMC2130_PWM_AMPL +#define M6_TMC2130_PWM_AMPL 200 // 6pamp +#endif +#ifndef M6_TMC2130_HEND +#define M6_TMC2130_HEND 0 // 6hend +#endif +#ifndef M6_TMC2130_HSTRT +#define M6_TMC2130_HSTRT 0 // 6hsrt +#endif +#ifndef M6_TMC2130_SMIN +#define M6_TMC2130_SMIN 5 // 6smin +#endif +#ifndef M6_TMC2130_SMAX +#define M6_TMC2130_SMAX 5 // 6smax +#endif +#ifndef M6_TMC2130_SUP +#define M6_TMC2130_SUP 2 // 6sup +#endif +#ifndef M6_TMC2130_SDN +#define M6_TMC2130_SDN 1 // 6sdn +#endif +// END Generated + //***************************************************************************** //*** Axis Settings *********************************************************** //***************************************************************************** From e6b41a3f12aa8a9b3623e54a0ac8f430ff8309b7 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Fri, 1 Dec 2017 16:39:07 -0600 Subject: [PATCH 142/193] First pass at spring-compensation --- g2core/canonical_machine.cpp | 27 +++++++++++ g2core/canonical_machine.h | 10 +++++ g2core/plan_exec.cpp | 50 ++++++++++++++++++++- g2core/plan_line.cpp | 1 + g2core/planner.h | 3 ++ g2core/settings/settings_Ultimaker_2_Plus.h | 25 ++++++----- 6 files changed, 105 insertions(+), 11 deletions(-) diff --git a/g2core/canonical_machine.cpp b/g2core/canonical_machine.cpp index 63a783905..a5fbb6717 100644 --- a/g2core/canonical_machine.cpp +++ b/g2core/canonical_machine.cpp @@ -2665,6 +2665,26 @@ stat_t cm_set_mto(nvObj_t *nv) return(STAT_OK); } +/* + * cm_get_so() - get spring factor offset + * + */ + +stat_t cm_get_so(nvObj_t *nv) +{ + if (cm_get_motion_state() == MOTION_STOP) { + nv->value = 0; + } else { + nv->value = mp_get_runtime_spring_value(_get_axis(nv->index)); + if (cm_get_units_mode(RUNTIME) == INCHES) { + nv->value *= INCHES_PER_MM; + } + } + nv->precision = GET_TABLE_WORD(precision); + nv->valuetype = TYPE_FLOAT; + return (STAT_OK); +} + /* * Commands * @@ -2880,6 +2900,9 @@ static const char fmt_Xtn[] = "[%s%s] %s travel minimum%17.3f%s\n"; static const char fmt_Xjm[] = "[%s%s] %s jerk maximum%15.0f%s/min^3 * 1 million\n"; static const char fmt_Xjh[] = "[%s%s] %s jerk homing%16.0f%s/min^3 * 1 million\n"; static const char fmt_Xra[] = "[%s%s] %s radius value%20.4f%s\n"; +static const char fmt_Xsf[] = "[%s%s] %s spring offset factor%20.4f%s\n"; +static const char fmt_Xsm[] = "[%s%s] %s spring offset max%20.4f%s\n"; +static const char fmt_Xso[] = "[%s%s] %s spring offset%20.4f%s\n"; static const char fmt_Xhi[] = "[%s%s] %s homing input%15d [input 1-N or 0 to disable homing this axis]\n"; static const char fmt_Xhd[] = "[%s%s] %s homing direction%11d [0=search-to-negative, 1=search-to-positive]\n"; static const char fmt_Xsv[] = "[%s%s] %s search velocity%12.0f%s/min\n"; @@ -2957,6 +2980,10 @@ void cm_print_jm(nvObj_t *nv) { _print_axis_flt(nv, fmt_Xjm);} void cm_print_jh(nvObj_t *nv) { _print_axis_flt(nv, fmt_Xjh);} void cm_print_ra(nvObj_t *nv) { _print_axis_flt(nv, fmt_Xra);} +void cm_print_sf(nvObj_t *nv) { _print_axis_flt(nv, fmt_Xsf);} +void cm_print_sm(nvObj_t *nv) { _print_axis_flt(nv, fmt_Xsm);} +void cm_print_so(nvObj_t *nv) { _print_axis_flt(nv, fmt_Xso);} + void cm_print_hi(nvObj_t *nv) { _print_axis_ui8(nv, fmt_Xhi);} void cm_print_hd(nvObj_t *nv) { _print_axis_ui8(nv, fmt_Xhd);} void cm_print_sv(nvObj_t *nv) { _print_axis_flt(nv, fmt_Xsv);} diff --git a/g2core/canonical_machine.h b/g2core/canonical_machine.h index ab825b4ff..e4768cff1 100644 --- a/g2core/canonical_machine.h +++ b/g2core/canonical_machine.h @@ -384,6 +384,10 @@ typedef struct cmAxis { float latch_velocity; // homing latch velocity float latch_backoff; // backoff sufficient to clear a switch float zero_backoff; // backoff from switches for machine zero + + float spring_offset_factor; // factor of feed offset (sof * velocity = spring_offset) + float spring_retraction_factor; // factor of the x/y velocity to reverse the axis during non-movement + float spring_offset_max; // max amount of spring offset compensation allowed } cfgAxis_t; typedef struct cmSingleton { // struct to manage cm globals and cycles @@ -704,6 +708,8 @@ stat_t cm_set_jh(nvObj_t *nv); // set jerk high with 1,000,000 correcti stat_t cm_set_mfo(nvObj_t *nv); // set manual feedrate override factor stat_t cm_set_mto(nvObj_t *nv); // set manual traverse override factor +stat_t cm_get_so(nvObj_t *nv); // get spring factor offset + stat_t cm_set_probe(nvObj_t *nv); // store current position as the latest probe @@ -774,6 +780,10 @@ stat_t cm_get_nxln(nvObj_t *nv); // return what value we expect the next line void cm_print_jh(nvObj_t *nv); void cm_print_ra(nvObj_t *nv); + void cm_print_sf(nvObj_t *nv); + void cm_print_sm(nvObj_t *nv); + void cm_print_so(nvObj_t *nv); + void cm_print_hi(nvObj_t *nv); void cm_print_hd(nvObj_t *nv); void cm_print_sv(nvObj_t *nv); diff --git a/g2core/plan_exec.cpp b/g2core/plan_exec.cpp index ed891e463..2768fdf30 100644 --- a/g2core/plan_exec.cpp +++ b/g2core/plan_exec.cpp @@ -1073,12 +1073,55 @@ static stat_t _exec_aline_tail(mpBuf_t *bf) static stat_t _exec_aline_segment() { float travel_steps[MOTORS]; + // we don't want to keep the adjusted target in the recorded position, so we'll adjust after + float adjusted_target[AXES]; + + for (uint8_t a=0; a -cm.a[a].spring_retraction_factor) { + // retract backward as fast as allowed, up to -cm.a[a].spring_retraction_factor + new_spring_offset = mr.spring_offset[a]-(mr.segment_time * cm.a[a].velocity_max); + if (new_spring_offset <= -cm.a[a].spring_retraction_factor) { + new_spring_offset = -cm.a[a].spring_retraction_factor; + mr.spring_retraction_backward[a] = false; + } + } else { + // undo retract at half velocity + new_spring_offset = std::max(0.0, mr.spring_offset[a] + (mr.segment_time * cm.a[a].velocity_max)/2.0); + mr.spring_retraction_backward[a] = false; + } + } else { + new_spring_offset = std::min( + (double)cm.a[a].spring_offset_factor * axis_velocity, // new actual offset + (double)mr.spring_offset[a]+((mr.segment_time * cm.a[a].velocity_max)-(mr.unit[a] * (mr.segment_velocity+mr.target_velocity) * 0.5 * mr.segment_time)) // offset at max speed + ); + mr.spring_retraction_backward[a] = true; // next zero-velocity move should be a retraction + } + new_spring_offset = std::max(-cm.a[a].spring_offset_max, std::min(cm.a[a].spring_offset_max, new_spring_offset)); + mr.spring_offset[a] = new_spring_offset; + } else +#endif + { + mr.spring_offset[a] = 0; + } + } + // Set target position for the segment // If the segment ends on a section waypoint synchronize to the head, body or tail end // Otherwise if not at a section waypoint compute target from segment time and velocity // Don't do waypoint correction if you are going into a hold. + // See https://en.wikipedia.org/wiki/Kahan_summation_algorithm + // for the description of the summation compensation used. + if ((--mr.segment_count == 0) && (cm.motion_state != MOTION_HOLD)) { copy_vector(mr.gm.target, mr.waypoint[mr.section]); } else { @@ -1099,6 +1142,11 @@ static stat_t _exec_aline_segment() mr.gm.target[a] = target; } } + copy_vector(adjusted_target, mr.gm.target); + { + uint8_t a = AXIS_A; + adjusted_target[a] += mr.spring_offset[a]; + } // Convert target position to steps // Bucket-brigade the old target down the chain before getting the new target from kinematics @@ -1113,7 +1161,7 @@ static stat_t _exec_aline_segment() mr.encoder_steps[m] = en_read_encoder(m); // get current encoder position (time aligns to commanded_steps) mr.following_error[m] = mr.encoder_steps[m] - mr.commanded_steps[m]; } - kn_inverse_kinematics(mr.gm.target, mr.target_steps); // now determine the target steps... + kn_inverse_kinematics(adjusted_target, mr.target_steps); // now determine the target steps... for (uint8_t m=0; m Date: Fri, 1 Dec 2017 21:25:42 -0600 Subject: [PATCH 143/193] Fix issue where setting `{prbr:t}` (or any value) wasn't working. --- g2core/config_app.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/g2core/config_app.cpp b/g2core/config_app.cpp index d0e54e265..0f570f07a 100644 --- a/g2core/config_app.cpp +++ b/g2core/config_app.cpp @@ -173,7 +173,7 @@ const cfgItem_t cfgArray[] = { { "prb","prbb",_f0, 3, tx_print_nul, get_flt, set_ro, (float *)&cm.probe_results[0][AXIS_B], 0 }, { "prb","prbc",_f0, 3, tx_print_nul, get_flt, set_ro, (float *)&cm.probe_results[0][AXIS_C], 0 }, { "prb","prbs",_f0, 0, tx_print_nul, get_nul, cm_set_probe, (float *)&cs.null, 0 }, // store probe - { "prb","prbr",_f0, 0, tx_print_nul, cm_get_prbr, cm_get_prbr, nullptr, 0 }, // enable probe report. Init in cm_init + { "prb","prbr",_f0, 0, tx_print_nul, cm_get_prbr, cm_set_prbr, nullptr, 0 }, // enable probe report. Init in cm_init { "jog","jogx",_f0, 0, tx_print_nul, get_nul, cm_run_jogx, (float *)&cm.jogging_dest, 0}, { "jog","jogy",_f0, 0, tx_print_nul, get_nul, cm_run_jogy, (float *)&cm.jogging_dest, 0}, From 93a0bb1d3e4a6dc1435e9a18bf1a7b6c6f5ecca0 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Sat, 2 Dec 2017 07:55:46 -0600 Subject: [PATCH 144/193] Removing testing code. --- g2core/config_app.cpp | 4 ---- 1 file changed, 4 deletions(-) diff --git a/g2core/config_app.cpp b/g2core/config_app.cpp index 0f570f07a..99260e1a5 100644 --- a/g2core/config_app.cpp +++ b/g2core/config_app.cpp @@ -442,10 +442,6 @@ const cfgItem_t cfgArray[] = { { "a","ajm",_fip, 0, cm_print_jm, get_flt, cm_set_jm, (float *)&cm.a[AXIS_A].jerk_max, A_JERK_MAX }, { "a","ajh",_fip, 0, cm_print_jh, get_flt, cm_set_jh, (float *)&cm.a[AXIS_A].jerk_high, A_JERK_HIGH_SPEED }, { "a","ara",_fipc, 3, cm_print_ra, get_flt, set_flt, (float *)&cm.a[AXIS_A].radius, A_RADIUS}, - { "a","asf",_fipc, 3, cm_print_sf, get_flt, set_flt, (float *)&cm.a[AXIS_A].spring_offset_factor, A_SPRING_OFFSET_FACTOR}, - { "a","asm",_fipc, 3, cm_print_sm, get_flt, set_flt, (float *)&cm.a[AXIS_A].spring_offset_max, A_SPRING_OFFSET_MAX}, - { "a","arf",_fipc, 3, cm_print_sf, get_flt, set_flt, (float *)&cm.a[AXIS_A].spring_retraction_factor,A_SPRING_RETRACTION_FACTOR}, - { "a","aso", _f0, 3, cm_print_so, cm_get_so, set_ro, (float *)&cs.null, 0 }, { "a","ahi",_fip, 0, cm_print_hi, get_ui8, cm_set_hi, (float *)&cm.a[AXIS_A].homing_input, A_HOMING_INPUT }, { "a","ahd",_fip, 0, cm_print_hd, get_ui8, set_01, (float *)&cm.a[AXIS_A].homing_dir, A_HOMING_DIRECTION }, { "a","asv",_fip, 0, cm_print_sv, get_flt, set_fltp, (float *)&cm.a[AXIS_A].search_velocity,A_SEARCH_VELOCITY }, From a0ad3a5c7c500aa2755a28f379b5e5d98d8760cd Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Sat, 2 Dec 2017 08:10:19 -0600 Subject: [PATCH 145/193] Remove old constant-rate stepper and related forward difference code. --- g2core/plan_exec.cpp | 68 ----------------- g2core/planner.h | 2 - g2core/stepper.cpp | 170 ------------------------------------------- g2core/stepper.h | 18 ----- 4 files changed, 258 deletions(-) diff --git a/g2core/plan_exec.cpp b/g2core/plan_exec.cpp index ed891e463..17a46785f 100644 --- a/g2core/plan_exec.cpp +++ b/g2core/plan_exec.cpp @@ -839,40 +839,6 @@ static void _init_forward_diffs(const float v_0, const float v_1) const float Bh_4 = B * h_4; const float Ch_3 = C * h_3; -#if !defined(NEW_FWD_DIFF) || (NEW_FWD_DIFF==0) - const float const1 = 7.5625; // (121.0/16.0) - const float const2 = 3.25; // ( 13.0/ 4.0) - const float const3 = 82.5; // (165.0/ 2.0) - - /* - * F_5 = (121/16)A h^5 + 5 B h^4 + (13/4) C h^3 + 2 D h^2 + Eh - * F_4 = (165/2)A h^5 + 29 B h^4 + 9 C h^3 + 2 D h^2 - * F_3 = 255 A h^5 + 48 B h^4 + 6 C h^3 - * F_2 = 300 A h^5 + 24 B h^4 - * F_1 = 120 A h^5 - */ - - mr.forward_diff_5 = const1*Ah_5 + 5.0*Bh_4 + const2*Ch_3; - mr.forward_diff_4 = const3*Ah_5 + 29.0*Bh_4 + 9.0*Ch_3; - mr.forward_diff_3 = 255.0*Ah_5 + 48.0*Bh_4 + 6.0*Ch_3; - mr.forward_diff_2 = 300.0*Ah_5 + 24.0*Bh_4; - mr.forward_diff_1 = 120.0*Ah_5; - - // Calculate the initial velocity by calculating V(h/2) - const float half_h = h * 0.5; // h/2 - const float half_h_3 = half_h * half_h * half_h; - const float half_h_4 = half_h_3 * half_h; - const float half_h_5 = half_h_4 * half_h; - - const float half_Ch_3 = C * half_h_3; - const float half_Bh_4 = B * half_h_4; - const float half_Ah_5 = A * half_h_5; - - mr.segment_velocity = half_Ah_5 + half_Bh_4 + half_Ch_3 + v_0; - -#else - // NEW_FWD_DIFF == 1 - /* * F_5 = A h^5 + B h^4 + C h^3 + D h^2 + E h * F_4 = 30 A h^5 + 14 B h^4 + 6 C h^3 + 2 D h^2 @@ -889,8 +855,6 @@ static void _init_forward_diffs(const float v_0, const float v_1) mr.segment_velocity = v_0; mr.target_velocity = v_0 + mr.forward_diff_5; -#endif - } /********************************************************************************************* @@ -901,9 +865,6 @@ static stat_t _exec_aline_head(mpBuf_t *bf) { bool first_pass = false; if (mr.section_state == SECTION_NEW) { // INITIALIZATION -#if !defined(NEW_FWD_DIFF) || (NEW_FWD_DIFF==0) - first_pass = true; -#endif if (fp_ZERO(mr.r->head_length)) { mr.section = SECTION_BODY; return(_exec_aline_body(bf)); // skip ahead to the body generator @@ -914,13 +875,8 @@ static stat_t _exec_aline_head(mpBuf_t *bf) if (mr.segment_count == 1) { // We will only have one segment, simply average the velocities -#if !defined(NEW_FWD_DIFF) || (NEW_FWD_DIFF==0) - mr.segment_velocity = mr.r->head_length / mr.segment_time; -#else mr.segment_velocity = mr.entry_velocity; mr.target_velocity = mr.r->cruise_velocity; -#endif - } else { _init_forward_diffs(mr.entry_velocity, mr.r->cruise_velocity); // <-- sets inital segment_velocity } @@ -931,12 +887,8 @@ static stat_t _exec_aline_head(mpBuf_t *bf) mr.section = SECTION_HEAD; mr.section_state = SECTION_RUNNING; } else { -#if !defined(NEW_FWD_DIFF) || (NEW_FWD_DIFF==0) - mr.segment_velocity += mr.forward_diff_5; -#else mr.segment_velocity = mr.target_velocity; mr.target_velocity += mr.forward_diff_5; -#endif } if (_exec_aline_segment() == STAT_OK) { // set up for second half @@ -1001,10 +953,6 @@ static stat_t _exec_aline_tail(mpBuf_t *bf) { bool first_pass = false; if (mr.section_state == SECTION_NEW) { // INITIALIZATION -#if !defined(NEW_FWD_DIFF) || (NEW_FWD_DIFF==0) - first_pass = true; -#endif - // Mark the block as unplannable bf->plannable = false; @@ -1014,12 +962,8 @@ static stat_t _exec_aline_tail(mpBuf_t *bf) mr.segment_time = mr.r->tail_time / mr.segments; // time to advance for each segment if (mr.segment_count == 1) { -#if !defined(NEW_FWD_DIFF) || (NEW_FWD_DIFF==0) - mr.segment_velocity = mr.r->tail_length / mr.segment_time; -#else mr.segment_velocity = mr.r->cruise_velocity; mr.target_velocity = mr.r->exit_velocity; -#endif } else { _init_forward_diffs(mr.r->cruise_velocity, mr.r->exit_velocity); // <-- sets inital segment_velocity } @@ -1031,12 +975,8 @@ static stat_t _exec_aline_tail(mpBuf_t *bf) mr.section = SECTION_TAIL; mr.section_state = SECTION_RUNNING; } else { -#if !defined(NEW_FWD_DIFF) || (NEW_FWD_DIFF==0) - mr.segment_velocity += mr.forward_diff_5; -#else mr.segment_velocity = mr.target_velocity; mr.target_velocity += mr.forward_diff_5; -#endif } if (_exec_aline_segment() == STAT_OK) { @@ -1082,11 +1022,7 @@ static stat_t _exec_aline_segment() if ((--mr.segment_count == 0) && (cm.motion_state != MOTION_HOLD)) { copy_vector(mr.gm.target, mr.waypoint[mr.section]); } else { -#if !defined(NEW_FWD_DIFF) || (NEW_FWD_DIFF==0) - float segment_length = mr.segment_velocity * mr.segment_time; -#else float segment_length = (mr.segment_velocity+mr.target_velocity) * 0.5 * mr.segment_time; -#endif // see https://en.wikipedia.org/wiki/Kahan_summation_algorithm // for the summation compensation description for (uint8_t a=0; a 0) { motor_1.stepStart(); // turn step bit on -#if NEW_DDA == 1 st_run.mot[MOTOR_1].substep_accumulator -= DDA_SUBSTEPS; //st_run.dda_ticks_X_substeps; -#else - st_run.mot[MOTOR_1].substep_accumulator -= st_run.dda_ticks_X_substeps; -#endif INCREMENT_ENCODER(MOTOR_1); } -#if defined(NEW_FWD_DIFF) && (NEW_FWD_DIFF==1) st_run.mot[MOTOR_1].substep_increment += st_run.mot[MOTOR_1].substep_increment_increment; -#endif if ((st_run.mot[MOTOR_2].substep_accumulator += st_run.mot[MOTOR_2].substep_increment) > 0) { motor_2.stepStart(); // turn step bit on -#if NEW_DDA == 1 st_run.mot[MOTOR_2].substep_accumulator -= DDA_SUBSTEPS; //st_run.dda_ticks_X_substeps; -#else - st_run.mot[MOTOR_2].substep_accumulator -= st_run.dda_ticks_X_substeps; -#endif INCREMENT_ENCODER(MOTOR_2); } -#if defined(NEW_FWD_DIFF) && (NEW_FWD_DIFF==1) st_run.mot[MOTOR_2].substep_increment += st_run.mot[MOTOR_2].substep_increment_increment; -#endif #if MOTORS > 2 if ((st_run.mot[MOTOR_3].substep_accumulator += st_run.mot[MOTOR_3].substep_increment) > 0) { motor_3.stepStart(); // turn step bit on -#if NEW_DDA == 1 st_run.mot[MOTOR_3].substep_accumulator -= DDA_SUBSTEPS; //st_run.dda_ticks_X_substeps; -#else - st_run.mot[MOTOR_3].substep_accumulator -= st_run.dda_ticks_X_substeps; -#endif INCREMENT_ENCODER(MOTOR_3); } -#if defined(NEW_FWD_DIFF) && (NEW_FWD_DIFF==1) st_run.mot[MOTOR_3].substep_increment += st_run.mot[MOTOR_3].substep_increment_increment; #endif -#endif #if MOTORS > 3 if ((st_run.mot[MOTOR_4].substep_accumulator += st_run.mot[MOTOR_4].substep_increment) > 0) { motor_4.stepStart(); // turn step bit on -#if NEW_DDA == 1 st_run.mot[MOTOR_4].substep_accumulator -= DDA_SUBSTEPS; //st_run.dda_ticks_X_substeps; -#else - st_run.mot[MOTOR_4].substep_accumulator -= st_run.dda_ticks_X_substeps; -#endif INCREMENT_ENCODER(MOTOR_4); } -#if defined(NEW_FWD_DIFF) && (NEW_FWD_DIFF==1) st_run.mot[MOTOR_4].substep_increment += st_run.mot[MOTOR_4].substep_increment_increment; #endif -#endif #if MOTORS > 4 if ((st_run.mot[MOTOR_5].substep_accumulator += st_run.mot[MOTOR_5].substep_increment) > 0) { motor_5.stepStart(); // turn step bit on -#if NEW_DDA == 1 st_run.mot[MOTOR_5].substep_accumulator -= DDA_SUBSTEPS; //st_run.dda_ticks_X_substeps; -#else - st_run.mot[MOTOR_5].substep_accumulator -= st_run.dda_ticks_X_substeps; -#endif INCREMENT_ENCODER(MOTOR_5); -#if defined(NEW_FWD_DIFF) && (NEW_FWD_DIFF==1) st_run.mot[MOTOR_5].substep_increment += st_run.mot[MOTOR_5].substep_increment_increment; -#endif } #endif #if MOTORS > 5 if ((st_run.mot[MOTOR_6].substep_accumulator += st_run.mot[MOTOR_6].substep_increment) > 0) { motor_6.stepStart(); // turn step bit on -#if NEW_DDA == 1 st_run.mot[MOTOR_6].substep_accumulator -= DDA_SUBSTEPS; //st_run.dda_ticks_X_substeps; -#else - st_run.mot[MOTOR_6].substep_accumulator -= st_run.dda_ticks_X_substeps; -#endif INCREMENT_ENCODER(MOTOR_6); } -#if defined(NEW_FWD_DIFF) && (NEW_FWD_DIFF==1) st_run.mot[MOTOR_6].substep_increment += st_run.mot[MOTOR_6].substep_increment_increment; -#endif #endif // Process end of segment. @@ -533,10 +497,6 @@ static void _load_move() //**** setup the new segment **** // st_run.dda_ticks_downcount is setup right before turning on the interrupt, since we don't turn it off -#if NEW_DDA == 1 -#else - st_run.dda_ticks_X_substeps = st_pre.dda_ticks_X_substeps; -#endif // INLINED VERSION: 4.3us //**** MOTOR_1 LOAD **** @@ -550,16 +510,7 @@ static void _load_move() // segments it may have been inactive in between. // Apply accumulator correction if the time base has changed since previous segment -#if NEW_DDA == 1 -#if defined(NEW_FWD_DIFF) && (NEW_FWD_DIFF==1) st_run.mot[MOTOR_1].substep_increment_increment = st_pre.mot[MOTOR_1].substep_increment_increment; -#endif -#else - if (st_pre.mot[MOTOR_1].accumulator_correction_flag == true) { - st_pre.mot[MOTOR_1].accumulator_correction_flag = false; - st_run.mot[MOTOR_1].substep_accumulator *= st_pre.mot[MOTOR_1].accumulator_correction; - } -#endif // Detect direction change and if so: // Set the direction bit in hardware. @@ -567,11 +518,7 @@ static void _load_move() if (st_pre.mot[MOTOR_1].direction != st_pre.mot[MOTOR_1].prev_direction) { st_pre.mot[MOTOR_1].prev_direction = st_pre.mot[MOTOR_1].direction; -#if NEW_DDA == 1 st_run.mot[MOTOR_1].substep_accumulator = -(DDA_SUBSTEPS + st_run.mot[MOTOR_1].substep_accumulator); // invert the accumulator for the direction change -#else - st_run.mot[MOTOR_1].substep_accumulator = -(st_run.dda_ticks_X_substeps + st_run.mot[MOTOR_1].substep_accumulator); -#endif motor_1.setDirection(st_pre.mot[MOTOR_1].direction); } @@ -580,9 +527,7 @@ static void _load_move() SET_ENCODER_STEP_SIGN(MOTOR_1, st_pre.mot[MOTOR_1].step_sign); } else { // Motor has 0 steps; might need to energize motor for power mode processing -#if defined(NEW_FWD_DIFF) && (NEW_FWD_DIFF==1) st_run.mot[MOTOR_1].substep_increment_increment = 0; -#endif motor_1.motionStopped(); } // accumulate counted steps to the step position and zero out counted steps for the segment currently being loaded @@ -590,155 +535,80 @@ static void _load_move() #if (MOTORS >= 2) if ((st_run.mot[MOTOR_2].substep_increment = st_pre.mot[MOTOR_2].substep_increment) != 0) { -#if NEW_DDA == 1 -#if defined(NEW_FWD_DIFF) && (NEW_FWD_DIFF==1) st_run.mot[MOTOR_2].substep_increment_increment = st_pre.mot[MOTOR_2].substep_increment_increment; -#endif -#else - if (st_pre.mot[MOTOR_2].accumulator_correction_flag == true) { - st_pre.mot[MOTOR_2].accumulator_correction_flag = false; - st_run.mot[MOTOR_2].substep_accumulator *= st_pre.mot[MOTOR_2].accumulator_correction; - } -#endif if (st_pre.mot[MOTOR_2].direction != st_pre.mot[MOTOR_2].prev_direction) { st_pre.mot[MOTOR_2].prev_direction = st_pre.mot[MOTOR_2].direction; -#if NEW_DDA == 1 st_run.mot[MOTOR_2].substep_accumulator = -(DDA_SUBSTEPS + st_run.mot[MOTOR_2].substep_accumulator); // invert the accumulator for the direction change -#else - st_run.mot[MOTOR_2].substep_accumulator = -(st_run.dda_ticks_X_substeps + st_run.mot[MOTOR_2].substep_accumulator); -#endif motor_2.setDirection(st_pre.mot[MOTOR_2].direction); } motor_2.enable(); SET_ENCODER_STEP_SIGN(MOTOR_2, st_pre.mot[MOTOR_2].step_sign); } else { -#if defined(NEW_FWD_DIFF) && (NEW_FWD_DIFF==1) st_run.mot[MOTOR_2].substep_increment_increment = 0; -#endif motor_2.motionStopped(); } ACCUMULATE_ENCODER(MOTOR_2); #endif #if (MOTORS >= 3) if ((st_run.mot[MOTOR_3].substep_increment = st_pre.mot[MOTOR_3].substep_increment) != 0) { -#if NEW_DDA == 1 -#if defined(NEW_FWD_DIFF) && (NEW_FWD_DIFF==1) st_run.mot[MOTOR_3].substep_increment_increment = st_pre.mot[MOTOR_3].substep_increment_increment; -#endif -#else - if (st_pre.mot[MOTOR_3].accumulator_correction_flag == true) { - st_pre.mot[MOTOR_3].accumulator_correction_flag = false; - st_run.mot[MOTOR_3].substep_accumulator *= st_pre.mot[MOTOR_3].accumulator_correction; - } -#endif if (st_pre.mot[MOTOR_3].direction != st_pre.mot[MOTOR_3].prev_direction) { st_pre.mot[MOTOR_3].prev_direction = st_pre.mot[MOTOR_3].direction; -#if NEW_DDA == 1 st_run.mot[MOTOR_3].substep_accumulator = -(DDA_SUBSTEPS + st_run.mot[MOTOR_3].substep_accumulator); // invert the accumulator for the direction change -#else - st_run.mot[MOTOR_3].substep_accumulator = -(st_run.dda_ticks_X_substeps + st_run.mot[MOTOR_3].substep_accumulator); -#endif motor_3.setDirection(st_pre.mot[MOTOR_3].direction); } motor_3.enable(); SET_ENCODER_STEP_SIGN(MOTOR_3, st_pre.mot[MOTOR_3].step_sign); } else { -#if defined(NEW_FWD_DIFF) && (NEW_FWD_DIFF==1) st_run.mot[MOTOR_3].substep_increment_increment = 0; -#endif motor_3.motionStopped(); } ACCUMULATE_ENCODER(MOTOR_3); #endif #if (MOTORS >= 4) if ((st_run.mot[MOTOR_4].substep_increment = st_pre.mot[MOTOR_4].substep_increment) != 0) { -#if NEW_DDA == 1 -#if defined(NEW_FWD_DIFF) && (NEW_FWD_DIFF==1) st_run.mot[MOTOR_4].substep_increment_increment = st_pre.mot[MOTOR_4].substep_increment_increment; -#endif -#else - if (st_pre.mot[MOTOR_4].accumulator_correction_flag == true) { - st_pre.mot[MOTOR_4].accumulator_correction_flag = false; - st_run.mot[MOTOR_4].substep_accumulator *= st_pre.mot[MOTOR_4].accumulator_correction; - } -#endif if (st_pre.mot[MOTOR_4].direction != st_pre.mot[MOTOR_4].prev_direction) { st_pre.mot[MOTOR_4].prev_direction = st_pre.mot[MOTOR_4].direction; -#if NEW_DDA == 1 st_run.mot[MOTOR_4].substep_accumulator = -(DDA_SUBSTEPS + st_run.mot[MOTOR_4].substep_accumulator); // invert the accumulator for the direction change -#else - st_run.mot[MOTOR_4].substep_accumulator = -(st_run.dda_ticks_X_substeps + st_run.mot[MOTOR_4].substep_accumulator); -#endif motor_4.setDirection(st_pre.mot[MOTOR_4].direction); } motor_4.enable(); SET_ENCODER_STEP_SIGN(MOTOR_4, st_pre.mot[MOTOR_4].step_sign); } else { -#if defined(NEW_FWD_DIFF) && (NEW_FWD_DIFF==1) st_run.mot[MOTOR_4].substep_increment_increment = 0; -#endif motor_4.motionStopped(); } ACCUMULATE_ENCODER(MOTOR_4); #endif #if (MOTORS >= 5) if ((st_run.mot[MOTOR_5].substep_increment = st_pre.mot[MOTOR_5].substep_increment) != 0) { -#if NEW_DDA == 1 -#if defined(NEW_FWD_DIFF) && (NEW_FWD_DIFF==1) st_run.mot[MOTOR_5].substep_increment_increment = st_pre.mot[MOTOR_5].substep_increment_increment; -#endif -#else - if (st_pre.mot[MOTOR_5].accumulator_correction_flag == true) { - st_pre.mot[MOTOR_5].accumulator_correction_flag = false; - st_run.mot[MOTOR_5].substep_accumulator *= st_pre.mot[MOTOR_5].accumulator_correction; - } -#endif if (st_pre.mot[MOTOR_5].direction != st_pre.mot[MOTOR_5].prev_direction) { st_pre.mot[MOTOR_5].prev_direction = st_pre.mot[MOTOR_5].direction; -#if NEW_DDA == 1 st_run.mot[MOTOR_5].substep_accumulator = -(DDA_SUBSTEPS + st_run.mot[MOTOR_5].substep_accumulator); // invert the accumulator for the direction change -#else - st_run.mot[MOTOR_5].substep_accumulator = -(st_run.dda_ticks_X_substeps + st_run.mot[MOTOR_5].substep_accumulator); -#endif motor_5.setDirection(st_pre.mot[MOTOR_5].direction); } motor_5.enable(); SET_ENCODER_STEP_SIGN(MOTOR_5, st_pre.mot[MOTOR_5].step_sign); } else { -#if defined(NEW_FWD_DIFF) && (NEW_FWD_DIFF==1) st_run.mot[MOTOR_5].substep_increment_increment = 0; -#endif motor_5.motionStopped(); } ACCUMULATE_ENCODER(MOTOR_5); #endif #if (MOTORS >= 6) if ((st_run.mot[MOTOR_6].substep_increment = st_pre.mot[MOTOR_6].substep_increment) != 0) { -#if NEW_DDA == 1 -#if defined(NEW_FWD_DIFF) && (NEW_FWD_DIFF==1) st_run.mot[MOTOR_6].substep_increment_increment = st_pre.mot[MOTOR_6].substep_increment_increment; -#endif -#else - if (st_pre.mot[MOTOR_6].accumulator_correction_flag == true) { - st_pre.mot[MOTOR_6].accumulator_correction_flag = false; - st_run.mot[MOTOR_6].substep_accumulator *= st_pre.mot[MOTOR_6].accumulator_correction; - } -#endif if (st_pre.mot[MOTOR_6].direction != st_pre.mot[MOTOR_6].prev_direction) { st_pre.mot[MOTOR_6].prev_direction = st_pre.mot[MOTOR_6].direction; -#if NEW_DDA == 1 st_run.mot[MOTOR_6].substep_accumulator = -(DDA_SUBSTEPS + st_run.mot[MOTOR_6].substep_accumulator); // invert the accumulator for the direction change -#else - st_run.mot[MOTOR_6].substep_accumulator = -(st_run.dda_ticks_X_substeps + st_run.mot[MOTOR_6].substep_accumulator); -#endif motor_6.setDirection(st_pre.mot[MOTOR_6].direction); } motor_6.enable(); SET_ENCODER_STEP_SIGN(MOTOR_6, st_pre.mot[MOTOR_6].step_sign); } else { -#if defined(NEW_FWD_DIFF) && (NEW_FWD_DIFF==1) st_run.mot[MOTOR_6].substep_increment_increment = 0; -#endif motor_6.motionStopped(); } ACCUMULATE_ENCODER(MOTOR_6); @@ -791,11 +661,7 @@ static void _load_move() * dda_ticks_X_substeps = (int32_t)((microseconds/1000000) * f_dda * dda_substeps); */ -#if !defined(NEW_FWD_DIFF) || (NEW_FWD_DIFF==0) -stat_t st_prep_line(float travel_steps[], float following_error[], float segment_time) -#else stat_t st_prep_line(float start_velocity, float end_velocity, float travel_steps[], float following_error[], float segment_time) -#endif { stepper_debug("😶"); // trap assertion failures and other conditions that would prevent queuing the line @@ -814,16 +680,10 @@ stat_t st_prep_line(float start_velocity, float end_velocity, float travel_steps //st_pre.dda_period = _f_to_period(FREQUENCY_DDA); // FYI: this is a constant st_pre.dda_ticks = (int32_t)(segment_time * 60 * FREQUENCY_DDA);// NB: converts minutes to seconds -#if NEW_DDA == 1 -#else - st_pre.dda_ticks_X_substeps = st_pre.dda_ticks * DDA_SUBSTEPS; -#endif // setup motor parameters -#if defined(NEW_FWD_DIFF) && (NEW_FWD_DIFF==1) // this is explained later double t_v0_v1 = (double)st_pre.dda_ticks * (start_velocity + end_velocity); -#endif float correction_steps; for (uint8_t motor=0; motor 0.0000001) { // highly tuned FP != compare - if (fp_NOT_ZERO(st_pre.mot[motor].prev_segment_time)) { // special case to skip first move - st_pre.mot[motor].accumulator_correction_flag = true; - st_pre.mot[motor].accumulator_correction = segment_time / st_pre.mot[motor].prev_segment_time; - } - st_pre.mot[motor].prev_segment_time = segment_time; - } -#endif // 'Nudge' correction strategy. Inject a single, scaled correction value then hold off // NOTE: This clause can be commented out to test for numerical accuracy and accumulating errors @@ -882,17 +728,6 @@ stat_t st_prep_line(float start_velocity, float end_velocity, float travel_steps // Rounding is performed to eliminate a negative bias in the uint32 conversion // that results in long-term negative drift. (fabs/round order doesn't matter) -#if NEW_DDA == 1 -#if !defined(NEW_FWD_DIFF) || (NEW_FWD_DIFF==0) - // t = v n s - // m = v n - // t = m s - // m = t/s - // Needed is steps/tick - // 1/m = s/t - - st_pre.mot[motor].substep_increment = round(fabs(travel_steps[motor] / (float)st_pre.dda_ticks) * (float)DDA_SUBSTEPS); -#else // t is ticks duration of the move // T is time duration of the move in minutes // f is dda frequency, ticks/sec @@ -931,11 +766,6 @@ stat_t st_prep_line(float start_velocity, float end_velocity, float travel_steps // option 2: // d = (b (v_1 - v_0))/((t-1) a) st_pre.mot[motor].substep_increment_increment = round(((s_double*(end_velocity-start_velocity))/(((double)st_pre.dda_ticks-1.0)*t_v0_v1)) * (double)DDA_SUBSTEPS); -#warning Using new increment style! -#endif -#else - st_pre.mot[motor].substep_increment = round(fabs(travel_steps[motor] * (double)DDA_SUBSTEPS)); -#endif } st_pre.block_type = BLOCK_TYPE_ALINE; st_pre.buffer_state = PREP_BUFFER_OWNED_BY_LOADER; // signal that prep buffer is ready diff --git a/g2core/stepper.h b/g2core/stepper.h index 3ec0e32d7..b8bc2c96f 100644 --- a/g2core/stepper.h +++ b/g2core/stepper.h @@ -254,8 +254,6 @@ #ifndef STEPPER_H_ONCE #define STEPPER_H_ONCE -#define NEW_DDA 1 - #include "MotateUtilities.h" // for HOT_DATA and HOT_FUNC #include "planner.h" // planner.h must precede stepper.h for moveType typedef @@ -313,11 +311,7 @@ typedef enum { * The ARM is roughly the same as the DDA clock rate is 4x higher but the segment time is ~1/5 * Decreasing the nominal segment time increases the number precision. */ -#if NEW_DDA == 1 #define DDA_SUBSTEPS (INT64_MAX-100) -#else -#define DDA_SUBSTEPS ((MAX_LONG * 0.90) / (FREQUENCY_DDA * (NOM_SEGMENT_TIME * 60))) -#endif /* Step correction settings * @@ -384,10 +378,6 @@ typedef struct stRunSingleton { // Stepper static values and axis pa magic_t magic_start; // magic number to test memory integrity uint32_t dda_ticks_downcount; // dda tick down-counter (unscaled) uint32_t dwell_ticks_downcount; // dwell tick down-counter (unscaled) -#if NEW_DDA == 1 -#else - uint32_t dda_ticks_X_substeps; // ticks multiplied by scaling factor -#endif stRunMotor_t mot[MOTORS]; // runtime motor structures magic_t magic_end; } stRunSingleton_t; @@ -424,10 +414,6 @@ typedef struct stPrepSingleton { uint32_t dda_ticks; // DDA ticks for the move float dda_ticks_holdover; // partial DDA ticks from previous segment uint32_t dwell_ticks; // dwell ticks remaining -#if NEW_DDA == 1 -#else - uint32_t dda_ticks_X_substeps; // DDA ticks scaled by substep factor -#endif stPrepMotor_t mot[MOTORS]; // prep time motor structs magic_t magic_end; } stPrepSingleton_t; @@ -609,11 +595,7 @@ void st_prep_null(void); void st_prep_command(void *bf); // use a void pointer since we don't know about mpBuf_t yet) void st_prep_dwell(float milliseconds); void st_request_out_of_band_dwell(float microseconds); -#if !defined(NEW_FWD_DIFF) || (NEW_FWD_DIFF==0) -stat_t st_prep_line(float travel_steps[], float following_error[], float segment_time) HOT_FUNC; -#else stat_t st_prep_line(float start_velocity, float end_velocity, float travel_steps[], float following_error[], float segment_time) HOT_FUNC; -#endif stat_t st_set_ma(nvObj_t *nv); stat_t st_set_sa(nvObj_t *nv); From 5bafefdf7839a1c714563d66d34de8caf7db490a Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Sat, 2 Dec 2017 08:30:13 -0600 Subject: [PATCH 146/193] Updating README with changelog (in progress) --- README.md | 240 ++++++++++++------------------------------------------ 1 file changed, 50 insertions(+), 190 deletions(-) diff --git a/README.md b/README.md index 85e41dd7e..f9ad55a7b 100644 --- a/README.md +++ b/README.md @@ -9,203 +9,63 @@ G2 [Edge](https://github.com/synthetos/g2/tree/edge) is the branch for beta test That said, Edge is for the adventurous. It is not guaranteed to be stable, but we do our best to achieve this. For production uses we recommend using the [Master branch](https://github.com/synthetos/g2/tree/master). -## Firmware Build 100 `{fb:100.xx}` +## Firmware Build 101 `{fb:101.xx}` ### Feature Enhancements -The fb:100 release is a major change from the fb:089 and earlier branches. It represents about a year of development and has many major feature enhancements summarized below. These are described in more detail in the rest of this readme and the linked wiki pages. -- New Gcode and CNC features -- 3d printing support, including [Marlin Compatibility](https://github.com/synthetos/g2/wiki/Marlin-Compatibility) -- GPIO system enhancements -- Planner enhancements and other operating improvements for high-speed operation -- Intital support for new processors, including the ARM M7 + +The fb:101 release is a mostly internal change from the fb:100 branches. Here are the highlights, more detailed changelog below: +- Updated JT (Junction integration Time, a.k.a. "cornering") handling to be more optimized, and to treat the last move as a corner to a move with no active axes. This allows a non-zero stopping velocity based on the allowed jerk and active JT value. +- Updated motion execution at the segment (smallest) level to be linear velocity instead of constant velocity, resulting in notably smoother motion and more faithful execution of the jerk limitations. (Incidentally, the sound of the motors is also slightly quieter and more "natural.") +- Probing enhancements. +- Added support for gQuintic (rev B) and fixed issues with gQuadratic board support. (This mostly happened in Motate.) +- Temperature control enhancements. (Ongoing.) +- More complete support for TMC2130 by adding more JSON controls for live feedback and configuration. ### Project Changes -The project is now called g2core (even if the repo remains g2). As of this release the g2core code base is split from the TinyG code base. TinyG will continue to be supported for the Xmega 8-bit platform, and new features will be added, specifically as related to continued support for CNC milling applications. The g2core project will focus on various ARM platforms, as it currently does, and add functions that are not possible in the 8-bit platform. - -In this release the Motate hardware abstraction layer has been split into a separate project and is included in g2core as a git submodule. This release also provides better support for cross platform / cross target compilation. A summary of project changes is provided below, with details in this readme and linked wiki pages. -- Motate submodule -- Cross platform / cross target support -- Multiple processor support - ARM M3, M4, M7 cores -- Device tree / multiple motor types -- Simplified host-to-board communication protocol (line mode) -- NodeJS host module for host-to-board communications - -### More To Come -The fb:100 release is the base for number of other enhancements in the works and planned, including: -- Further enhancements to GPIO system -- Additional JSON processing and UI support -- Enhancements to 3d printer support, including a simplified g2 printer dialect ## Changelog for Edge Branch -### Edge branch, Build 100.xx - -Build 100.xx has a number of changes, mostly related to extending Gcode support and supporting 3D printing using g2core. These include temperature controls, auto-bed leveling, planner performance improvements and active JSON comments in Gcode. +### Edge branch, Build 101.xx -Communications has advanced to support a linemode protocol to greatly simplify host communications and flow control for very rapid Gcode streams. Please read the Communications pages for details. Also see the NodeJS communications module docs if you are building a UI or host controller. - -Build 100.xx also significantly advances the project structure to support multiple processor architectures, hardware configurations and machine configurations in the same code base. Motate has been cleaved off into its own subproject. We recommend carefully reading the Dev pages if you are coding or compiling. +This build is primarily focused on support for the new boards based on the Atmel SamS70 family, as well as refining the motion control and long awaited feature enhancements. This list will be added to as development proceed.s #### Functional Changes: -- **Gcode and CNC Changes** - - Included `G10 L1`, `G10 L10`, `G43`, `G49` tool length offset and added 16 slot tool table (deferred until build 100.12) - - Included `G10 L20` offset mode - - Extended `G38.2` probing to also include `G38.3`, `G38.4`, `G38.5` - - Homing can now be set to a non-zero switch. Homing will set to the travel value of the positive or negative switch, as determined by the search direction. This allows homing to home to a maximum - for example - and set the homed location to the non-zero switch. - - [100.13] Fixes for dwells mixed with gcode moves. - - [100.13] Minor planner refactoring to better handle commands and gcode mixed. (Forward-planning now looks past commands.) - - [100.13] *Experimental!* Optioan `TRAVERSE_AT_HIGH_JERK` (defaults to off, set to 1 in a settings file to enable) will make traverse moves (`G0`) use the high-jerk settings instead of the normal jerk settings. This applies to all axes universally. - -- **Planner and Motion Changes** - - Junction Integration Time - the [`{jt:...}`](https://github.com/synthetos/g2/wiki/Configuring-0.99-System-Groups#jt-junction-integration-time) parameter is now the way to set cornering velocity limits. Cornering now obeys full jerk limitation instead of the centripetal acceleration heuristic, making it much more accurate and more true to the jerk limits set for the machine. JT is a normalized scaled factor that is nominally set to 1.000. Set to less than 1 for slower cornering (less aggressive), greater than 1 (but probably less than 2) for more aggressive cornering. This parameter replaces Junction Acceleration `{ja:...}` and the axis Junction Deviation commands - e.g. `{xjd:0.01}`. - - Deprecated `{ja:...}` global parameter. Will return error. - - Deprecated `{_jd:...}` per-axis parameter. Will return error. - - -- **3D Printing Support** - - Planner improvements to handle extreme cases found in some 3DP slicer outputs - - Added automatic bed leveling [{tram:t}](https://github.com/synthetos/g2/wiki/Configuring-0.99-3D-Printing-Extensions#tramt-tram-command) using 3 point probe and coordinate rotation - - Added [`{he1:n}`, `{he2:n}`, `{he3:n}`](https://github.com/synthetos/g2/wiki/Configuring-0.99-3D-Printing-Extensions#heater-groups) heater control groups - - Added `{pid1:n}`, `{pid2:n}`, `{pid3:n}` ADC PID groups - - Note: The semantics of `{he:...}` and `{pid:...}` are still in development and may change. - - -- **[GPIO Changes](https://github.com/synthetos/g2/wiki/Digital-IO)** - - Changed configuration for [`{di1:n}` ... `{di12:n}`](https://github.com/synthetos/g2/wiki/Digital-IO#digital-inputs) somewhat - - Added [`{do1:n}` ... `{do12:n}`](https://github.com/synthetos/g2/wiki/Digital-IO#digital-outputs) digital output controls for controlling general outputs such as fans - - Added [`{out1:n}` ... `{out12:n}`](https://github.com/synthetos/g2/wiki/Digital-IO#digital-outputs) digital output state readers for reading the condition of do's - - -- **Active JSON comments** - i.e. JSON called from Gcode - - Added `M100 ({...})` active comment. Currently only supports temperature setting command. - - Added `M101 ({...})` "wait-on-event" active comment. Currently only supports temperature wait command. - - Additional note: `M101` will only wait on values that return `true` or `false`, and will only work if given `true` or `false`. - - Valid example: - ``` - M101 ({in1: true}) - ``` - - Using `0` or `1`, or anything except `true` or `false` will *not* work. - - -- **System and Communications** - - [100.13] **Important:** USB will only expose one virtal serial port by default. - - This can be overridden in the settings file with: - ```c++ - // Valid options are 1 or 2 only! - #define USB_SERIAL_PORTS_EXPOSED 1 - ``` - - [100.13] Refactored XIO to handle `!`, `%`, `~`, and JSON commends intermixed with gcode better. - - [100.13] Fixes to USB connection, initialization, and DMA operation for Sam3X-base machines. - - Added `Linemode` communication protocol, and provide guidance to use linemode for much simpler and more reliable application-level flow control - - Footer format has changed. Checksum is no longer supported and has been removed - - Added `ENQ/ACK handshake`. If the host sends an ASCII `ENQ (0x05)` the board should respond with an `ACK (0x06)`. This is provided to facilitate low-level communications startup and automated testing - - Added [`{fbs:n}`](https://github.com/synthetos/g2/wiki/Configuring-0.99-System-Groups#fbsn-firmware-build-string) as a read-only parameter to report the git commit used during compilation - - Added [`{fbc:n}`](https://github.com/synthetos/g2/wiki/Configuring-0.99-System-Groups#fbcn-firmware-build-config-file) as a read-only parameter to report the configuration file used during compilation - - Changes to [`{ej:1}`](https://github.com/synthetos/g2/wiki/Configuring-0.99-System-Groups#ej-enable-json-mode) Enable JSON parameter. JSON and text mode are now "sticky". Auto mode (old style) is also available - - Added [`{Nsu:..}`](https://github.com/synthetos/g2/wiki/Configuring-0.99-Motors#1su-steps-per-unit) to directly set motor N's steps-per-unit value - - Changes to [Status Codes](https://github.com/synthetos/g2/wiki/Status-Codes) (...or see error.h for source) - - [Power Management](https://github.com/synthetos/g2/wiki/Power-Management) commands have been updated as of fb:100.11. Notably `{me:n}` and `{md:n}` are no longer valid commands - use `{me:0}` and `{md:0}` instead. Read the link for more changes. - - Additional [`stat`](https://github.com/synthetos/g2/wiki/Status-Reports#stat-values) machine states - - Removed `{cv:n}` configuration version tag - - Removed `{js:...}` JSON syntax. Responses are now always Strict. Accepts Strict or Relaxed on input - - Removed `{ec:...}` Expand CR to CRLF - - Removed `{ee:...}` Echo command - - Removed `{baud:...}` Set baud rate command - - Removed `{ml:...}` Minimum line segment hidden parameter - - Removed `{ma:...}` Minimum arc segment hidden parameter - - Removed `{ms:...}` Minimum segment time hidden parameter - - Exception reports now provide more information about the nature and location of the exception - - Removed code for embedded tests. These were a holdover from the TinyGv8 codebase and were not functional in g2. The code is now removed from the project. - - -- **[Project Structure and Motate](https://github.com/synthetos/g2/wiki/Project-Structure-and-Motate)** - - Motate underpinnings and project structure have changed significantly to support multiple processor architectures, boards, and machine configurations cleanly in the same project. If this affects you please read up on the wiki. - - -- **NodeJS g2core Communcications Module** - - A pre-release of the NodeJS g2core communications module that uses Linemode protocol is available here. This will be superseded with the official release - - -- **Automated Regression Testing** - - A simple Python functional and regression test suite is available in [Githup/Synthetos/tg_pytest](https://github.com/synthetos/tg_pytest). Please feel free to use and extend, but be aware that we are not offering much support for this. If you are familiar with Python and JSON the Readme should have everything you need. - - -#### Known Issues -- Communications bug for high-speed transmission - - -## Earlier Edges - -### Edge branch, build 083.07 -These changes are primarily fixes applied after testing -- Fixes to spindle speed settings (082.11) -- Fixes to build environments for Linux and other platforms -- Fixes for reporting error in inches mode - -### Edge branch, build 082.10 -- **[Digital IO (GPIO)](Digital-IO-(GPIO))** introduces major changes to the way switches and other inputs are handled. The digital inputs are completed, the digital outputs have not been. In short, inputs are now just numbered inputs that are mapped to axes, functions, and motion behaviors (feedholds). - - **Your configurations will need to change to accommodate these changes.** See settings/settings_shapeoko2.h for an example of setup and use - pay particular attention to `axis settings` and the new `inputs` section. - - Typing `$`, `$x`, `$di`, `$in` at the command line is also informative. Of course, all these commands are available as JSON, but in text mode you get the human readable annotations. - - These changes also rev the firmware version to 0.98 from 0.97, as a new configuration wiki page will need to be generated (not started yet). - - {lim:0}, {lim:1} was added to allow a limit override to backing off switches when a limit is tripped - - See also [Alarm Processing](Alarm-Processing), which is intimately related to these changes. - -- **[Alarm processing](Alarm-Processing)** has been significantly updated. There are now 3 alarm states: - - [ALARM](Alarm-Processing#alarm) - used to support soft and hard limits, safety interlock behaviors (door open), and other conditions. - - [SHUTDOWN](Alarm-Processing#shutdown) - used to support external ESTOP functions (the controller doe NOT do ESTOP - read the SHUTDOWN section as to why. - - [PANIC](Alarm-Processing#panic) - shuts down the machine immediately if there is an assertion failure or some other unrecoverable error - - [CLEAR](Alarm-Processing#clear) describes how to clear alarm states. - -- **[Job Exception Handling](Job-Exception-Handling)** has been refined. A new Job Kill has been introduced which is different than a queue flush (%), as these are actually 2 very different use cases. - -- **Homing** changes. Homing input switches are now configured differently. - - The switch configurations have been removed from the axes and moved to the digital IO inputs. - - Two new parameters have been added to the axis configs. All other parameters remain the same. - - {xhd:1} - homing direction - 0=search-to-negative, 1=search-to-positive - - {xhi:N} - homing input - 0=disable axis for homing, 1-N=enable homing for this input (switch) - - Note that setting the homing input to a non-zero value (1) enables homing for this axis, and (2) overrides whatever settings for that input for the duration of homing. So it's possible to set di1 (Xmin) as a limit switch and a homing switch. When not in homing it will be used as a limit switch. - -- **Safety Interlock** added - - An input configured for interlock will invoke a feedhold when the interlock becomes diseangaged and restart movement when re-engaged. - - {saf:0}, {saf:1} was added to enable or disable the interlock system. - - There are optional settings for spindle and coolant actions on feedhold. See below - -- **Spindle Changes** Expect updates to spindle behaviors in future branches. Here's where it is now: - - The spindle can be paused on feedhold with the Spindle-pause-on-hold global setting {spph:1}. For now we recommend not using this {spph:0} as there is not yet a delay in spindle restart. - - Spindle enable and direction polarity can now be set using the {spep: } and {spdp: } commands. - - Spindle enable and direction state can be returned using {spe:n} and {spd:n}, and these can be configured in status reports - - Spindle speed can be returned using {sps:n} and can be configured in status reports - -- **Coolant Changes** Expect coolant changes in future branches, in particular to accommodate changes in the digital outputs. - - The coolant can be paused on feedhold with the Coolant-pause-on-hold global setting {coph:0}. - - Flood and mist coolant polarity can now be set using the {cofp: } and {comp: } commands. - - Flood and mist coolant state can be returned using {cof:n} and {com:n}, and these can be configured in status reports - - In v9 the flood (M8) and mist (M7) commands are operative, but map the same pin. M9 clears them both, as expected. These should both be set to the same polarity for proper operation. On a Due or a platform with more output pins these can be separated - the code is written for this possibility. The changes should be limited to the pin mapping layers. - -- **Power Management** is fully working, as far as we can tell. See $1pm for settings - -- **Arc Changes** have been added. Please note any issues immediately. This is still under test. - - Fixed bug on very large arcs - - Fixed bug on G18 rotation direction - - Added P parameter to allow for arcs > 360 degree rotation - -- **G10 L20** was added for easier offset setting - -- **Bug Fixes** - - Fixed some units mode display errors for G20 mode (inches) - -- **Still To Go** - - SD card persistence - - Spindle restart dwell - - Digital output generalization and changes - - Still needs rigorous testing for very fast feedhold/resume and flush cycles - -### Edge branch, build 071.02 - -* **No Persistence**. Most ARM chips (including the ATSAM3X8C on v9 and ATSAM3X8E on the Arduino Due) do not have persistence. This is the main reason the v9 has a microSD slot. But this has not been programmed yet. So your options are to either load the board each time you fire it up or reset it, or to build yourself a profile and compile your own settings as the defaults. - -* **Still working on feedhold.** The serial communications runs a native USB on the ARM instead of through an FTDI USB-to-Serial adapter. We are still shing some bugs out of the single character commands such as feedhold (!), queue flush (%) and cycle start (~). - -* **Power Management needs work.** It doesn't always shut the motors off at the end of a cycle. -* **Different Behaviors**. There are some behaviors that are different. - * Feedhold / queue flush on v8 works with !%~ in one line. In g2 it requires a newline. Use !\n%\n This is due to using a USB stack that is partly on the chip and not being able to get at the individual characters that far upstream. This will probably not change in v9. +- **Linear-Velocity Segment Execution** + - The overall motion is still jerk-controlled and the computation of motion remains largely the same (although slightly simplified). At the smallest level above raw steps (what we call "segments," which are nominally 0.25ms to 1ms in duration) we previously executed the steps at a constant velocity. We now execute them with a linear change from a start velocity to an end velocity. This results in smoother motion that is more faithful to the planned jerk constraints. + - This changed the way the forward differences are used to compute the segment speeds as well. Previously, we were computing the curve at the midpoint (time-wise) of each segment in order to get the median velocity. Now that we want the start and end velocity of each segment we only compute the end (time-wise) of each segment, and use that again later as the start-point of the next segment. + +- **Probing enhancements** + - Added `{"prbs":true}` to store the current position as if it were to position of a succesful probe. + - Added `{"prbr":true}` to enable and `{"prbr":false}` to enable and disable (respectively) the JSON `{prb:{...}}` report after a probe. + +- **gQuintic support** + - Support for the gQuintic rev B was added. Support for rev D will come shortly. + +- **Temperature control enhancements** + - Added the following settings defines: + - `HAS_TEMPERATURE_SENSOR_1`, `HAS_TEMPERATURE_SENSOR_2`, and `HAS_TEMPERATURE_SENSOR_3` + - `EXTRUDER_1_OUTPUT_PIN`, `EXTRUDER_2_OUTPUT_PIN`, and `BED_OUTPUT_PIN` + - Added `BED_OUTPUT_INIT` in order to control configuration of the Bed output pin settings. + - Defaults to `{kNormal, fet_pin3_freq}`. + - `EXTRUDER_1_FAN_PIN` for control of the temperature-enabled fan on extruder 1. (Only available on extruder 1 at the moment.) + +- **TMC2130 JSON controls** + - Added the following setting keys to the motors (`1` - `6`): + - `ts` - *(R)* get the value of the `TSTEP` register + - `pth` - *(R/W)* get/set the value of the `TPWMTHRS` register + - `cth` - *(R/W)* get/set the value of the `TCOOLTHRS` register + - `hth` - *(R/W)* get/set the value of the `THIGH` register + - `sgt` - *(R/W)* get/set the value of the `sgt` value of the `COOLCONF` register + - `sgr` - *(R)* get the `SG_RESULT` value of the `DRV_STATUS` register + - `csa` - *(R)* get the `CS_ACTUAL` value of the `DRV_STATUS` register + - `sgs` - *(R)* get the `stallGuard` value of the `DRV_STATUS` register + - `tbl` - *(R/W)* get/set the `TBL` value of the `CHOPCONF` register + - `pgrd` - *(R/W)* get/set the `PWM_GRAD` value of the `PWMCONF` register + - `pamp` - *(R/W)* get/set the `PWM_AMPL` value of the `PWMCONF` register + - `hend` - *(R/W)* get/set the `HEND_OFFSET` value of the `CHOPCONF` register + - `hsrt` - *(R/W)* get/set the `HSTRT/TFD012` value of the `CHOPCONF` register + - `smin` - *(R/W)* get/set the `semin` value of the `COOLCONF` register + - `smax` - *(R/W)* get/set the `semax` value of the `COOLCONF` register + - `sup` - *(R/W)* get/set the `seup` value of the `COOLCONF` register + - `sdn` - *(R/W)* get/set the `sedn` value of the `COOLCONF` register + - Note that all gets retrieve the last cached value. From 196791923e4f308034e350bd737463563c3b4144 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Sat, 2 Dec 2017 08:51:12 -0600 Subject: [PATCH 147/193] Fixes for temperature settings in the various Printrbot settings --- g2core/settings/settings_Printrbot_Play.h | 64 ++++++------------- g2core/settings/settings_Printrbot_Plus.h | 45 ++++++------- .../settings/settings_Printrbot_Simple_1403.h | 45 ++++++------- .../settings/settings_Printrbot_Simple_1608.h | 43 ++++++------- 4 files changed, 76 insertions(+), 121 deletions(-) diff --git a/g2core/settings/settings_Printrbot_Play.h b/g2core/settings/settings_Printrbot_Play.h index bcae1bf19..a1e2a9f49 100644 --- a/g2core/settings/settings_Printrbot_Play.h +++ b/g2core/settings/settings_Printrbot_Play.h @@ -323,69 +323,45 @@ //** Temperature Sensors ** -#include "device/max31865/max31865.h" - -#define USING_A_MAX31865 1 - #define HAS_TEMPERATURE_SENSOR_1 true #if HAS_TEMPERATURE_SENSOR_1 -// #define TEMPERATURE_SENSOR_1_CIRCUIT_TYPE ADCCircuitSimplePullup -// #define TEMPERATURE_SENSOR_1_CIRCUIT_INIT { /*pullup_resistance:*/ 4700 } -// #define TEMPERATURE_SENSOR_1_TYPE Thermistor -// #define TEMPERATURE_SENSOR_1_INIT { \ -// /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ -// /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, &temperature_sensor_1_circuit \ -// } - - #define TEMPERATURE_SENSOR_1_CIRCUIT_TYPE ADCCircuitRawResistance - #define TEMPERATURE_SENSOR_1_CIRCUIT_INIT { /*pullup_resistance:*/ 430 } - #define TEMPERATURE_SENSOR_1_TYPE Thermistor> + #define TEMPERATURE_SENSOR_1_CIRCUIT_TYPE ADCCircuitSimplePullup + #define TEMPERATURE_SENSOR_1_CIRCUIT_INIT { /*pullup_resistance:*/ 4700 } + #define TEMPERATURE_SENSOR_1_TYPE Thermistor> #define TEMPERATURE_SENSOR_1_INIT { \ /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ - /*R1:*/ 99500.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, &temperature_sensor_1_circuit \ - /*MAX31865 config*/ spiBus, spiCSPinMux.getCS(5), 150000 \ + /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, \ + &temperature_sensor_1_circuit \ } - #endif // HAS_TEMPERATURE_SENSOR_1 -#define EXTRUDER_1_OUTPUT_PIN kHeaterOutput1_PinNumber -#define EXTRUDER_1_FAN_PIN kOutput5_PinNumber - +#define EXTRUDER_1_OUTPUT_PIN kOutput1_PinNumber +#define EXTRUDER_1_FAN_PIN kOutput3_PinNumber #define HAS_TEMPERATURE_SENSOR_2 false #if HAS_TEMPERATURE_SENSOR_2 -#if 1 // 1 if a Thermistor, 0 if a PT100 - #define TEMPERATURE_SENSOR_2_TYPE Thermistor> + #define TEMPERATURE_SENSOR_2_CIRCUIT_TYPE ADCCircuitSimplePullup + #define TEMPERATURE_SENSOR_2_CIRCUIT_INIT { /*pullup_resistance:*/ 4700 } + #define TEMPERATURE_SENSOR_2_TYPE Thermistor> #define TEMPERATURE_SENSOR_2_INIT { \ - /*T1:*/ 25.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ - /*R1:*/ 99500.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 10500.0 \ + /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ + /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, \ + &temperature_sensor_2_circuit \ } -#else - #define TEMPERATURE_SENSOR_2_TYPE PT100> - #define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 200, /*inline_resistance*/0.0} -// #define TEMPERATURE_SENSOR_2_TYPE PT100> -// #define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 430, /*inline_resistance*/0, spiBus, spiCSPinMux.getCS(5)} -#endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_2 -#define EXTRUDER_2_OUTPUT_PIN kHeaterOutput2_PinNumber - +#define EXTRUDER_2_OUTPUT_PIN kOutput2_PinNumber #define HAS_TEMPERATURE_SENSOR_3 false #if HAS_TEMPERATURE_SENSOR_3 -#if 1 // 1 if a Thermistor, 0 if a PT100 - #define TEMPERATURE_SENSOR_3_TYPE Thermistor> + #define TEMPERATURE_SENSOR_3_CIRCUIT_TYPE ADCCircuitSimplePullup + #define TEMPERATURE_SENSOR_3_CIRCUIT_INIT { /*pullup_resistance:*/ 4700 } + #define TEMPERATURE_SENSOR_3_TYPE Thermistor> #define TEMPERATURE_SENSOR_3_INIT { \ - /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ - /*R1:*/ 99500.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 10500.0 \ + /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ + /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, \ + &temperature_sensor_3_circuit \ } -#else - // #define TEMPERATURE_SENSOR_3_TYPE PT100> - // #define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 200, /*inline_resistance*/0.0} - #define TEMPERATURE_SENSOR_3_TYPE PT100> - #define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 430, /*inline_resistance*/0, spiBus, spiCSPinMux.getCS(6)} - -#endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_3 #define BED_OUTPUT_PIN kHeaterOutput11_PinNumber diff --git a/g2core/settings/settings_Printrbot_Plus.h b/g2core/settings/settings_Printrbot_Plus.h index af2707930..1881b8887 100644 --- a/g2core/settings/settings_Printrbot_Plus.h +++ b/g2core/settings/settings_Printrbot_Plus.h @@ -247,50 +247,43 @@ #define HAS_TEMPERATURE_SENSOR_1 true #if HAS_TEMPERATURE_SENSOR_1 -// Must choose Thermistor or PT100 -#if 1 // 1 if a Thermistor, 0 if a PT100 - #define TEMPERATURE_SENSOR_1_TYPE Thermistor + #define TEMPERATURE_SENSOR_1_CIRCUIT_TYPE ADCCircuitSimplePullup + #define TEMPERATURE_SENSOR_1_CIRCUIT_INIT { /*pullup_resistance:*/ 4700 } + #define TEMPERATURE_SENSOR_1_TYPE Thermistor> #define TEMPERATURE_SENSOR_1_INIT { \ /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ - /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ + /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, \ + &temperature_sensor_1_circuit \ } -#else - #define TEMPERATURE_SENSOR_1_TYPE PT100 - #define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} -#endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_1 #define EXTRUDER_1_OUTPUT_PIN kOutput1_PinNumber #define EXTRUDER_1_FAN_PIN kOutput3_PinNumber -#define HAS_TEMPERATURE_SENSOR_2 true +#define HAS_TEMPERATURE_SENSOR_2 false #if HAS_TEMPERATURE_SENSOR_2 -#if 1 // 1 if a Thermistor, 0 if a PT100 - #define TEMPERATURE_SENSOR_2_TYPE Thermistor + #define TEMPERATURE_SENSOR_2_CIRCUIT_TYPE ADCCircuitSimplePullup + #define TEMPERATURE_SENSOR_2_CIRCUIT_INIT { /*pullup_resistance:*/ 4700 } + #define TEMPERATURE_SENSOR_2_TYPE Thermistor> #define TEMPERATURE_SENSOR_2_INIT { \ - /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ - /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ + /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ + /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, \ + &temperature_sensor_2_circuit \ } -#else - #define TEMPERATURE_SENSOR_2_TYPE PT100 - #define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} -#endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_2 #define EXTRUDER_2_OUTPUT_PIN kOutput2_PinNumber -#define HAS_TEMPERATURE_SENSOR_3 true +#define HAS_TEMPERATURE_SENSOR_3 false #if HAS_TEMPERATURE_SENSOR_3 -#if 1 // 1 if a Thermistor, 0 if a PT100 - #define TEMPERATURE_SENSOR_3_TYPE Thermistor + #define TEMPERATURE_SENSOR_3_CIRCUIT_TYPE ADCCircuitSimplePullup + #define TEMPERATURE_SENSOR_3_CIRCUIT_INIT { /*pullup_resistance:*/ 4700 } + #define TEMPERATURE_SENSOR_3_TYPE Thermistor> #define TEMPERATURE_SENSOR_3_INIT { \ - /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ - /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ + /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ + /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, \ + &temperature_sensor_3_circuit \ } -#else - #define TEMPERATURE_SENSOR_3_TYPE PT100 - #define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} -#endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_3 #define BED_OUTPUT_PIN kOutput11_PinNumber diff --git a/g2core/settings/settings_Printrbot_Simple_1403.h b/g2core/settings/settings_Printrbot_Simple_1403.h index dc9ea2a9d..053d79a28 100644 --- a/g2core/settings/settings_Printrbot_Simple_1403.h +++ b/g2core/settings/settings_Printrbot_Simple_1403.h @@ -243,50 +243,43 @@ #define HAS_TEMPERATURE_SENSOR_1 true #if HAS_TEMPERATURE_SENSOR_1 -// Must choose Thermistor or PT100 -#if 1 // 1 if a Thermistor, 0 if a PT100 - #define TEMPERATURE_SENSOR_1_TYPE Thermistor + #define TEMPERATURE_SENSOR_1_CIRCUIT_TYPE ADCCircuitSimplePullup + #define TEMPERATURE_SENSOR_1_CIRCUIT_INIT { /*pullup_resistance:*/ 4700 } + #define TEMPERATURE_SENSOR_1_TYPE Thermistor> #define TEMPERATURE_SENSOR_1_INIT { \ /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ - /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ + /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, \ + &temperature_sensor_1_circuit \ } -#else - #define TEMPERATURE_SENSOR_1_TYPE PT100 - #define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} -#endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_1 #define EXTRUDER_1_OUTPUT_PIN kOutput1_PinNumber #define EXTRUDER_1_FAN_PIN kOutput3_PinNumber -#define HAS_TEMPERATURE_SENSOR_2 true +#define HAS_TEMPERATURE_SENSOR_2 false #if HAS_TEMPERATURE_SENSOR_2 -#if 1 // 1 if a Thermistor, 0 if a PT100 - #define TEMPERATURE_SENSOR_2_TYPE Thermistor + #define TEMPERATURE_SENSOR_2_CIRCUIT_TYPE ADCCircuitSimplePullup + #define TEMPERATURE_SENSOR_2_CIRCUIT_INIT { /*pullup_resistance:*/ 4700 } + #define TEMPERATURE_SENSOR_2_TYPE Thermistor> #define TEMPERATURE_SENSOR_2_INIT { \ - /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ - /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ + /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ + /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, \ + &temperature_sensor_2_circuit \ } -#else - #define TEMPERATURE_SENSOR_2_TYPE PT100 - #define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} -#endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_2 #define EXTRUDER_2_OUTPUT_PIN kOutput2_PinNumber -#define HAS_TEMPERATURE_SENSOR_3 true +#define HAS_TEMPERATURE_SENSOR_3 false #if HAS_TEMPERATURE_SENSOR_3 -#if 1 // 1 if a Thermistor, 0 if a PT100 - #define TEMPERATURE_SENSOR_3_TYPE Thermistor + #define TEMPERATURE_SENSOR_3_CIRCUIT_TYPE ADCCircuitSimplePullup + #define TEMPERATURE_SENSOR_3_CIRCUIT_INIT { /*pullup_resistance:*/ 4700 } + #define TEMPERATURE_SENSOR_3_TYPE Thermistor> #define TEMPERATURE_SENSOR_3_INIT { \ - /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ - /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ + /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ + /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, \ + &temperature_sensor_3_circuit \ } -#else - #define TEMPERATURE_SENSOR_3_TYPE PT100 - #define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} -#endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_3 #define BED_OUTPUT_PIN kOutput11_PinNumber diff --git a/g2core/settings/settings_Printrbot_Simple_1608.h b/g2core/settings/settings_Printrbot_Simple_1608.h index aec6782fd..8bfd6b684 100644 --- a/g2core/settings/settings_Printrbot_Simple_1608.h +++ b/g2core/settings/settings_Printrbot_Simple_1608.h @@ -257,17 +257,14 @@ #define HAS_TEMPERATURE_SENSOR_1 true #if HAS_TEMPERATURE_SENSOR_1 -// Must choose Thermistor or PT100 -#if 1 // 1 if a Thermistor, 0 if a PT100 - #define TEMPERATURE_SENSOR_1_TYPE Thermistor + #define TEMPERATURE_SENSOR_1_CIRCUIT_TYPE ADCCircuitSimplePullup + #define TEMPERATURE_SENSOR_1_CIRCUIT_INIT { /*pullup_resistance:*/ 4700 } + #define TEMPERATURE_SENSOR_1_TYPE Thermistor> #define TEMPERATURE_SENSOR_1_INIT { \ /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ - /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ + /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, \ + &temperature_sensor_1_circuit \ } -#else - #define TEMPERATURE_SENSOR_1_TYPE PT100 - #define TEMPERATURE_SENSOR_1_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} -#endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_1 #define EXTRUDER_1_OUTPUT_PIN kOutput1_PinNumber @@ -275,32 +272,28 @@ #define HAS_TEMPERATURE_SENSOR_2 false #if HAS_TEMPERATURE_SENSOR_2 -#if 1 // 1 if a Thermistor, 0 if a PT100 - #define TEMPERATURE_SENSOR_2_TYPE Thermistor + #define TEMPERATURE_SENSOR_2_CIRCUIT_TYPE ADCCircuitSimplePullup + #define TEMPERATURE_SENSOR_2_CIRCUIT_INIT { /*pullup_resistance:*/ 4700 } + #define TEMPERATURE_SENSOR_2_TYPE Thermistor> #define TEMPERATURE_SENSOR_2_INIT { \ - /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ - /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ + /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ + /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, \ + &temperature_sensor_2_circuit \ } -#else - #define TEMPERATURE_SENSOR_2_TYPE PT100 - #define TEMPERATURE_SENSOR_2_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} -#endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_2 #define EXTRUDER_2_OUTPUT_PIN kOutput2_PinNumber -#define HAS_TEMPERATURE_SENSOR_3 true +#define HAS_TEMPERATURE_SENSOR_3 false #if HAS_TEMPERATURE_SENSOR_3 -#if 1 // 1 if a Thermistor, 0 if a PT100 - #define TEMPERATURE_SENSOR_3_TYPE Thermistor + #define TEMPERATURE_SENSOR_3_CIRCUIT_TYPE ADCCircuitSimplePullup + #define TEMPERATURE_SENSOR_3_CIRCUIT_INIT { /*pullup_resistance:*/ 4700 } + #define TEMPERATURE_SENSOR_3_TYPE Thermistor> #define TEMPERATURE_SENSOR_3_INIT { \ - /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ - /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, /*pullup_resistance:*/ 4700 \ + /*T1:*/ 20.0, /*T2:*/ 190.0, /*T3:*/ 255.0, \ + /*R1:*/ 144700.0, /*R2:*/ 5190.0, /*R3:*/ 4809.0, \ + &temperature_sensor_3_circuit \ } -#else - #define TEMPERATURE_SENSOR_3_TYPE PT100 - #define TEMPERATURE_SENSOR_3_INIT {/*pullup_resistance:*/ 2325, /*inline_resistance*/0.75} -#endif // 0 or 1 #endif // HAS_TEMPERATURE_SENSOR_3 #define BED_OUTPUT_PIN kOutput11_PinNumber From abd655c601c520037419c2ead336dadc1a2bcebc Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Sat, 2 Dec 2017 09:57:21 -0600 Subject: [PATCH 148/193] Fix disambiguation of outputs to heaters on all board types. --- g2core/board/G2v9/motate_pin_assignments.h | 9 ++++++--- g2core/board/gquadratic/motate_pin_assignments.h | 9 ++++++--- g2core/board/printrboardg2/motate_pin_assignments.h | 9 ++++++--- g2core/board/printrboardg2/printrboardG2v3-pinout.h | 4 ++-- g2core/settings/settings_Printrbot_Play.h | 5 +++-- g2core/settings/settings_Printrbot_Plus.h | 7 ++++--- g2core/settings/settings_Printrbot_Simple_1403.h | 7 ++++--- g2core/settings/settings_Printrbot_Simple_1608.h | 7 ++++--- 8 files changed, 35 insertions(+), 22 deletions(-) diff --git a/g2core/board/G2v9/motate_pin_assignments.h b/g2core/board/G2v9/motate_pin_assignments.h index 2b3450ce2..28091bc43 100644 --- a/g2core/board/G2v9/motate_pin_assignments.h +++ b/g2core/board/G2v9/motate_pin_assignments.h @@ -171,8 +171,10 @@ pin_number kGRBL_CommonEnablePinNumber = -1; // g2ref extensions // These first 5 may replace the Spindle and Coolant pins, above -pin_number kOutput1_PinNumber = 130; // DO_1: Extruder1_PWM -pin_number kOutput2_PinNumber = 131; // DO_2: Extruder2_PWM +pin_number kHeaterOutput1_PinNumber = -1; // DO_1: Extruder1_PWM +pin_number kHeaterOutput2_PinNumber = -1; // DO_2: Extruder2_PWM +pin_number kOutput1_PinNumber = 130; // DO_1: +pin_number kOutput2_PinNumber = 131; // DO_2: pin_number kOutput3_PinNumber = 132; // DO_3: Fan1A_PWM pin_number kOutput4_PinNumber = 133; // DO_4: Fan1B_PWM pin_number kOutput5_PinNumber = 134; // DO_5: Fan2A_PWM @@ -183,7 +185,8 @@ pin_number kOutput8_PinNumber = -1; // 137; // See Coolant Enable pin_number kOutput9_PinNumber = 138; // pin_number kOutput10_PinNumber = 139; // DO_10: Fan2B_PWM -pin_number kOutput11_PinNumber = 140; // DO_11: Heated Bed FET +pin_number kHeaterOutput11_PinNumber = -1; // DO_11: Heated Bed FET +pin_number kOutput11_PinNumber = 140; // DO_11: pin_number kOutput12_PinNumber = 141; // DO_12: Indicator_LED pin_number kOutput13_PinNumber = -1; // 142; pin_number kOutput14_PinNumber = -1; // 143; diff --git a/g2core/board/gquadratic/motate_pin_assignments.h b/g2core/board/gquadratic/motate_pin_assignments.h index 957b7c8d3..0057a9e4c 100755 --- a/g2core/board/gquadratic/motate_pin_assignments.h +++ b/g2core/board/gquadratic/motate_pin_assignments.h @@ -176,8 +176,10 @@ pin_number kGRBL_CommonEnablePinNumber = -1; // g2ref extensions // These first 5 may replace the Spindle and Coolant pins, above -pin_number kOutput1_PinNumber = 130; // DO_1: Extruder1_PWM -pin_number kOutput2_PinNumber = 131; // DO_2: Extruder2_PWM +pin_number kHeaterOutput1_PinNumber = -1; // DO_1: Extruder1_PWM +pin_number kHeaterOutput2_PinNumber = -1; // DO_2: Extruder2_PWM +pin_number kOutput1_PinNumber = 130; // DO_1: +pin_number kOutput2_PinNumber = 131; // DO_2: pin_number kOutput3_PinNumber = 132; // DO_3: Fan1A_PWM pin_number kOutput4_PinNumber = 133; // DO_4: Fan1B_PWM pin_number kOutput5_PinNumber = 134; // DO_5: Fan2A_PWM @@ -188,7 +190,8 @@ pin_number kOutput8_PinNumber = 137; // See Coolant Enable pin_number kOutput9_PinNumber = 138; // SAFE signal pin_number kOutput10_PinNumber = 139; // DO_10: Fan2B_PWM -pin_number kOutput11_PinNumber = 140; // DO_11: Heated Bed FET +pin_number kHeaterOutput11_PinNumber = -1; // DO_11: Heated Bed FET +pin_number kOutput11_PinNumber = 140; // DO_11: pin_number kOutput12_PinNumber = 141; // DO_12: Indicator_LED pin_number kOutput13_PinNumber = -1; // 142; pin_number kOutput14_PinNumber = -1; // 143; diff --git a/g2core/board/printrboardg2/motate_pin_assignments.h b/g2core/board/printrboardg2/motate_pin_assignments.h index e90c5e119..3ebdcc5aa 100755 --- a/g2core/board/printrboardg2/motate_pin_assignments.h +++ b/g2core/board/printrboardg2/motate_pin_assignments.h @@ -178,8 +178,10 @@ pin_number kGRBL_CommonEnablePinNumber = -1; // g2ref extensions // These first 5 may replace the Spindle and Coolant pins, above -pin_number kOutput1_PinNumber = 130; // DO_1: Extruder1_PWM -pin_number kOutput2_PinNumber = 131; // DO_2: Extruder2_PWM +pin_number kHeaterOutput1_PinNumber = 130; // DO_1: Extruder1_PWM +pin_number kHeaterOutput2_PinNumber = 131; // DO_2: Extruder2_PWM +pin_number kOutput1_PinNumber = -1; // DO_1: +pin_number kOutput2_PinNumber = -1; // DO_2: pin_number kOutput3_PinNumber = 132; // DO_3: Fan1A_PWM pin_number kOutput4_PinNumber = 133; // DO_4: Fan1B_PWM pin_number kOutput5_PinNumber = 134; // DO_5: Fan2A_PWM @@ -190,7 +192,8 @@ pin_number kOutput8_PinNumber = 137; // See Coolant Enable pin_number kOutput9_PinNumber = 138; // SAFE signal pin_number kOutput10_PinNumber = 139; // DO_10: Fan2B_PWM -pin_number kOutput11_PinNumber = 140; // DO_11: Heated Bed FET +pin_number kHeaterOutput11_PinNumber = 140; // DO_11: Heated Bed FET +pin_number kOutput11_PinNumber = -1; // DO_11: pin_number kOutput12_PinNumber = 141; // DO_12: Indicator_LED pin_number kOutput13_PinNumber = -1; // 142; pin_number kOutput14_PinNumber = -1; // 143; diff --git a/g2core/board/printrboardg2/printrboardG2v3-pinout.h b/g2core/board/printrboardg2/printrboardG2v3-pinout.h index 386524a8d..429d31116 100755 --- a/g2core/board/printrboardg2/printrboardG2v3-pinout.h +++ b/g2core/board/printrboardg2/printrboardG2v3-pinout.h @@ -121,7 +121,7 @@ _MAKE_MOTATE_PIN(kUnassigned2, 'A', 1); // nc _MAKE_MOTATE_PIN(kSocket4_VrefPinNumber, 'A', 2); // M4_Vref _MAKE_MOTATE_PIN(kUnassigned3, 'A', 3); // nc _MAKE_MOTATE_PIN(kADC3_PinNumber, 'A', 4); // BED_ADC -_MAKE_MOTATE_PIN(kOutput1_PinNumber, 'A', 5); // DO_1 (Extruder1_PWM) +_MAKE_MOTATE_PIN(kHeaterOutput1_PinNumber, 'A', 5); // DO_1 (Extruder1_PWM) _MAKE_MOTATE_PIN(kOutput3_PinNumber, 'A', 6); // DO_3 (Fan1B_PWM) _MAKE_MOTATE_PIN(kOutputSAFE_PinNumber, 'A', 7); // DO_9 (SAFE_PULSES - output from MCU) _MAKE_MOTATE_PIN(kSerial_RXPinNumber, 'A', 8); // UART_RX @@ -171,7 +171,7 @@ _MAKE_MOTATE_PIN(kSocket2_Microstep_2PinNumber, 'B', 20); // M2_MS2 _MAKE_MOTATE_PIN(kSocket2_Microstep_0PinNumber, 'B', 21); // M2_MS0 (M2_MS1 is slaved to this signal also) _MAKE_MOTATE_PIN(kSocket4_EnablePinNumber, 'B', 22); // M4_ENABLE _MAKE_MOTATE_PIN(kSocket4_DirPinNumber, 'B', 23); // M4_DIR -_MAKE_MOTATE_PIN(kOutput11_PinNumber, 'B', 24); // DO_11 (Header Bed FET) +_MAKE_MOTATE_PIN(kHeaterOutput11_PinNumber, 'B', 24); // DO_11 (Header Bed FET) _MAKE_MOTATE_PIN(kOutput5_PinNumber, 'B', 25); // DO_5 (Fan2A_PWM) _MAKE_MOTATE_PIN(kInput1_PinNumber, 'B', 26); // DI_1 (XMin) _MAKE_MOTATE_PIN(kOutput4_PinNumber, 'B', 27); // DO_4 (Fan1A_PWM) diff --git a/g2core/settings/settings_Printrbot_Play.h b/g2core/settings/settings_Printrbot_Play.h index a1e2a9f49..1420995f4 100644 --- a/g2core/settings/settings_Printrbot_Play.h +++ b/g2core/settings/settings_Printrbot_Play.h @@ -335,7 +335,7 @@ } #endif // HAS_TEMPERATURE_SENSOR_1 -#define EXTRUDER_1_OUTPUT_PIN kOutput1_PinNumber +#define EXTRUDER_1_OUTPUT_PIN kHeaterOutput1_PinNumber #define EXTRUDER_1_FAN_PIN kOutput3_PinNumber #define HAS_TEMPERATURE_SENSOR_2 false @@ -350,7 +350,8 @@ } #endif // HAS_TEMPERATURE_SENSOR_2 -#define EXTRUDER_2_OUTPUT_PIN kOutput2_PinNumber +// Warning - the PrintrBoardG2 doesn't have a Output2 +#define EXTRUDER_2_OUTPUT_PIN kHeaterOutput2_PinNumber #define HAS_TEMPERATURE_SENSOR_3 false #if HAS_TEMPERATURE_SENSOR_3 diff --git a/g2core/settings/settings_Printrbot_Plus.h b/g2core/settings/settings_Printrbot_Plus.h index 1881b8887..2ec59827f 100644 --- a/g2core/settings/settings_Printrbot_Plus.h +++ b/g2core/settings/settings_Printrbot_Plus.h @@ -257,7 +257,7 @@ } #endif // HAS_TEMPERATURE_SENSOR_1 -#define EXTRUDER_1_OUTPUT_PIN kOutput1_PinNumber +#define EXTRUDER_1_OUTPUT_PIN kHeaterOutput1_PinNumber #define EXTRUDER_1_FAN_PIN kOutput3_PinNumber #define HAS_TEMPERATURE_SENSOR_2 false @@ -272,7 +272,8 @@ } #endif // HAS_TEMPERATURE_SENSOR_2 -#define EXTRUDER_2_OUTPUT_PIN kOutput2_PinNumber +// Warning - the PrintrBoardG2 doesn't have a Output2 +#define EXTRUDER_2_OUTPUT_PIN kHeaterOutput2_PinNumber #define HAS_TEMPERATURE_SENSOR_3 false #if HAS_TEMPERATURE_SENSOR_3 @@ -286,7 +287,7 @@ } #endif // HAS_TEMPERATURE_SENSOR_3 -#define BED_OUTPUT_PIN kOutput11_PinNumber +#define BED_OUTPUT_PIN kHeaterOutput11_PinNumber //** Digital Inputs ** diff --git a/g2core/settings/settings_Printrbot_Simple_1403.h b/g2core/settings/settings_Printrbot_Simple_1403.h index 053d79a28..25318c00e 100644 --- a/g2core/settings/settings_Printrbot_Simple_1403.h +++ b/g2core/settings/settings_Printrbot_Simple_1403.h @@ -253,7 +253,7 @@ } #endif // HAS_TEMPERATURE_SENSOR_1 -#define EXTRUDER_1_OUTPUT_PIN kOutput1_PinNumber +#define EXTRUDER_1_OUTPUT_PIN kHeaterOutput1_PinNumber #define EXTRUDER_1_FAN_PIN kOutput3_PinNumber #define HAS_TEMPERATURE_SENSOR_2 false @@ -268,7 +268,8 @@ } #endif // HAS_TEMPERATURE_SENSOR_2 -#define EXTRUDER_2_OUTPUT_PIN kOutput2_PinNumber +// Warning - the PrintrBoardG2 doesn't have a Output2 +#define EXTRUDER_2_OUTPUT_PIN kHeaterOutput2_PinNumber #define HAS_TEMPERATURE_SENSOR_3 false #if HAS_TEMPERATURE_SENSOR_3 @@ -282,7 +283,7 @@ } #endif // HAS_TEMPERATURE_SENSOR_3 -#define BED_OUTPUT_PIN kOutput11_PinNumber +#define BED_OUTPUT_PIN kHeaterOutput11_PinNumber /* diff --git a/g2core/settings/settings_Printrbot_Simple_1608.h b/g2core/settings/settings_Printrbot_Simple_1608.h index 8bfd6b684..ad64072a6 100644 --- a/g2core/settings/settings_Printrbot_Simple_1608.h +++ b/g2core/settings/settings_Printrbot_Simple_1608.h @@ -267,7 +267,7 @@ } #endif // HAS_TEMPERATURE_SENSOR_1 -#define EXTRUDER_1_OUTPUT_PIN kOutput1_PinNumber +#define EXTRUDER_1_OUTPUT_PIN kHeaterOutput1_PinNumber #define EXTRUDER_1_FAN_PIN kOutput3_PinNumber #define HAS_TEMPERATURE_SENSOR_2 false @@ -282,7 +282,8 @@ } #endif // HAS_TEMPERATURE_SENSOR_2 -#define EXTRUDER_2_OUTPUT_PIN kOutput2_PinNumber +// Warning - the PrintrBoardG2 doesn't have a Output2 +#define EXTRUDER_2_OUTPUT_PIN kHeaterOutput2_PinNumber #define HAS_TEMPERATURE_SENSOR_3 false #if HAS_TEMPERATURE_SENSOR_3 @@ -296,7 +297,7 @@ } #endif // HAS_TEMPERATURE_SENSOR_3 -#define BED_OUTPUT_PIN kOutput11_PinNumber +#define BED_OUTPUT_PIN kHeaterOutput11_PinNumber //** Digital Inputs ** From 5c85583c95aeccbdf4e38bf32c8d15a93fcec533 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Sat, 2 Dec 2017 11:59:47 -0600 Subject: [PATCH 149/193] Readme updates (attempting to use details tag) --- README.md | 37 ++++++++++++++++++++++++++++++++----- 1 file changed, 32 insertions(+), 5 deletions(-) diff --git a/README.md b/README.md index f9ad55a7b..984e250b6 100644 --- a/README.md +++ b/README.md @@ -19,6 +19,7 @@ The fb:101 release is a mostly internal change from the fb:100 branches. Here ar - Added support for gQuintic (rev B) and fixed issues with gQuadratic board support. (This mostly happened in Motate.) - Temperature control enhancements. (Ongoing.) - More complete support for TMC2130 by adding more JSON controls for live feedback and configuration. +- Initial support for Core XY kinematics. ### Project Changes @@ -30,18 +31,28 @@ This build is primarily focused on support for the new boards based on the Atmel #### Functional Changes: -- **Linear-Velocity Segment Execution** +
Linear-Velocity Segment Execution + - The overall motion is still jerk-controlled and the computation of motion remains largely the same (although slightly simplified). At the smallest level above raw steps (what we call "segments," which are nominally 0.25ms to 1ms in duration) we previously executed the steps at a constant velocity. We now execute them with a linear change from a start velocity to an end velocity. This results in smoother motion that is more faithful to the planned jerk constraints. - This changed the way the forward differences are used to compute the segment speeds as well. Previously, we were computing the curve at the midpoint (time-wise) of each segment in order to get the median velocity. Now that we want the start and end velocity of each segment we only compute the end (time-wise) of each segment, and use that again later as the start-point of the next segment. -- **Probing enhancements** +
+ +
Probing enhancements + - Added `{"prbs":true}` to store the current position as if it were to position of a succesful probe. - Added `{"prbr":true}` to enable and `{"prbr":false}` to enable and disable (respectively) the JSON `{prb:{...}}` report after a probe. -- **gQuintic support** +
+ +
gQuintic support + - Support for the gQuintic rev B was added. Support for rev D will come shortly. -- **Temperature control enhancements** +
+ +
Temperature control enhancements + - Added the following settings defines: - `HAS_TEMPERATURE_SENSOR_1`, `HAS_TEMPERATURE_SENSOR_2`, and `HAS_TEMPERATURE_SENSOR_3` - `EXTRUDER_1_OUTPUT_PIN`, `EXTRUDER_2_OUTPUT_PIN`, and `BED_OUTPUT_PIN` @@ -49,7 +60,10 @@ This build is primarily focused on support for the new boards based on the Atmel - Defaults to `{kNormal, fet_pin3_freq}`. - `EXTRUDER_1_FAN_PIN` for control of the temperature-enabled fan on extruder 1. (Only available on extruder 1 at the moment.) -- **TMC2130 JSON controls** +
+ +
TMC2130 JSON controls + - Added the following setting keys to the motors (`1` - `6`): - `ts` - *(R)* get the value of the `TSTEP` register - `pth` - *(R/W)* get/set the value of the `TPWMTHRS` register @@ -69,3 +83,16 @@ This build is primarily focused on support for the new boards based on the Atmel - `sup` - *(R/W)* get/set the `seup` value of the `COOLCONF` register - `sdn` - *(R/W)* get/set the `sedn` value of the `COOLCONF` register - Note that all gets retrieve the last cached value. +
+ +
Core XY Kinematics Support + - Enabled at compile-time by setting the `KINEMATICS` define to `KINE_CORE_XY` + - The default (and only other valid value) for `KINEMATICS` is `KINE_CARTESIAN` + - Note that the X and Y axes must have the same settings, or the behavior is undefined. + - For the sake of motor mapping, the values `AXIS_COREXY_A` and `AXIS_COREXY_B` have been created. + - Example usage: + ```c++ + #define M1_MOTOR_MAP AXIS_COREXY_A // 1ma + #define M2_MOTOR_MAP AXIS_COREXY_B // 2ma + ``` +
From feb5c84aba37e3858bef0b8e80942ff96c07aa38 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Sat, 2 Dec 2017 12:00:51 -0600 Subject: [PATCH 150/193] Readme updates (attempting to use details tag) --- README.md | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/README.md b/README.md index 984e250b6..ce1a6b473 100644 --- a/README.md +++ b/README.md @@ -35,20 +35,17 @@ This build is primarily focused on support for the new boards based on the Atmel - The overall motion is still jerk-controlled and the computation of motion remains largely the same (although slightly simplified). At the smallest level above raw steps (what we call "segments," which are nominally 0.25ms to 1ms in duration) we previously executed the steps at a constant velocity. We now execute them with a linear change from a start velocity to an end velocity. This results in smoother motion that is more faithful to the planned jerk constraints. - This changed the way the forward differences are used to compute the segment speeds as well. Previously, we were computing the curve at the midpoint (time-wise) of each segment in order to get the median velocity. Now that we want the start and end velocity of each segment we only compute the end (time-wise) of each segment, and use that again later as the start-point of the next segment. -
Probing enhancements - Added `{"prbs":true}` to store the current position as if it were to position of a succesful probe. - Added `{"prbr":true}` to enable and `{"prbr":false}` to enable and disable (respectively) the JSON `{prb:{...}}` report after a probe. -
gQuintic support - Support for the gQuintic rev B was added. Support for rev D will come shortly. -
Temperature control enhancements @@ -59,7 +56,6 @@ This build is primarily focused on support for the new boards based on the Atmel - Added `BED_OUTPUT_INIT` in order to control configuration of the Bed output pin settings. - Defaults to `{kNormal, fet_pin3_freq}`. - `EXTRUDER_1_FAN_PIN` for control of the temperature-enabled fan on extruder 1. (Only available on extruder 1 at the moment.) -
TMC2130 JSON controls @@ -86,6 +82,7 @@ This build is primarily focused on support for the new boards based on the Atmel
Core XY Kinematics Support + - Enabled at compile-time by setting the `KINEMATICS` define to `KINE_CORE_XY` - The default (and only other valid value) for `KINEMATICS` is `KINE_CARTESIAN` - Note that the X and Y axes must have the same settings, or the behavior is undefined. From ef0839d1e0950797f7d5aae58e1813d74ec7de06 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Sat, 2 Dec 2017 12:15:37 -0600 Subject: [PATCH 151/193] More work on the ReadMe --- README.md | 22 ++++++++++++++++++++++ 1 file changed, 22 insertions(+) diff --git a/README.md b/README.md index ce1a6b473..f166122e5 100644 --- a/README.md +++ b/README.md @@ -20,6 +20,8 @@ The fb:101 release is a mostly internal change from the fb:100 branches. Here ar - Temperature control enhancements. (Ongoing.) - More complete support for TMC2130 by adding more JSON controls for live feedback and configuration. - Initial support for Core XY kinematics. +- Boards are in more control of the planner settings. +- Experimental setting to have traverse (G0) use the 'high jerk' axis settings. ### Project Changes @@ -93,3 +95,23 @@ This build is primarily focused on support for the new boards based on the Atmel #define M2_MOTOR_MAP AXIS_COREXY_B // 2ma ```
+ +
Planner settings control from board files + + - The defines `PLANNER_BUFFER_POOL_SIZE` and `MIN_SEGMENT_MS` are now set in the `board/*/hardware.h` files. + - `PLANNER_BUFFER_POOL_SIZE` sets the size of the planner buffer array. + - Default value if not defined: `48` + - `MIN_SEGMENT_MS` sets the minimum segment time (in milliseconds) and several other settings that are comuted based on it. + - Default values if not defined: `0.75` + - A few of the computed values are shown: + ```c++ + #define NOM_SEGMENT_MS ((float)MIN_SEGMENT_MS*2.0) // nominal segment ms (at LEAST MIN_SEGMENT_MS * 2) + #define MIN_BLOCK_MS ((float)MIN_SEGMENT_MS*2.0) // minimum block (whole move) milliseconds + ``` +
+ +
Planner settings control from board files + + - The new define `TRAVERSE_AT_HIGH_JERK` can be set to `true`, making traverse (`G0`) moves (including `E`-only moves in Marlin-flavored gcode mode) will use the jerk-high (`jh`) settings. + - If set to `false` or undefined `G0` moves will continue to use the jerk-max (`jm`) settings that feed (`G1`) moves use. +
From 187e24734fcc0816fa662d59b1d6107eded6ef59 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Sat, 2 Dec 2017 12:23:42 -0600 Subject: [PATCH 152/193] More work on the ReadMe --- README.md | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/README.md b/README.md index f166122e5..f7ec1ba20 100644 --- a/README.md +++ b/README.md @@ -58,6 +58,11 @@ This build is primarily focused on support for the new boards based on the Atmel - Added `BED_OUTPUT_INIT` in order to control configuration of the Bed output pin settings. - Defaults to `{kNormal, fet_pin3_freq}`. - `EXTRUDER_1_FAN_PIN` for control of the temperature-enabled fan on extruder 1. (Only available on extruder 1 at the moment.) + - (*Experimental*) Analog input is now interpreted through one of various `ADCCircuit` objects. + - Three are provided currently: `ADCCircuitSimplePullup`, `ADCCircuitDifferentialPullup`, `ADCCircuitRawResistance` + - `Thermistor` and `PT100` objects no longer take the pullup value in their constructor, but instead take a pointer to an `ADCCircuit` object. + - `Thermistor` and `PT100` objects no longer assume an `ADCPin` is used, but now take the type that conforms to the `ADCPin` interface as a template argument. + - **TODO:** Make more of these configurable at runtime. Separate the ADC input from the consumer, and allow other things than temperature to read it.
TMC2130 JSON controls @@ -110,7 +115,7 @@ This build is primarily focused on support for the new boards based on the Atmel ```
-
Planner settings control from board files +
Experimental traverse at high jerk - The new define `TRAVERSE_AT_HIGH_JERK` can be set to `true`, making traverse (`G0`) moves (including `E`-only moves in Marlin-flavored gcode mode) will use the jerk-high (`jh`) settings. - If set to `false` or undefined `G0` moves will continue to use the jerk-max (`jm`) settings that feed (`G1`) moves use. From 459f7c5c4342bf0e286b066a0caf135f40b3cdbd Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Sat, 2 Dec 2017 12:31:53 -0600 Subject: [PATCH 153/193] More work on the ReadMe --- README.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/README.md b/README.md index f7ec1ba20..5d65654d3 100644 --- a/README.md +++ b/README.md @@ -33,6 +33,8 @@ This build is primarily focused on support for the new boards based on the Atmel #### Functional Changes: +*Note: Click the header next to the arrow to expand and display the details.* +
Linear-Velocity Segment Execution - The overall motion is still jerk-controlled and the computation of motion remains largely the same (although slightly simplified). At the smallest level above raw steps (what we call "segments," which are nominally 0.25ms to 1ms in duration) we previously executed the steps at a constant velocity. We now execute them with a linear change from a start velocity to an end velocity. This results in smoother motion that is more faithful to the planned jerk constraints. From b70abe40673bcd2a3d9ecdefab00d878cd150f56 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Sun, 3 Dec 2017 16:10:22 -0600 Subject: [PATCH 154/193] Switched from `fabs` to `std::abs` which is type-aware and safer going forward. --- g2core/board/gquadratic/hardware.cpp | 4 ++-- g2core/canonical_machine.cpp | 4 ++-- g2core/cycle_homing.cpp | 10 +++++----- g2core/cycle_jogging.cpp | 2 +- g2core/device/neopixel/neopixel.h | 2 +- g2core/plan_arc.cpp | 14 +++++++------- g2core/plan_line.cpp | 12 ++++++------ g2core/plan_zoid.cpp | 10 +++++----- g2core/planner.h | 4 ++-- g2core/report.cpp | 2 +- g2core/stepper.cpp | 10 +++++----- g2core/temperature.cpp | 28 ++++++++++------------------ g2core/util.h | 12 ++++++------ 13 files changed, 53 insertions(+), 61 deletions(-) diff --git a/g2core/board/gquadratic/hardware.cpp b/g2core/board/gquadratic/hardware.cpp index 494a9dab4..d3674a2ee 100755 --- a/g2core/board/gquadratic/hardware.cpp +++ b/g2core/board/gquadratic/hardware.cpp @@ -99,13 +99,13 @@ stat_t hardware_periodic() { #if EXPERIMENTAL_NEOPIXEL_SUPPORT == 1 float x_pos = cm_get_work_position(ACTIVE_MODEL, AXIS_X); - if (fabs(LEDs::old_x_pos - x_pos) > 0.01) { + if (std::abs(LEDs::old_x_pos - x_pos) > 0.01) { LEDs::old_x_pos = x_pos; float led_pos = x_pos * ((float)(LEDs::rgbw_leds.count-1) / 40); for (uint8_t pixel = 0; pixel < LEDs::rgbw_leds.count; pixel++) { - float value = fabs(led_pos - (float)pixel); + float value = std::abs(led_pos - (float)pixel); if (value < 1.001) { value = 1.0 - value; if (LEDs::display_color[pixel].red < value) { diff --git a/g2core/canonical_machine.cpp b/g2core/canonical_machine.cpp index 63a783905..f78f11a87 100644 --- a/g2core/canonical_machine.cpp +++ b/g2core/canonical_machine.cpp @@ -718,8 +718,8 @@ stat_t cm_test_soft_limits(const float target[]) for (uint8_t axis = AXIS_X; axis < AXES; axis++) { if (cm.homed[axis] != true) { continue; } // skip axis if not homed if (fp_EQ(cm.a[axis].travel_min, cm.a[axis].travel_max)) { continue; } // skip axis if identical - if (fabs(cm.a[axis].travel_min) > DISABLE_SOFT_LIMIT) { continue; } // skip min test if disabled - if (fabs(cm.a[axis].travel_max) > DISABLE_SOFT_LIMIT) { continue; } // skip max test if disabled + if (std::abs(cm.a[axis].travel_min) > DISABLE_SOFT_LIMIT) { continue; } // skip min test if disabled + if (std::abs(cm.a[axis].travel_max) > DISABLE_SOFT_LIMIT) { continue; } // skip max test if disabled if (target[axis] < cm.a[axis].travel_min) { return (_finalize_soft_limits(STAT_SOFT_LIMIT_EXCEEDED_XMIN + 2*axis)); diff --git a/g2core/cycle_homing.cpp b/g2core/cycle_homing.cpp index 1f0051764..93c4d130c 100644 --- a/g2core/cycle_homing.cpp +++ b/g2core/cycle_homing.cpp @@ -235,7 +235,7 @@ static stat_t _homing_axis_start(int8_t axis) { } // calculate and test travel distance - float travel_distance = fabs(cm.a[axis].travel_max - cm.a[axis].travel_min) + cm.a[axis].latch_backoff; + float travel_distance = std::abs(cm.a[axis].travel_max - cm.a[axis].travel_min) + cm.a[axis].latch_backoff; if (fp_ZERO(travel_distance)) { return (_homing_error_exit(axis, STAT_HOMING_ERROR_TRAVEL_MIN_MAX_IDENTICAL)); } @@ -245,22 +245,22 @@ static stat_t _homing_axis_start(int8_t axis) { hm.homing_input = cm.a[axis].homing_input; gpio_set_homing_mode(hm.homing_input, true); hm.axis = axis; // persist the axis - hm.search_velocity = fabs(cm.a[axis].search_velocity); // search velocity is always positive - hm.latch_velocity = fabs(cm.a[axis].latch_velocity); // latch velocity is always positive + hm.search_velocity = std::abs(cm.a[axis].search_velocity); // search velocity is always positive + hm.latch_velocity = std::abs(cm.a[axis].latch_velocity); // latch velocity is always positive bool homing_to_max = cm.a[axis].homing_dir; // setup parameters for positive or negative travel (homing to the max or min switch) if (homing_to_max) { hm.search_travel = travel_distance; // search travels in positive direction - hm.latch_backoff = fabs(cm.a[axis].latch_backoff); // latch travels in positive direction + hm.latch_backoff = std::abs(cm.a[axis].latch_backoff); // latch travels in positive direction hm.zero_backoff = -max(0.0f, cm.a[axis].zero_backoff); // zero backoff is negative direction (or zero) // will set the maximum position // (plus any negative backoff) hm.setpoint = cm.a[axis].travel_max + (max(0.0f, -cm.a[axis].zero_backoff)); } else { hm.search_travel = -travel_distance; // search travels in negative direction - hm.latch_backoff = -fabs(cm.a[axis].latch_backoff); // latch travels in negative direction + hm.latch_backoff = -std::abs(cm.a[axis].latch_backoff); // latch travels in negative direction hm.zero_backoff = max(0.0f, cm.a[axis].zero_backoff); // zero backoff is positive direction (or zero) // will set the minimum position // (minus any negative backoff) diff --git a/g2core/cycle_jogging.cpp b/g2core/cycle_jogging.cpp index bd0b6da5f..a12263e32 100644 --- a/g2core/cycle_jogging.cpp +++ b/g2core/cycle_jogging.cpp @@ -153,7 +153,7 @@ static stat_t _jogging_axis_start(int8_t axis) { static stat_t _jogging_axis_ramp_jog(int8_t axis) // run the jog ramp { float direction = jog.start_pos <= jog.dest_pos ? 1. : -1.; - float delta = fabs(jog.dest_pos - jog.start_pos); + float delta = std::abs(jog.dest_pos - jog.start_pos); uint8_t last = 0; float velocity = diff --git a/g2core/device/neopixel/neopixel.h b/g2core/device/neopixel/neopixel.h index 4c69f8dcf..60836cae1 100755 --- a/g2core/device/neopixel/neopixel.h +++ b/g2core/device/neopixel/neopixel.h @@ -72,7 +72,7 @@ struct HSI_Color_t : NeopixelColorTag { float h_2 = h * h; // to_hue needs to be the closest transition - if (fabs(hue - to_hue) > fabs(hue - (360.0 + to_hue))) { + if (std::abs(hue - to_hue) > std::abs(hue - (360.0 + to_hue))) { to_hue += 360.0; } diff --git a/g2core/plan_arc.cpp b/g2core/plan_arc.cpp index 01756acce..3faeacb12 100644 --- a/g2core/plan_arc.cpp +++ b/g2core/plan_arc.cpp @@ -179,7 +179,7 @@ stat_t cm_arc_feed(const float target[], const bool target_f[], // target en // test radius arcs for radius tolerance if (radius_f) { arc.radius = _to_millimeters(radius); // set radius to internal format (mm) - if (fabs(arc.radius) < MIN_ARC_RADIUS) { // radius value must be > minimum radius + if (std::abs(arc.radius) < MIN_ARC_RADIUS) { // radius value must be > minimum radius return (STAT_ARC_RADIUS_OUT_OF_TOLERANCE); } } @@ -298,7 +298,7 @@ static stat_t _compute_arc(const bool radius_f) // Compute end radius from the center of circle (offsets) to target endpoint float end_0 = arc.gm.target[arc.plane_axis_0] - arc.position[arc.plane_axis_0] - arc.offset[arc.plane_axis_0]; float end_1 = arc.gm.target[arc.plane_axis_1] - arc.position[arc.plane_axis_1] - arc.offset[arc.plane_axis_1]; - float err = fabs(hypotf(end_0, end_1) - arc.radius); // end radius - start radius + float err = std::abs(hypotf(end_0, end_1) - arc.radius); // end radius - start radius if ((err > ARC_RADIUS_ERROR_MAX) || ((err > ARC_RADIUS_ERROR_MIN) && (err > arc.radius * ARC_RADIUS_TOLERANCE))) { return (STAT_ARC_HAS_IMPOSSIBLE_CENTER_POINT); @@ -338,7 +338,7 @@ static stat_t _compute_arc(const bool radius_f) // Length is the total mm of travel of the helix (or just the planar arc) arc.linear_travel = arc.gm.target[arc.linear_axis] - arc.position[arc.linear_axis]; arc.planar_travel = arc.angular_travel * arc.radius; - arc.length = hypotf(arc.planar_travel, fabs(arc.linear_travel)); + arc.length = hypotf(arc.planar_travel, std::abs(arc.linear_travel)); // Find the minimum number of segments that meet accuracy and time constraints... // Note: removed segment_length test as segment_time accounts for this (build 083.37) @@ -497,10 +497,10 @@ static float _estimate_arc_time (float arc_time) } // Downgrade the time if there is a rate-limiting axis - arc_time = max(arc_time, (float)fabs(arc.planar_travel/cm.a[arc.plane_axis_0].feedrate_max)); - arc_time = max(arc_time, (float)fabs(arc.planar_travel/cm.a[arc.plane_axis_1].feedrate_max)); - if (fabs(arc.linear_travel) > 0) { - arc_time = max(arc_time, (float)fabs(arc.linear_travel/cm.a[arc.linear_axis].feedrate_max)); + arc_time = max(arc_time, (float)std::abs(arc.planar_travel/cm.a[arc.plane_axis_0].feedrate_max)); + arc_time = max(arc_time, (float)std::abs(arc.planar_travel/cm.a[arc.plane_axis_1].feedrate_max)); + if (std::abs(arc.linear_travel) > 0) { + arc_time = max(arc_time, (float)std::abs(arc.linear_travel/cm.a[arc.linear_axis].feedrate_max)); } return (arc_time); } diff --git a/g2core/plan_line.cpp b/g2core/plan_line.cpp index 405a6b4e5..0a8c3cfb7 100644 --- a/g2core/plan_line.cpp +++ b/g2core/plan_line.cpp @@ -530,10 +530,10 @@ static void _calculate_jerk(mpBuf_t* bf) float jerk = 0; for (uint8_t axis = 0; axis < AXES; axis++) { - if (fabs(bf->unit[axis]) > 0) { // if this axis is participating in the move + if (std::abs(bf->unit[axis]) > 0) { // if this axis is participating in the move float axis_jerk = _get_axis_jerk(bf, axis); - jerk = axis_jerk / fabs(bf->unit[axis]); + jerk = axis_jerk / std::abs(bf->unit[axis]); if (jerk < bf->jerk) { bf->jerk = jerk; // bf->jerk_axis = axis; // +++ diagnostic @@ -636,9 +636,9 @@ static void _calculate_vmaxes(mpBuf_t* bf, const float axis_length[], const floa for (uint8_t axis = AXIS_X; axis < AXES; axis++) { if (bf->axis_flags[axis]) { if (bf->gm.motion_mode == MOTION_MODE_STRAIGHT_TRAVERSE) { - tmp_time = fabs(axis_length[axis]) / cm.a[axis].velocity_max; + tmp_time = std::abs(axis_length[axis]) / cm.a[axis].velocity_max; } else { // gm.motion_mode == MOTION_MODE_STRAIGHT_FEED - tmp_time = fabs(axis_length[axis]) / cm.a[axis].feedrate_max; + tmp_time = std::abs(axis_length[axis]) / cm.a[axis].feedrate_max; } max_time = max(max_time, tmp_time); @@ -733,11 +733,11 @@ static void _calculate_junction_vmax(mpBuf_t* bf) for (uint8_t axis = 0; axis < AXES; axis++) { if (bf->axis_flags[axis] || bf->nx->axis_flags[axis]) { // (A) skip axes with no movement - float delta = fabs(bf->unit[axis] - bf->nx->unit[axis]); // formula (1) + float delta = std::abs(bf->unit[axis] - bf->nx->unit[axis]); // formula (1) if (using_junction_unit) { // (B) special case // use the highest delta of the two - delta = std::max(delta, fabs(bf->junction_unit[axis] - bf->nx->unit[axis])); // formula (1) + delta = std::max(delta, std::abs(bf->junction_unit[axis] - bf->nx->unit[axis])); // formula (1) // push the junction_unit for this axis into the next block, for future (B) cases bf->nx->junction_unit[axis] = bf->junction_unit[axis]; diff --git a/g2core/plan_zoid.cpp b/g2core/plan_zoid.cpp index e3d7ab6ed..8bfe902aa 100644 --- a/g2core/plan_zoid.cpp +++ b/g2core/plan_zoid.cpp @@ -375,7 +375,7 @@ void mp_calculate_ramps(mpBlockRuntimeBuf_t* block, mpBuf_t* bf, const float ent float mp_get_target_length(const float v_0, const float v_1, const mpBuf_t* bf) { const float q_recip_2_sqrt_j = bf->q_recip_2_sqrt_j; - return q_recip_2_sqrt_j * sqrt(fabs(v_1 - v_0)) * (v_1 + v_0); + return q_recip_2_sqrt_j * sqrt(std::abs(v_1 - v_0)) * (v_1 + v_0); } /* @@ -417,7 +417,7 @@ float mp_get_target_velocity(const float v_0, const float L, const mpBuf_t* bf) // v_1 = 1/3 ((const1a v_0^2)/b + b const2a - v_0) const float v_1 = const3 * ((const1a * v_0_2) / b + b * const2a - v_0); - return fabs(v_1); + return std::abs(v_1); } @@ -447,7 +447,7 @@ float mp_get_decel_velocity(const float v_0, const float L, const mpBuf_t* bf) const float sqrt_delta_v_0 = sqrt(v_0 - v_1); const float l_t = q_recip_2_sqrt_j * (sqrt_delta_v_0 * (v_1 + v_0)) - L; - if (fabs(l_t) < 0.00001) { + if (std::abs(l_t) < 0.00001) { break; } // For the first pass, we tested velocity 0. @@ -548,8 +548,8 @@ static float _get_meet_velocity(const float v_0, } // Precompute some common chunks -- note that some attempts may have v_1 < v_0 or v_1 < v_2 - const float sqrt_delta_v_0 = sqrt(fabs(v_1 - v_0)); - const float sqrt_delta_v_2 = sqrt(fabs(v_1 - v_2)); // 849us + const float sqrt_delta_v_0 = sqrt(std::abs(v_1 - v_0)); + const float sqrt_delta_v_2 = sqrt(std::abs(v_1 - v_2)); // 849us // l_c is our total-length calculation with the current v_1 estimate, minus the expected length. // This makes l_c == 0 when v_1 is the correct value. diff --git a/g2core/planner.h b/g2core/planner.h index 6dc30ce51..e097b79f2 100644 --- a/g2core/planner.h +++ b/g2core/planner.h @@ -283,13 +283,13 @@ typedef enum { //// RG: Simulation shows +-0.001 is about as much as we should allow. // VELOCITY_EQ(v0,v1) reads: "True if v0 is within 0.0001 of v1" // VELOCITY_LT(v0,v1) reads: "True if v0 is less than v1 by at least 0.0001" -#define VELOCITY_EQ(v0,v1) ( fabs(v0-v1) < 0.0001 ) +#define VELOCITY_EQ(v0,v1) ( std::abs(v0-v1) < 0.0001 ) #define VELOCITY_LT(v0,v1) ( (v1 - v0) > 0.0001 ) #define Vthr2 300.0 #define Veq2_hi 10.0 #define Veq2_lo 1.0 -#define VELOCITY_ROUGHLY_EQ(v0,v1) ( (v0 > Vthr2) ? fabs(v0-v1) < Veq2_hi : fabs(v0-v1) < Veq2_lo ) +#define VELOCITY_ROUGHLY_EQ(v0,v1) ( (v0 > Vthr2) ? std::abs(v0-v1) < Veq2_hi : std::abs(v0-v1) < Veq2_lo ) //#define ASCII_ART(s) xio_writeline(s) #define ASCII_ART(s) diff --git a/g2core/report.cpp b/g2core/report.cpp index c4e667ac2..d9e39d0cd 100644 --- a/g2core/report.cpp +++ b/g2core/report.cpp @@ -388,7 +388,7 @@ static uint8_t _populate_filtered_status_report() nv_get_nvObj(nv); // report values that have changed by more than 0.0001, but always stops and ends - if ((fabs(nv->value - sr.status_report_value[i]) > EPSILON3) || + if ((std::abs(nv->value - sr.status_report_value[i]) > EPSILON3) || ((nv->index == sr.stat_index) && fp_EQ(nv->value, COMBINED_PROGRAM_STOP)) || ((nv->index == sr.stat_index) && fp_EQ(nv->value, COMBINED_PROGRAM_END))) { diff --git a/g2core/stepper.cpp b/g2core/stepper.cpp index d934ff761..8658ab258 100644 --- a/g2core/stepper.cpp +++ b/g2core/stepper.cpp @@ -709,15 +709,15 @@ stat_t st_prep_line(float start_velocity, float end_velocity, float travel_steps // 'Nudge' correction strategy. Inject a single, scaled correction value then hold off // NOTE: This clause can be commented out to test for numerical accuracy and accumulating errors if ((--st_pre.mot[motor].correction_holdoff < 0) && - (fabs(following_error[motor]) > STEP_CORRECTION_THRESHOLD)) { + (std::abs(following_error[motor]) > STEP_CORRECTION_THRESHOLD)) { st_pre.mot[motor].correction_holdoff = STEP_CORRECTION_HOLDOFF; correction_steps = following_error[motor] * STEP_CORRECTION_FACTOR; if (correction_steps > 0) { - correction_steps = std::min(std::min(correction_steps, fabs(travel_steps[motor])), STEP_CORRECTION_MAX); + correction_steps = std::min(std::min(correction_steps, std::abs(travel_steps[motor])), STEP_CORRECTION_MAX); } else { - correction_steps = std::max(std::max(correction_steps, -fabs(travel_steps[motor])), -STEP_CORRECTION_MAX); + correction_steps = std::max(std::max(correction_steps, -std::abs(travel_steps[motor])), -STEP_CORRECTION_MAX); } st_pre.mot[motor].corrected_steps += correction_steps; travel_steps[motor] -= correction_steps; @@ -726,7 +726,7 @@ stat_t st_prep_line(float start_velocity, float end_velocity, float travel_steps // Compute substeb increment. The accumulator must be *exactly* the incoming // fractional steps times the substep multiplier or positional drift will occur. // Rounding is performed to eliminate a negative bias in the uint32 conversion - // that results in long-term negative drift. (fabs/round order doesn't matter) + // that results in long-term negative drift. (std::abs/round order doesn't matter) // t is ticks duration of the move // T is time duration of the move in minutes @@ -757,7 +757,7 @@ stat_t st_prep_line(float start_velocity, float end_velocity, float travel_steps // option 2: // d = (b (v_1 - v_0))/((t-1) a) - double s_double = fabs(travel_steps[motor] * 2.0); + double s_double = std::abs(travel_steps[motor] * 2.0); // 1/m_0 = (2 s v_0)/(t (v_0 + v_1)) st_pre.mot[motor].substep_increment = round(((s_double * start_velocity)/(t_v0_v1)) * (double)DDA_SUBSTEPS); diff --git a/g2core/temperature.cpp b/g2core/temperature.cpp index cc588029d..3ca79ea40 100755 --- a/g2core/temperature.cpp +++ b/g2core/temperature.cpp @@ -199,7 +199,7 @@ struct ValueHistory { float get_std_dev() { // Important note: this is a POPULATION standard deviation, not a population standard deviation float variance = (rolling_sum_sq/(float)sampled) - (rolling_mean*rolling_mean); - return sqrt(fabs(variance)); + return sqrt(std::abs(variance)); }; float value() { @@ -209,7 +209,7 @@ struct ValueHistory { float std_dev = get_std_dev(); for (uint16_t i=0; i 0) { - e = e*e; - } else { - e = -(e*e); - } + e = std::abs(e)*e; // P = Proportional @@ -760,11 +756,7 @@ struct PID { float d = _derivative * _d_factor; _feed_forward = (_set_point-21); // 21 is for a roughly ideal room temperature - if (_feed_forward > 0) { - _feed_forward = _feed_forward*_feed_forward; - } else { - _feed_forward = -(_feed_forward*_feed_forward); - } + _feed_forward = std::abs(_feed_forward)*_feed_forward; float f = _f_factor * _feed_forward; @@ -934,7 +926,7 @@ stat_t temperature_callback() float out1 = pid1.getNewOutput(temp); fet_pin1.write(out1); - if (fabs(temp - last_reported_temp1) > kTempDiffSRTrigger) { + if (std::abs(temp - last_reported_temp1) > kTempDiffSRTrigger) { last_reported_temp1 = temp; sr_requested = true; } @@ -946,7 +938,7 @@ stat_t temperature_callback() float out2 = pid2.getNewOutput(temp); fet_pin2.write(out2); - if (fabs(temp - last_reported_temp2) > kTempDiffSRTrigger) { + if (std::abs(temp - last_reported_temp2) > kTempDiffSRTrigger) { last_reported_temp2 = temp; sr_requested = true; } @@ -960,7 +952,7 @@ stat_t temperature_callback() float out3 = pid3.getNewOutput(temp); fet_pin3.write(out3); - if (fabs(temp - last_reported_temp3) > kTempDiffSRTrigger) { + if (std::abs(temp - last_reported_temp3) > kTempDiffSRTrigger) { last_reported_temp3 = temp; sr_requested = true; } diff --git a/g2core/util.h b/g2core/util.h index a7322beb4..b9839d0fe 100644 --- a/g2core/util.h +++ b/g2core/util.h @@ -113,7 +113,7 @@ using std::max; template inline T square(const T x) { return (x)*(x); } /* UNSAFE */ -//inline float abs(const float a) { return fabs(a); } +//inline float abs(const float a) { return std::abs(a); } #ifndef avg template @@ -129,19 +129,19 @@ inline T avg(const T a,const T b) {return (a+b)/2; } // These functions all require math.h to be included in each file that uses them #ifndef fp_EQ -#define fp_EQ(a,b) (fabs(a-b) < EPSILON) +#define fp_EQ(a,b) (std::abs(a-b) < EPSILON) #endif #ifndef fp_NE -#define fp_NE(a,b) (fabs(a-b) > EPSILON) +#define fp_NE(a,b) (std::abs(a-b) > EPSILON) #endif #ifndef fp_GE -#define fp_GE(a,b) (fabs(a-b) < EPSILON || a-b > EPSILON) +#define fp_GE(a,b) (std::abs(a-b) < EPSILON || a-b > EPSILON) #endif #ifndef fp_ZERO -#define fp_ZERO(a) (fabs(a) < EPSILON) +#define fp_ZERO(a) (std::abs(a) < EPSILON) #endif #ifndef fp_NOT_ZERO -#define fp_NOT_ZERO(a) (fabs(a) > EPSILON) +#define fp_NOT_ZERO(a) (std::abs(a) > EPSILON) #endif #ifndef fp_FALSE #define fp_FALSE(a) (a < EPSILON) From d36049f671b22ffd9f32e56e41cb692e65455fe2 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Sun, 3 Dec 2017 16:54:06 -0600 Subject: [PATCH 155/193] More work on the ReadMe --- README.md | 29 +++++++++++++++++++++-------- 1 file changed, 21 insertions(+), 8 deletions(-) diff --git a/README.md b/README.md index 5d65654d3..b47bfcb0f 100644 --- a/README.md +++ b/README.md @@ -12,16 +12,19 @@ That said, Edge is for the adventurous. It is not guaranteed to be stable, but w ## Firmware Build 101 `{fb:101.xx}` ### Feature Enhancements -The fb:101 release is a mostly internal change from the fb:100 branches. Here are the highlights, more detailed changelog below: -- Updated JT (Junction integration Time, a.k.a. "cornering") handling to be more optimized, and to treat the last move as a corner to a move with no active axes. This allows a non-zero stopping velocity based on the allowed jerk and active JT value. +The fb:101 release is a mostly internal change from the fb:100 branches. Here are the highlights, more detailed on each item are further below: - Updated motion execution at the segment (smallest) level to be linear velocity instead of constant velocity, resulting in notably smoother motion and more faithful execution of the jerk limitations. (Incidentally, the sound of the motors is also slightly quieter and more "natural.") +- Updated JT (Junction integration Time, a.k.a. "cornering") handling to be more optimized, and to treat the last move as a corner to a move with no active axes. This allows a non-zero stopping velocity based on the allowed jerk and active JT value. - Probing enhancements. - Added support for gQuintic (rev B) and fixed issues with gQuadratic board support. (This mostly happened in Motate.) -- Temperature control enhancements. (Ongoing.) +- Temperature control enhancements + - Temperature inputs are configured differently at compile time. (Ongoing.) + - PID control has been adjusted to PID+FF (Proportional, Integral, and Derivative, with Feed Forward). In this case, the feed forward is a multiplier of the difference between the current temperature and the ambient temperature. Since there is no temperature sensor for ambient temperature at the moment, it uses an idealized room temperature of 21ºC. - More complete support for TMC2130 by adding more JSON controls for live feedback and configuration. - Initial support for Core XY kinematics. - Boards are in more control of the planner settings. - Experimental setting to have traverse (G0) use the 'high jerk' axis settings. +- Outputs are now configured at board initialization (and later) to honor the settings more faithfully. This includes setting the pin high or low as soon as possible. ### Project Changes @@ -55,16 +58,20 @@ This build is primarily focused on support for the new boards based on the Atmel
Temperature control enhancements - Added the following settings defines: - - `HAS_TEMPERATURE_SENSOR_1`, `HAS_TEMPERATURE_SENSOR_2`, and `HAS_TEMPERATURE_SENSOR_3` - - `EXTRUDER_1_OUTPUT_PIN`, `EXTRUDER_2_OUTPUT_PIN`, and `BED_OUTPUT_PIN` - - Added `BED_OUTPUT_INIT` in order to control configuration of the Bed output pin settings. - - Defaults to `{kNormal, fet_pin3_freq}`. - - `EXTRUDER_1_FAN_PIN` for control of the temperature-enabled fan on extruder 1. (Only available on extruder 1 at the moment.) + - `HAS_TEMPERATURE_SENSOR_1`, `HAS_TEMPERATURE_SENSOR_2`, and `HAS_TEMPERATURE_SENSOR_3` + - `EXTRUDER_1_OUTPUT_PIN`, `EXTRUDER_2_OUTPUT_PIN`, and `BED_OUTPUT_PIN` + - Added `BED_OUTPUT_INIT` in order to control configuration of the Bed output pin settings. + - Defaults to `{kNormal, fet_pin3_freq}`. + - `EXTRUDER_1_FAN_PIN` for control of the temperature-enabled fan on extruder 1. (Only available on extruder 1 at the moment.) - (*Experimental*) Analog input is now interpreted through one of various `ADCCircuit` objects. - Three are provided currently: `ADCCircuitSimplePullup`, `ADCCircuitDifferentialPullup`, `ADCCircuitRawResistance` - `Thermistor` and `PT100` objects no longer take the pullup value in their constructor, but instead take a pointer to an `ADCCircuit` object. - `Thermistor` and `PT100` objects no longer assume an `ADCPin` is used, but now take the type that conforms to the `ADCPin` interface as a template argument. - **TODO:** Make more of these configurable at runtime. Separate the ADC input from the consumer, and allow other things than temperature to read it. + - PID+FF control adds feed-forward (FF) to adjust the output to a reasonable minimum based on heat loss dues to room temperature. + - This can be effectively disabled, making the controller a PID controller, by setting the F value to `0.0`. + - **Warning** setting this value too high can cause thermal runaway. Set this value conservatively (low), since there's currently no ambient temperature, and the actual heat loss may be less than computed. This will be magnified by another heater (such as that on a heat bed of a 3D printer) in close proximity. +
TMC2130 JSON controls @@ -122,3 +129,9 @@ This build is primarily focused on support for the new boards based on the Atmel - The new define `TRAVERSE_AT_HIGH_JERK` can be set to `true`, making traverse (`G0`) moves (including `E`-only moves in Marlin-flavored gcode mode) will use the jerk-high (`jh`) settings. - If set to `false` or undefined `G0` moves will continue to use the jerk-max (`jm`) settings that feed (`G1`) moves use.
+ +
Output setting as soon as possible + + - At board initialization, the output value on each of the `out` objects is set to whatever the pin is configured to be "inactive." This is based on the settings file `DO`*n*`_MODE` setting. + - For example, if `DO10_MODE == IO_ACTIVE_LOW` then the pin at `DO10` is initialized as `HIGH` at board setup. This happen even before the `main()` function starts, shortly after the GPIO clocks are enabled for each port. +
From 25932d59130beb147cf74030ad420bf84c55de33 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Sun, 3 Dec 2017 17:00:52 -0600 Subject: [PATCH 156/193] More work on the ReadMe --- README.md | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/README.md b/README.md index b47bfcb0f..f2b2bef0d 100644 --- a/README.md +++ b/README.md @@ -130,6 +130,15 @@ This build is primarily focused on support for the new boards based on the Atmel - If set to `false` or undefined `G0` moves will continue to use the jerk-max (`jm`) settings that feed (`G1`) moves use.
+
PID+FF - added feed forward + + - There is a new JSON value `f` in each `pid`*`n`* object (read-only, for reporting) as well as an `f` setting in the `he`*`n`* objects (for control). + - This is a value that is multiplied to by current temp - 21 and added to the current computed output. + - **Warning!** Setting this value too high can result in thermal runaway. Set it conservatively (low) or disable it completely if in doubt. + - Set the `he`*`n`*`f` value to `0.0` to effectively disable feed-forward. + +
+
Output setting as soon as possible - At board initialization, the output value on each of the `out` objects is set to whatever the pin is configured to be "inactive." This is based on the settings file `DO`*n*`_MODE` setting. From 16482dcfc3511d858cd0b76692d591231585c934 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Sun, 3 Dec 2017 17:02:39 -0600 Subject: [PATCH 157/193] More work on the ReadMe --- README.md | 1 + 1 file changed, 1 insertion(+) diff --git a/README.md b/README.md index f2b2bef0d..bb96f933a 100644 --- a/README.md +++ b/README.md @@ -133,6 +133,7 @@ This build is primarily focused on support for the new boards based on the Atmel
PID+FF - added feed forward - There is a new JSON value `f` in each `pid`*`n`* object (read-only, for reporting) as well as an `f` setting in the `he`*`n`* objects (for control). + - This is controlled in the settings file via `H`*`n`*`_DEFAULT_F`, such as `H1_DEFAULT_F`. Default value is `0.0`. - This is a value that is multiplied to by current temp - 21 and added to the current computed output. - **Warning!** Setting this value too high can result in thermal runaway. Set it conservatively (low) or disable it completely if in doubt. - Set the `he`*`n`*`f` value to `0.0` to effectively disable feed-forward. From a68e81b7a3ac5f5e3e9c2d9c291585229d7cb157 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Tue, 5 Dec 2017 11:53:00 -0600 Subject: [PATCH 158/193] Initial support for gQuintic rev D --- g2core/board/gquintic.mk | 6 + g2core/board/gquintic/gquintic-d-pinout.h | 215 ++++++++++++++++++ .../board/gquintic/motate_pin_assignments.h | 7 + g2core/boards.mk | 2 +- 4 files changed, 229 insertions(+), 1 deletion(-) create mode 100755 g2core/board/gquintic/gquintic-d-pinout.h diff --git a/g2core/board/gquintic.mk b/g2core/board/gquintic.mk index c5dfd5ec5..3c5f8d622 100755 --- a/g2core/board/gquintic.mk +++ b/g2core/board/gquintic.mk @@ -24,6 +24,12 @@ ifeq ("$(BOARD)","gquintic-c") DEVICE_DEFINES += SETTINGS_FILE=${SETTINGS_FILE} endif +ifeq ("$(BOARD)","gquintic-d") +BASE_BOARD=gquintic +DEVICE_DEFINES += MOTATE_BOARD="gquintic-d" +DEVICE_DEFINES += SETTINGS_FILE=${SETTINGS_FILE} +endif + ########## # The general gquintic BASE_BOARD. diff --git a/g2core/board/gquintic/gquintic-d-pinout.h b/g2core/board/gquintic/gquintic-d-pinout.h new file mode 100755 index 000000000..72180b124 --- /dev/null +++ b/g2core/board/gquintic/gquintic-d-pinout.h @@ -0,0 +1,215 @@ +/* + * gquintic-c-pinout.h - board pinout specification + * This file is part of the g2core project + * + * Copyright (c) 2017 Robert Giseburt + * Copyright (c) 2017 Alden S. Hart Jr. + * + * This file is part of the Motate Library. + * + * This file ("the software") is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License, version 2 as published by the + * Free Software Foundation. You should have received a copy of the GNU General Public + * License, version 2 along with the software. If not, see . + * + * As a special exception, you may use this file as part of a software library without + * restriction. Specifically, if other files instantiate templates or use macros or + * inline functions from this file, or you compile this file and link it with other + * files to produce an executable, this file does not by itself cause the resulting + * executable to be covered by the GNU General Public License. This exception does not + * however invalidate any other reasons why the executable file might be covered by the + * GNU General Public License. + * + * THE SOFTWARE IS DISTRIBUTED IN THE HOPE THAT IT WILL BE USEFUL, BUT WITHOUT ANY + * WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES + * OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT + * SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF + * OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + * + */ + +#ifndef gquintic_a_pinout_h +#define gquintic_a_pinout_h + +/* + * USAGE NOTES + * + * Read this first: + * https://github.com/synthetos/g2/wiki/Adding-and-Revising-Boards + * + * USAGE: + * + * This file is lays out all the pin capabilities of the SAM3X8C organized by pin number. + * Each pin has its associated functions listed at the bottom of the file, and is essentially + * immutable for each processor. + * + * To use, assign Motate pin numbers to the first value in the _MAKE_MOTATE_PIN() macro. + * ALL PINS MUST BE ASSIGNED A NUMBER, even if they are not used. There will NOT be a + * code-size or speed penalty for unused pins, but the WILL be a compiler-failure for + * unassigned pins. This new restriction allows for simplification of linkages deep in + * Motate. + */ +/* See motate_pin_assignments.h for pin names to be used int he rest of the G2 code. + * EXAMPLES: + * + * *** Vanilla pin example *** + * + * _MAKE_MOTATE_PIN(4, A, 'A', 27); // SPI0_SCKPinNumber + * + * This assigns Motate pin 4 to Port A, pin 27 (A27) + * Look in motate_pin_assignments.h to see that this is kSPI_SCKPinNumber + * + * ** Other pin functions *** + * + * Please look in /platform/atmel_sam/motate_chip_pin_functions.h + */ + + +#include + +// We don't have all of the inputs, so we have to indicate as much: +#define INPUT1_AVAILABLE 1 +#define INPUT2_AVAILABLE 1 +#define INPUT3_AVAILABLE 1 +#define INPUT4_AVAILABLE 1 +#define INPUT5_AVAILABLE 1 +#define INPUT6_AVAILABLE 1 +#define INPUT7_AVAILABLE 1 +#define INPUT8_AVAILABLE 1 +#define INPUT9_AVAILABLE 1 +#define INPUT10_AVAILABLE 1 +#define INPUT11_AVAILABLE 0 +#define INPUT12_AVAILABLE 0 +#define INPUT13_AVAILABLE 0 + +#define XIO_HAS_USB 1 +#define XIO_HAS_UART 1 +#define XIO_HAS_SPI 0 +#define XIO_HAS_I2C 0 + +#define TEMPERATURE_OUTPUT_ON 1 // NO ADC yet + +// Some pins, if the PWM capability is turned on, it will cause timer conflicts. +// So we have to explicitly enable them as PWM pins. +// Generated with: +// perl -e 'for($i=1;$i<14;$i++) { print "#define OUTPUT${i}_PWM 0\n";}' +//#define OUTPUT1_PWM 1 // TC 0,1 - Fet 1 +//#define OUTPUT2_PWM 1 // PWM 0,1 - Fet 2 +#define OUTPUT1_PWM 0 // Used by EX1 +#define OUTPUT2_PWM 0 // Used by EX2 +#define OUTPUT3_PWM 1 // TC 1,0 - Fan 1 +#define OUTPUT4_PWM 1 // TC 1,1 - Fan 2 +#define OUTPUT5_PWM 1 // TC 2,0 - Fan 3 +#define OUTPUT6_PWM 1 // PWM 1,0 +#define OUTPUT7_PWM 1 // PWM 0,3 +#define OUTPUT8_PWM 1 // PWM 0,2 +#define OUTPUT9_PWM 0 // PWM 0,2 +#define OUTPUT10_PWM 1 // PWM 1,2 +#define OUTPUT11_PWM 0 // Used by Heatbed +//#define OUTPUT11_PWM 1 // PWM 1,3 - Fet 3 +#define OUTPUT12_PWM 0 // Unused +#define OUTPUT13_PWM 0 // Unused + +namespace Motate { + +// Unused: +// +// +// +// +// + +_MAKE_MOTATE_PIN(kLED_RGBWPixelPinNumber, 'A', 0); // +_MAKE_MOTATE_PIN(kHeaterOutput1_PinNumber, 'A', 1); // TC 0,1 +_MAKE_MOTATE_PIN(kHeaterOutput2_PinNumber, 'A', 2); // PWM 0,1 +_MAKE_MOTATE_PIN(kI2C1_SDAPinNumber, 'A', 3); // +_MAKE_MOTATE_PIN(kI2C1_SCLPinNumber, 'A', 4); // +_MAKE_MOTATE_PIN(kHeaterOutput11_PinNumber, 'A', 5); // PWM 1,3 +_MAKE_MOTATE_PIN(kExternalClock1_PinNumber, 'A', 6); // CPU_CLK +_MAKE_MOTATE_PIN(kOutput7_PinNumber, 'A', 7); // PWM 0,3 +_MAKE_MOTATE_PIN(kSerial_RTSPinNumber, 'A', 8); // +_MAKE_MOTATE_PIN(kSerial_RXPinNumber, 'A', 9); // +_MAKE_MOTATE_PIN(kSerial_TXPinNumber, 'A', 10); // +_MAKE_MOTATE_PIN(kSocket2_EnablePinNumber, 'A', 11); // +_MAKE_MOTATE_PIN(kOutput6_PinNumber, 'A', 12); // PWM 1,0 +_MAKE_MOTATE_PIN(kOutput8_PinNumber, 'A', 13); // PWM 0,2 +_MAKE_MOTATE_PIN(kSocket1_StepPinNumber, 'A', 14); // +_MAKE_MOTATE_PIN(kOutput3_PinNumber, 'A', 15); // TC 1,0 +_MAKE_MOTATE_PIN(kOutput4_PinNumber, 'A', 16); // TC 1,1 +_MAKE_MOTATE_PIN(kADC4_PinNumber, 'A', 17); // AFEC0,6 +_MAKE_MOTATE_PIN(kADC3_PinNumber, 'A', 18); // AFEC0,7 +_MAKE_MOTATE_PIN(kADC2_PinNumber, 'A', 19); // AFEC0,8 +_MAKE_MOTATE_PIN(kADC1_PinNumber, 'A', 20); // AFEC0,9 +_MAKE_MOTATE_PIN(kUnassigned1, 'A', 21); // AFEC0,1 +_MAKE_MOTATE_PIN(kSocket1_EnablePinNumber, 'A', 22); // +//_MAKE_MOTATE_PIN(kOutput10_PinNumber, 'A', 23); // PWM 1,2 +_MAKE_MOTATE_PIN(kServo1_PinNumber, 'A', 23); // +_MAKE_MOTATE_PIN(kSocket3_EnablePinNumber, 'A', 24); // +_MAKE_MOTATE_PIN(kSocket2_DirPinNumber, 'A', 25); // +_MAKE_MOTATE_PIN(kOutput5_PinNumber, 'A', 26); // TC 2,0 +_MAKE_MOTATE_PIN(kSocket3_DirPinNumber, 'A', 27); // On Timer 2! +_MAKE_MOTATE_PIN(kUnassigned2, 'A', 28); // DIAG1 +_MAKE_MOTATE_PIN(kUnassigned3, 'A', 29); // NO PHYSICAL PIN +_MAKE_MOTATE_PIN(kInput1_PinNumber, 'A', 30); // +_MAKE_MOTATE_PIN(kInput4_PinNumber, 'A', 31); // + +_MAKE_MOTATE_PIN(kSerial_CTSPinNumber, 'B', 0); // +_MAKE_MOTATE_PIN(kUnassigned9, 'B', 1); // AFEC1,0 +_MAKE_MOTATE_PIN(kSocket1_SPISlaveSelectPinNumber, 'B', 2); // +_MAKE_MOTATE_PIN(kOutputSAFE_PinNumber, 'B', 3); // +//_MAKE_MOTATE_PIN( , 'B', 4); // TDI +//_MAKE_MOTATE_PIN( , 'B', 5); // TRACESDO +//_MAKE_MOTATE_PIN( , 'B', 6); // SWDIO +//_MAKE_MOTATE_PIN( , 'B', 7); // SWDCLK +//_MAKE_MOTATE_PIN( , 'B', 8); // XOUT +//_MAKE_MOTATE_PIN( , 'B', 9); // XIN +//_MAKE_MOTATE_PIN( , 'B', 10); // USB_D- +//_MAKE_MOTATE_PIN( , 'B', 11); // USB_D+ +//_MAKE_MOTATE_PIN( , 'B', 12); // ERASE +_MAKE_MOTATE_PIN(kLED_USBRXPinNumber, 'B', 13); // LED_1 (Heartbeat) - PWM2 +_MAKE_MOTATE_PIN(kUnassigned6, 'B', 14); // NOT CONNECTED + + +//_MAKE_MOTATE_PIN( 'D', 0); // USB_VBUS +_MAKE_MOTATE_PIN(kInput9_PinNumber, 'D', 1); // +_MAKE_MOTATE_PIN(kInput10_PinNumber, 'D', 2); // +_MAKE_MOTATE_PIN(kInput8_PinNumber, 'D', 3); // +_MAKE_MOTATE_PIN(kInput7_PinNumber, 'D', 4); // +_MAKE_MOTATE_PIN(kInput6_PinNumber, 'D', 5); // +_MAKE_MOTATE_PIN(kInput5_PinNumber, 'D', 6); // +_MAKE_MOTATE_PIN(kInput3_PinNumber, 'D', 7); // +_MAKE_MOTATE_PIN(kInput2_PinNumber, 'D', 8); // ] +_MAKE_MOTATE_PIN(kTMC2130_DIAG0_pinNumber, 'D', 9); // DIAG0 +_MAKE_MOTATE_PIN(kUnassigned4, 'D', 10); // +_MAKE_MOTATE_PIN(kSocket5_StepPinNumber, 'D', 11); // +_MAKE_MOTATE_PIN(kSocket3_SPISlaveSelectPinNumber, 'D', 12); // +_MAKE_MOTATE_PIN(kSocket5_DirPinNumber, 'D', 13); // +_MAKE_MOTATE_PIN(kSocket5_EnablePinNumber, 'D', 14); // +_MAKE_MOTATE_PIN(kUnassigned5, 'D', 15); // +_MAKE_MOTATE_PIN(kSocket4_StepPinNumber, 'D', 16); // +_MAKE_MOTATE_PIN(kSocket4_DirPinNumber, 'D', 17); // +_MAKE_MOTATE_PIN(kSocket3_StepPinNumber, 'D', 18); // +_MAKE_MOTATE_PIN(kSocket1_DirPinNumber, 'D', 19); // +_MAKE_MOTATE_PIN(kSPI0_MISOPinNumber, 'D', 20); // +_MAKE_MOTATE_PIN(kSPI0_MOSIPinNumber, 'D', 21); // +_MAKE_MOTATE_PIN(kSPI0_SCKPinNumber, 'D', 22); // +_MAKE_MOTATE_PIN(kUnassigned7, 'D', 23); // NO PHYSICAL PIN +_MAKE_MOTATE_PIN(kSocket2_StepPinNumber, 'D', 24); // +_MAKE_MOTATE_PIN(kSocket2_SPISlaveSelectPinNumber, 'D', 25); // +_MAKE_MOTATE_PIN(kOutput9_PinNumber, 'D', 26); // PWM 2 +_MAKE_MOTATE_PIN(kSocket4_SPISlaveSelectPinNumber, 'D', 27); // +_MAKE_MOTATE_PIN(kSocket4_EnablePinNumber, 'D', 28); // +_MAKE_MOTATE_PIN(kUnassigned8, 'D', 29); // NO PHYSICAL PIN +_MAKE_MOTATE_PIN(kADC3_Neg_PinNumber, 'D', 30); // AFEC0,0 - was INTERRUPT_OUT +_MAKE_MOTATE_PIN(kUnassigned10, 'D', 31); // + +} // namespace Motate + +// We then allow each chip-type to have it's onw function definitions +// that will refer to these pin assignments. +#include "motate_chip_pin_functions.h" + +#endif + +// gquintic_a_pinout_h diff --git a/g2core/board/gquintic/motate_pin_assignments.h b/g2core/board/gquintic/motate_pin_assignments.h index 293ae1ec6..4be5c1dbb 100755 --- a/g2core/board/gquintic/motate_pin_assignments.h +++ b/g2core/board/gquintic/motate_pin_assignments.h @@ -202,6 +202,7 @@ pin_number kOutput14_PinNumber = -1; // 143; pin_number kOutput15_PinNumber = -1; // 144; pin_number kOutput16_PinNumber = -1; // 145; +// For rev-c where we use the differential pin_number kADC1_Pos_PinNumber = 150; // Extruder1_ADC pin_number kADC1_Neg_PinNumber = 151; // Extruder1_ADC pin_number kADC2_Pos_PinNumber = 152; // Extruder2_ADC @@ -209,6 +210,12 @@ pin_number kADC2_Neg_PinNumber = 153; // Extruder2_ADC pin_number kADC3_Pos_PinNumber = 154; // Heated bed thermistor ADC pin_number kADC3_Neg_PinNumber = 155; // Heated bed thermistor ADC +// for rev-d where we don't +pin_number kADC1_PinNumber = 150; // Extruder1_ADC +pin_number kADC2_PinNumber = 151; // Extruder2_ADC +pin_number kADC3_PinNumber = 152; // Heated bed thermistor ADC +pin_number kADC4_PinNumber = 153; // unused ADC + pin_number kExternalClock1_PinNumber = 170; // External pins for exporting a clock signal (for Trinamics) pin_number kServo1_PinNumber = 171; // diff --git a/g2core/boards.mk b/g2core/boards.mk index b2a643358..bc75ad948 100644 --- a/g2core/boards.mk +++ b/g2core/boards.mk @@ -153,7 +153,7 @@ endif ifeq ("$(CONFIG)","Ultimaker2Plus") ifeq ("$(BOARD)","NONE") - BOARD=gquintic-c + BOARD=gquintic-d endif SETTINGS_FILE="settings_Ultimaker_2_Plus.h" endif From d9eed39781d5f4fb30b88cbf8a52979341563401 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Tue, 5 Dec 2017 11:53:50 -0600 Subject: [PATCH 159/193] Minor cleanup in gpio.cpp --- g2core/gpio.cpp | 13 +++++-------- 1 file changed, 5 insertions(+), 8 deletions(-) diff --git a/g2core/gpio.cpp b/g2core/gpio.cpp index 14fb7cdbb..e731386ca 100644 --- a/g2core/gpio.cpp +++ b/g2core/gpio.cpp @@ -90,11 +90,11 @@ struct ioDigitalInputExt { ioDigitalInputExt(const ioDigitalInputExt&) = delete; // delete copy ioDigitalInputExt(ioDigitalInputExt&&) = delete; // delete move + static constexpr d_in_t *in = &d_in[ext_pin_number-1]; + void reset() { if (D_IN_CHANNELS < ext_pin_number) { return; } - d_in_t *in = &d_in[ext_pin_number-1]; - if (in->mode == IO_MODE_DISABLED) { in->state = INPUT_DISABLED; return; @@ -108,8 +108,6 @@ struct ioDigitalInputExt { void pin_changed() { if (D_IN_CHANNELS < ext_pin_number) { return; } - d_in_t *in = &d_in[ext_pin_number-1]; - // return if input is disabled (not supposed to happen) if (in->mode == IO_MODE_DISABLED) { in->state = INPUT_DISABLED; @@ -189,10 +187,9 @@ struct ioDigitalInputExt { if (in->action == INPUT_ACTION_RESET) { hw_hard_reset(); } - } - // these functions trigger on the leading edge - if (in->edge == INPUT_EDGE_LEADING) { + // these functions also trigger on the leading edge + if (in->function == INPUT_FUNCTION_LIMIT) { cm.limit_requested = ext_pin_number; @@ -202,7 +199,7 @@ struct ioDigitalInputExt { } else if (in->function == INPUT_FUNCTION_INTERLOCK) { cm.safety_interlock_disengaged = ext_pin_number; } - } + } // if (in->edge == INPUT_EDGE_LEADING) // trigger interlock release on trailing edge if (in->edge == INPUT_EDGE_TRAILING) { From 6c67e584846bf96b3868b1d3fd327bcc2e420a50 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Tue, 5 Dec 2017 11:54:40 -0600 Subject: [PATCH 160/193] Removing old comments --- g2core/temperature.cpp | 10 ---------- 1 file changed, 10 deletions(-) diff --git a/g2core/temperature.cpp b/g2core/temperature.cpp index 3ca79ea40..c7898d8a2 100755 --- a/g2core/temperature.cpp +++ b/g2core/temperature.cpp @@ -798,16 +798,6 @@ struct PID { bool atSetPoint() { return _at_set_point; } - -// //New-style JSON bindings. DISABLED FOR NOW. -// auto json_bindings(const char *object_name) { -// return JSON::bind_object(object_name, -// JSON::bind("set", _set_point, /*print precision:*/2), -// JSON::bind("p", _proportional, /*print precision:*/2), -// JSON::bind("i", _integral, /*print precision:*/5), -// JSON::bind("d", _derivative, /*print precision:*/5) -// ); -// } }; // NOTICE, the JSON alters incoming values for these! From 4f8aa01079de66b4da9d9c6624e0f666d20579ce Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Fri, 8 Dec 2017 17:34:11 -0600 Subject: [PATCH 161/193] Adjusting the spring factor computation and configuration --- g2core/canonical_machine.h | 1 - g2core/config_app.cpp | 1 - g2core/plan_exec.cpp | 43 +++++++++++---------- g2core/planner.h | 1 - g2core/settings/settings_Ultimaker_2_Plus.h | 3 +- 5 files changed, 24 insertions(+), 25 deletions(-) diff --git a/g2core/canonical_machine.h b/g2core/canonical_machine.h index e4768cff1..8db99bc63 100644 --- a/g2core/canonical_machine.h +++ b/g2core/canonical_machine.h @@ -386,7 +386,6 @@ typedef struct cmAxis { float zero_backoff; // backoff from switches for machine zero float spring_offset_factor; // factor of feed offset (sof * velocity = spring_offset) - float spring_retraction_factor; // factor of the x/y velocity to reverse the axis during non-movement float spring_offset_max; // max amount of spring offset compensation allowed } cfgAxis_t; diff --git a/g2core/config_app.cpp b/g2core/config_app.cpp index d0e54e265..c3a6d220d 100644 --- a/g2core/config_app.cpp +++ b/g2core/config_app.cpp @@ -444,7 +444,6 @@ const cfgItem_t cfgArray[] = { { "a","ara",_fipc, 3, cm_print_ra, get_flt, set_flt, (float *)&cm.a[AXIS_A].radius, A_RADIUS}, { "a","asf",_fipc, 3, cm_print_sf, get_flt, set_flt, (float *)&cm.a[AXIS_A].spring_offset_factor, A_SPRING_OFFSET_FACTOR}, { "a","asm",_fipc, 3, cm_print_sm, get_flt, set_flt, (float *)&cm.a[AXIS_A].spring_offset_max, A_SPRING_OFFSET_MAX}, - { "a","arf",_fipc, 3, cm_print_sf, get_flt, set_flt, (float *)&cm.a[AXIS_A].spring_retraction_factor,A_SPRING_RETRACTION_FACTOR}, { "a","aso", _f0, 3, cm_print_so, cm_get_so, set_ro, (float *)&cs.null, 0 }, { "a","ahi",_fip, 0, cm_print_hi, get_ui8, cm_set_hi, (float *)&cm.a[AXIS_A].homing_input, A_HOMING_INPUT }, { "a","ahd",_fip, 0, cm_print_hd, get_ui8, set_01, (float *)&cm.a[AXIS_A].homing_dir, A_HOMING_DIRECTION }, diff --git a/g2core/plan_exec.cpp b/g2core/plan_exec.cpp index 2768fdf30..516d29c4e 100644 --- a/g2core/plan_exec.cpp +++ b/g2core/plan_exec.cpp @@ -1081,28 +1081,31 @@ static stat_t _exec_aline_segment() #else // recompute the new spring offset if (a == AXIS_A) { - float axis_velocity = mr.target_velocity * mr.unit[a]; float new_spring_offset = 0.0; - if (fabs(axis_velocity) < 0.00001) { - // this axis isn't moving, so execute retraction vibration - if (mr.spring_retraction_backward[a] && mr.spring_offset[a] > -cm.a[a].spring_retraction_factor) { - // retract backward as fast as allowed, up to -cm.a[a].spring_retraction_factor - new_spring_offset = mr.spring_offset[a]-(mr.segment_time * cm.a[a].velocity_max); - if (new_spring_offset <= -cm.a[a].spring_retraction_factor) { - new_spring_offset = -cm.a[a].spring_retraction_factor; - mr.spring_retraction_backward[a] = false; - } - } else { - // undo retract at half velocity - new_spring_offset = std::max(0.0, mr.spring_offset[a] + (mr.segment_time * cm.a[a].velocity_max)/2.0); - mr.spring_retraction_backward[a] = false; - } + + float avg_axis_velocity = (mr.segment_velocity+mr.target_velocity) * 0.5 * mr.unit[a]; + float axis_travel = avg_axis_velocity * mr.segment_time; + float directional_velocity_max = (mr.unit[a] >= 0.0) ? cm.a[a].velocity_max : -cm.a[a].velocity_max; + float max_axis_travel = (mr.segment_velocity+directional_velocity_max) * 0.5 * mr.segment_time; + + // if the A axis is still, OR is the only axis moving, kill the remaining spring offset + if ((mr.axis_flags[a] || !(mr.axis_flags[AXIS_X] || mr.axis_flags[AXIS_Y] || mr.axis_flags[AXIS_Z])) && + mr.spring_offset[a] > 0.0001 + ) + { + // this axis isn't moving, so return offset to zero + // retract backward as fast as allowed, but don't go past 0.0 (positively or negatively) + new_spring_offset = mr.spring_offset[a] + (max_axis_travel - axis_travel); + new_spring_offset = (mr.unit[a] >= 0.0) ? + std::max(0.0f, new_spring_offset) : + std::min(0.0f, new_spring_offset); } else { - new_spring_offset = std::min( - (double)cm.a[a].spring_offset_factor * axis_velocity, // new actual offset - (double)mr.spring_offset[a]+((mr.segment_time * cm.a[a].velocity_max)-(mr.unit[a] * (mr.segment_velocity+mr.target_velocity) * 0.5 * mr.segment_time)) // offset at max speed - ); - mr.spring_retraction_backward[a] = true; // next zero-velocity move should be a retraction + new_spring_offset = cm.a[a].spring_offset_factor * avg_axis_velocity; + + if (std::abs(max_axis_travel) < std::abs(axis_travel+(new_spring_offset - mr.spring_offset[a]))) { + // adjust new_spring_offset down to meet maximum velocity + new_spring_offset = mr.spring_offset[a] + (max_axis_travel - axis_travel); + } } new_spring_offset = std::max(-cm.a[a].spring_offset_max, std::min(cm.a[a].spring_offset_max, new_spring_offset)); mr.spring_offset[a] = new_spring_offset; diff --git a/g2core/planner.h b/g2core/planner.h index ccad21836..4389c4d9b 100644 --- a/g2core/planner.h +++ b/g2core/planner.h @@ -490,7 +490,6 @@ typedef struct mpMotionRuntimeSingleton { // persistent runtime variables float unit[AXES]; // unit vector for axis scaling & planning float spring_offset[AXES]; // amount of spring offset compensation in effect per axis - bool spring_retraction_backward[AXES]; // true if that axis is retracting bool axis_flags[AXES]; // set true for axes participating in the move float target[AXES]; // final target for bf (used to correct rounding errors) float position[AXES]; // current move position diff --git a/g2core/settings/settings_Ultimaker_2_Plus.h b/g2core/settings/settings_Ultimaker_2_Plus.h index dff58d09f..532347fcf 100644 --- a/g2core/settings/settings_Ultimaker_2_Plus.h +++ b/g2core/settings/settings_Ultimaker_2_Plus.h @@ -337,8 +337,7 @@ // NYLON //#define A_JERK_HIGH_SPEED 35000.0 // ~30 million mm/min^3 {ajh:35000.0} #define A_SPRING_OFFSET_FACTOR 0 -#define A_SPRING_OFFSET_MAX 20 -#define A_SPRING_RETRACTION_FACTOR -0.001 +#define A_SPRING_OFFSET_MAX 100 #define B_AXIS_MODE AXIS_RADIUS From 6006574dd3433e13bd9d4f342d674a086b3d58e0 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Fri, 8 Dec 2017 17:35:55 -0600 Subject: [PATCH 162/193] Removing square of error in PID to increase PID reliability. --- g2core/temperature.cpp | 15 ++------------- 1 file changed, 2 insertions(+), 13 deletions(-) diff --git a/g2core/temperature.cpp b/g2core/temperature.cpp index cc588029d..204ac0fea 100755 --- a/g2core/temperature.cpp +++ b/g2core/temperature.cpp @@ -718,14 +718,6 @@ struct PID { } } - // Now tha we've done all the checks, square the error, maintaining the sign. - // The is because the energy required to heat an object is the number of degrees of change needed squared. - if (e > 0) { - e = e*e; - } else { - e = -(e*e); - } - // P = Proportional float p = _p_factor * e; @@ -759,12 +751,9 @@ struct PID { _derivative = (input - _previous_input)*(derivative_contribution) + (_derivative * (1.0-derivative_contribution)); float d = _derivative * _d_factor; + // F = feed-forward + _feed_forward = (_set_point-21); // 21 is for a roughly ideal room temperature - if (_feed_forward > 0) { - _feed_forward = _feed_forward*_feed_forward; - } else { - _feed_forward = -(_feed_forward*_feed_forward); - } float f = _f_factor * _feed_forward; From 01d3973b93d06df20c337ffff2dcf94f420750c4 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Wed, 13 Dec 2017 16:43:01 -0600 Subject: [PATCH 163/193] Reforctor of GPIO in prep of adding `ain`N and `ts`N (temperature sensor) objects --- .../Archim/{hardware.cpp => 0_hardware.cpp} | 0 g2core/board/Archim/board_gpio.cpp | 108 +++ g2core/board/Archim/board_gpio.h | 90 +++ .../{hardware.cpp => 0_hardware.cpp} | 0 g2core/board/ArduinoDue/board_gpio.cpp | 108 +++ g2core/board/ArduinoDue/board_gpio.h | 90 +++ .../G2v9/{hardware.cpp => 0_hardware.cpp} | 0 g2core/board/G2v9/board_gpio.cpp | 108 +++ g2core/board/G2v9/board_gpio.h | 90 +++ .../{hardware.cpp => 0_hardware.cpp} | 0 g2core/board/gquadratic/board_gpio.cpp | 108 +++ g2core/board/gquadratic/board_gpio.h | 90 +++ g2core/board/gquintic/board_gpio.cpp | 108 +++ g2core/board/gquintic/board_gpio.h | 90 +++ g2core/board/gquintic/board_stepper.cpp | 4 +- g2core/board/gquintic/board_stepper.h | 2 +- g2core/board/printrboardg2/board_gpio.cpp | 108 +++ g2core/board/printrboardg2/board_gpio.h | 90 +++ .../sbv300/{hardware.cpp => 0_hardware.cpp} | 0 g2core/board/sbv300/board_gpio.cpp | 108 +++ g2core/board/sbv300/board_gpio.h | 90 +++ g2core/config_app.cpp | 151 ++--- g2core/gpio.cpp | 622 +++--------------- g2core/gpio.h | 517 +++++++++++++-- g2core/stepper.h | 21 +- 25 files changed, 2033 insertions(+), 670 deletions(-) rename g2core/board/Archim/{hardware.cpp => 0_hardware.cpp} (100%) create mode 100644 g2core/board/Archim/board_gpio.cpp create mode 100644 g2core/board/Archim/board_gpio.h rename g2core/board/ArduinoDue/{hardware.cpp => 0_hardware.cpp} (100%) create mode 100644 g2core/board/ArduinoDue/board_gpio.cpp create mode 100644 g2core/board/ArduinoDue/board_gpio.h rename g2core/board/G2v9/{hardware.cpp => 0_hardware.cpp} (100%) create mode 100644 g2core/board/G2v9/board_gpio.cpp create mode 100644 g2core/board/G2v9/board_gpio.h rename g2core/board/gquadratic/{hardware.cpp => 0_hardware.cpp} (100%) create mode 100644 g2core/board/gquadratic/board_gpio.cpp create mode 100644 g2core/board/gquadratic/board_gpio.h create mode 100644 g2core/board/gquintic/board_gpio.cpp create mode 100644 g2core/board/gquintic/board_gpio.h create mode 100644 g2core/board/printrboardg2/board_gpio.cpp create mode 100644 g2core/board/printrboardg2/board_gpio.h rename g2core/board/sbv300/{hardware.cpp => 0_hardware.cpp} (100%) create mode 100644 g2core/board/sbv300/board_gpio.cpp create mode 100644 g2core/board/sbv300/board_gpio.h diff --git a/g2core/board/Archim/hardware.cpp b/g2core/board/Archim/0_hardware.cpp similarity index 100% rename from g2core/board/Archim/hardware.cpp rename to g2core/board/Archim/0_hardware.cpp diff --git a/g2core/board/Archim/board_gpio.cpp b/g2core/board/Archim/board_gpio.cpp new file mode 100644 index 000000000..4daf011d8 --- /dev/null +++ b/g2core/board/Archim/board_gpio.cpp @@ -0,0 +1,108 @@ +/* + * gpio.cpp - digital IO handling functions + * This file is part of the g2core project + * + * Copyright (c) 2015 - 2107 Alden S. Hart, Jr. + * Copyright (c) 2015 - 2017 Robert Giseburt + * + * This file ("the software") is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License, version 2 as published by the + * Free Software Foundation. You should have received a copy of the GNU General Public + * License, version 2 along with the software. If not, see . + * + * As a special exception, you may use this file as part of a software library without + * restriction. Specifically, if other files instantiate templates or use macros or + * inline functions from this file, or you compile this file and link it with other + * files to produce an executable, this file does not by itself cause the resulting + * executable to be covered by the GNU General Public License. This exception does not + * however invalidate any other reasons why the executable file might be covered by the + * GNU General Public License. + * + * THE SOFTWARE IS DISTRIBUTED IN THE HOPE THAT IT WILL BE USEFUL, BUT WITHOUT ANY + * WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES + * OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT + * SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF + * OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + */ +/* Switch Modes + * + * The switches are considered to be homing switches when cycle_state is + * CYCLE_HOMING. At all other times they are treated as limit switches: + * - Hitting a homing switch puts the current move into feedhold + * - Hitting a limit switch causes the machine to shut down and go into lockdown until reset + * + * The normally open switch modes (NO) trigger an interrupt on the falling edge + * and lockout subsequent interrupts for the defined lockout period. This approach + * beats doing debouncing as an integration as switches fire immediately. + * + * The normally closed switch modes (NC) trigger an interrupt on the rising edge + * and lockout subsequent interrupts for the defined lockout period. Ditto on the method. + */ + +#include "../../g2core.h" // #1 +#include "config.h" // #2 +#include "gpio.h" +#include "hardware.h" +#include "canonical_machine.h" + +#include "text_parser.h" +#include "controller.h" +#include "util.h" +#include "report.h" +#include "xio.h" + +#include "MotateTimers.h" + +/**** Setup Actual Objects ****/ + +gpioDigitalInputPin> din1 {DI1_MODE, 1}; +gpioDigitalInputPin> din2 {DI2_MODE, 2}; +gpioDigitalInputPin> din3 {DI3_MODE, 3}; +gpioDigitalInputPin> din4 {DI4_MODE, 4}; +gpioDigitalInputPin> din5 {DI5_MODE, 5}; +gpioDigitalInputPin> din6 {DI6_MODE, 6}; +gpioDigitalInputPin> din7 {DI7_MODE, 7}; +gpioDigitalInputPin> din8 {DI8_MODE, 8}; +gpioDigitalInputPin> din9 {DI9_MODE, 9}; +// gpioDigitalInputPin> din10 {DI10_MODE, 10}; +// gpioDigitalInputPin> din11 {DI11_MODE, 11}; +// gpioDigitalInputPin> din12 {DI12_MODE, 12}; + +gpioDigitalOutputPin> dout1 { DO1_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout2 { DO2_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout3 { DO3_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout4 { DO4_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout5 { DO5_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout6 { DO6_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout7 { DO7_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout8 { DO8_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout9 { DO9_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout10 { DO10_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout11 { DO11_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout12 { DO12_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout13 { DO13_MODE, (uint32_t)200000 }; + +/**** Setup Arrays - these are extern and MUST match the board_gpio.h ****/ + +gpioDigitalInput* const d_in[] = {&din1, &din2, &din3, &din4, &din5, &din6, &din7, &din8, &din9}; +gpioDigitalOutput* const d_out[] = {&dout1, &dout2, &dout3, &dout4, &dout5, &dout6, &dout7, &dout8, &dout9, &dout10, &dout11, &dout12, &dout13}; +// not yet used +// gpioAnalogInput* a_in[A_IN_CHANNELS]; +// gpioAnalogOutput* a_out[A_OUT_CHANNELS]; + +/************************************************************************************ + **** CODE ************************************************************************** + ************************************************************************************/ +/* + * gpio_reset() - reset inputs and outputs (no initialization) + */ + + +void outputs_reset(void) { + // nothing to do +} + +void inputs_reset(void) { + // nothing to do +} diff --git a/g2core/board/Archim/board_gpio.h b/g2core/board/Archim/board_gpio.h new file mode 100644 index 000000000..25a1cddcd --- /dev/null +++ b/g2core/board/Archim/board_gpio.h @@ -0,0 +1,90 @@ +/* + * gpio.h - Digital IO handling functions + * This file is part of the g2core project + * + * Copyright (c) 2015 - 2017 Alden S. Hart, Jr. + * Copyright (c) 2015 - 2017 Robert Giseburt + * + * This file ("the software") is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License, version 2 as published by the + * Free Software Foundation. You should have received a copy of the GNU General Public + * License, version 2 along with the software. If not, see . + * + * As a special exception, you may use this file as part of a software library without + * restriction. Specifically, if other files instantiate templates or use macros or + * inline functions from this file, or you compile this file and link it with other + * files to produce an executable, this file does not by itself cause the resulting + * executable to be covered by the GNU General Public License. This exception does not + * however invalidate any other reasons why the executable file might be covered by the + * GNU General Public License. + * + * THE SOFTWARE IS DISTRIBUTED IN THE HOPE THAT IT WILL BE USEFUL, BUT WITHOUT ANY + * WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES + * OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT + * SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF + * OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + */ +#ifndef BOARD_GPIO_H_ONCE +#define BOARD_GPIO_H_ONCE + +// this file is included from the bottom of gpio.h, but we do this for completeness +#include "../../gpio.h" + +/* + * GPIO defines + */ +//--- change as required for board and switch hardware ---// + +#define D_IN_CHANNELS 9 // v9 // number of digital inputs supported +#define D_OUT_CHANNELS 13 // number of digital outputs supported +#define A_IN_CHANNELS 0 // number of analog inputs supported +#define A_OUT_CHANNELS 0 // number of analog outputs supported + +#define INPUT_LOCKOUT_MS 10 // milliseconds to go dead after input firing + +/* + * The GPIO objects themselves - this must match up with board_gpio.cpp! + */ + +extern gpioDigitalInput* const d_in[D_IN_CHANNELS]; +extern gpioDigitalOutput* const d_out[D_OUT_CHANNELS]; +// extern gpioAnalogInput* a_in[A_IN_CHANNELS]; +// extern gpioAnalogOutput* a_out[A_OUT_CHANNELS]; + +// prepare the objects as externs (for config_app to not bloat) +using Motate::IRQPin; +using Motate::PWMOutputPin; +using Motate::PWMLikeOutputPin; +template +using OutputType = typename std::conditional, PWMLikeOutputPin>::type; + +extern gpioDigitalInputPin> din1; +extern gpioDigitalInputPin> din2; +extern gpioDigitalInputPin> din3; +extern gpioDigitalInputPin> din4; +extern gpioDigitalInputPin> din5; +extern gpioDigitalInputPin> din6; +extern gpioDigitalInputPin> din7; +extern gpioDigitalInputPin> din8; +extern gpioDigitalInputPin> din9; +// extern gpioDigitalInputPin> din10; +// extern gpioDigitalInputPin> din11; +// extern gpioDigitalInputPin> din12; + +extern gpioDigitalOutputPin> dout1; +extern gpioDigitalOutputPin> dout2; +extern gpioDigitalOutputPin> dout3; +extern gpioDigitalOutputPin> dout4; +extern gpioDigitalOutputPin> dout5; +extern gpioDigitalOutputPin> dout6; +extern gpioDigitalOutputPin> dout7; +extern gpioDigitalOutputPin> dout8; +extern gpioDigitalOutputPin> dout9; +extern gpioDigitalOutputPin> dout10; +extern gpioDigitalOutputPin> dout11; +extern gpioDigitalOutputPin> dout12; +extern gpioDigitalOutputPin> dout13; + + +#endif // End of include guard: BOARD_GPIO_H_ONCE diff --git a/g2core/board/ArduinoDue/hardware.cpp b/g2core/board/ArduinoDue/0_hardware.cpp similarity index 100% rename from g2core/board/ArduinoDue/hardware.cpp rename to g2core/board/ArduinoDue/0_hardware.cpp diff --git a/g2core/board/ArduinoDue/board_gpio.cpp b/g2core/board/ArduinoDue/board_gpio.cpp new file mode 100644 index 000000000..4daf011d8 --- /dev/null +++ b/g2core/board/ArduinoDue/board_gpio.cpp @@ -0,0 +1,108 @@ +/* + * gpio.cpp - digital IO handling functions + * This file is part of the g2core project + * + * Copyright (c) 2015 - 2107 Alden S. Hart, Jr. + * Copyright (c) 2015 - 2017 Robert Giseburt + * + * This file ("the software") is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License, version 2 as published by the + * Free Software Foundation. You should have received a copy of the GNU General Public + * License, version 2 along with the software. If not, see . + * + * As a special exception, you may use this file as part of a software library without + * restriction. Specifically, if other files instantiate templates or use macros or + * inline functions from this file, or you compile this file and link it with other + * files to produce an executable, this file does not by itself cause the resulting + * executable to be covered by the GNU General Public License. This exception does not + * however invalidate any other reasons why the executable file might be covered by the + * GNU General Public License. + * + * THE SOFTWARE IS DISTRIBUTED IN THE HOPE THAT IT WILL BE USEFUL, BUT WITHOUT ANY + * WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES + * OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT + * SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF + * OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + */ +/* Switch Modes + * + * The switches are considered to be homing switches when cycle_state is + * CYCLE_HOMING. At all other times they are treated as limit switches: + * - Hitting a homing switch puts the current move into feedhold + * - Hitting a limit switch causes the machine to shut down and go into lockdown until reset + * + * The normally open switch modes (NO) trigger an interrupt on the falling edge + * and lockout subsequent interrupts for the defined lockout period. This approach + * beats doing debouncing as an integration as switches fire immediately. + * + * The normally closed switch modes (NC) trigger an interrupt on the rising edge + * and lockout subsequent interrupts for the defined lockout period. Ditto on the method. + */ + +#include "../../g2core.h" // #1 +#include "config.h" // #2 +#include "gpio.h" +#include "hardware.h" +#include "canonical_machine.h" + +#include "text_parser.h" +#include "controller.h" +#include "util.h" +#include "report.h" +#include "xio.h" + +#include "MotateTimers.h" + +/**** Setup Actual Objects ****/ + +gpioDigitalInputPin> din1 {DI1_MODE, 1}; +gpioDigitalInputPin> din2 {DI2_MODE, 2}; +gpioDigitalInputPin> din3 {DI3_MODE, 3}; +gpioDigitalInputPin> din4 {DI4_MODE, 4}; +gpioDigitalInputPin> din5 {DI5_MODE, 5}; +gpioDigitalInputPin> din6 {DI6_MODE, 6}; +gpioDigitalInputPin> din7 {DI7_MODE, 7}; +gpioDigitalInputPin> din8 {DI8_MODE, 8}; +gpioDigitalInputPin> din9 {DI9_MODE, 9}; +// gpioDigitalInputPin> din10 {DI10_MODE, 10}; +// gpioDigitalInputPin> din11 {DI11_MODE, 11}; +// gpioDigitalInputPin> din12 {DI12_MODE, 12}; + +gpioDigitalOutputPin> dout1 { DO1_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout2 { DO2_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout3 { DO3_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout4 { DO4_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout5 { DO5_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout6 { DO6_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout7 { DO7_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout8 { DO8_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout9 { DO9_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout10 { DO10_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout11 { DO11_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout12 { DO12_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout13 { DO13_MODE, (uint32_t)200000 }; + +/**** Setup Arrays - these are extern and MUST match the board_gpio.h ****/ + +gpioDigitalInput* const d_in[] = {&din1, &din2, &din3, &din4, &din5, &din6, &din7, &din8, &din9}; +gpioDigitalOutput* const d_out[] = {&dout1, &dout2, &dout3, &dout4, &dout5, &dout6, &dout7, &dout8, &dout9, &dout10, &dout11, &dout12, &dout13}; +// not yet used +// gpioAnalogInput* a_in[A_IN_CHANNELS]; +// gpioAnalogOutput* a_out[A_OUT_CHANNELS]; + +/************************************************************************************ + **** CODE ************************************************************************** + ************************************************************************************/ +/* + * gpio_reset() - reset inputs and outputs (no initialization) + */ + + +void outputs_reset(void) { + // nothing to do +} + +void inputs_reset(void) { + // nothing to do +} diff --git a/g2core/board/ArduinoDue/board_gpio.h b/g2core/board/ArduinoDue/board_gpio.h new file mode 100644 index 000000000..25a1cddcd --- /dev/null +++ b/g2core/board/ArduinoDue/board_gpio.h @@ -0,0 +1,90 @@ +/* + * gpio.h - Digital IO handling functions + * This file is part of the g2core project + * + * Copyright (c) 2015 - 2017 Alden S. Hart, Jr. + * Copyright (c) 2015 - 2017 Robert Giseburt + * + * This file ("the software") is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License, version 2 as published by the + * Free Software Foundation. You should have received a copy of the GNU General Public + * License, version 2 along with the software. If not, see . + * + * As a special exception, you may use this file as part of a software library without + * restriction. Specifically, if other files instantiate templates or use macros or + * inline functions from this file, or you compile this file and link it with other + * files to produce an executable, this file does not by itself cause the resulting + * executable to be covered by the GNU General Public License. This exception does not + * however invalidate any other reasons why the executable file might be covered by the + * GNU General Public License. + * + * THE SOFTWARE IS DISTRIBUTED IN THE HOPE THAT IT WILL BE USEFUL, BUT WITHOUT ANY + * WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES + * OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT + * SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF + * OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + */ +#ifndef BOARD_GPIO_H_ONCE +#define BOARD_GPIO_H_ONCE + +// this file is included from the bottom of gpio.h, but we do this for completeness +#include "../../gpio.h" + +/* + * GPIO defines + */ +//--- change as required for board and switch hardware ---// + +#define D_IN_CHANNELS 9 // v9 // number of digital inputs supported +#define D_OUT_CHANNELS 13 // number of digital outputs supported +#define A_IN_CHANNELS 0 // number of analog inputs supported +#define A_OUT_CHANNELS 0 // number of analog outputs supported + +#define INPUT_LOCKOUT_MS 10 // milliseconds to go dead after input firing + +/* + * The GPIO objects themselves - this must match up with board_gpio.cpp! + */ + +extern gpioDigitalInput* const d_in[D_IN_CHANNELS]; +extern gpioDigitalOutput* const d_out[D_OUT_CHANNELS]; +// extern gpioAnalogInput* a_in[A_IN_CHANNELS]; +// extern gpioAnalogOutput* a_out[A_OUT_CHANNELS]; + +// prepare the objects as externs (for config_app to not bloat) +using Motate::IRQPin; +using Motate::PWMOutputPin; +using Motate::PWMLikeOutputPin; +template +using OutputType = typename std::conditional, PWMLikeOutputPin>::type; + +extern gpioDigitalInputPin> din1; +extern gpioDigitalInputPin> din2; +extern gpioDigitalInputPin> din3; +extern gpioDigitalInputPin> din4; +extern gpioDigitalInputPin> din5; +extern gpioDigitalInputPin> din6; +extern gpioDigitalInputPin> din7; +extern gpioDigitalInputPin> din8; +extern gpioDigitalInputPin> din9; +// extern gpioDigitalInputPin> din10; +// extern gpioDigitalInputPin> din11; +// extern gpioDigitalInputPin> din12; + +extern gpioDigitalOutputPin> dout1; +extern gpioDigitalOutputPin> dout2; +extern gpioDigitalOutputPin> dout3; +extern gpioDigitalOutputPin> dout4; +extern gpioDigitalOutputPin> dout5; +extern gpioDigitalOutputPin> dout6; +extern gpioDigitalOutputPin> dout7; +extern gpioDigitalOutputPin> dout8; +extern gpioDigitalOutputPin> dout9; +extern gpioDigitalOutputPin> dout10; +extern gpioDigitalOutputPin> dout11; +extern gpioDigitalOutputPin> dout12; +extern gpioDigitalOutputPin> dout13; + + +#endif // End of include guard: BOARD_GPIO_H_ONCE diff --git a/g2core/board/G2v9/hardware.cpp b/g2core/board/G2v9/0_hardware.cpp similarity index 100% rename from g2core/board/G2v9/hardware.cpp rename to g2core/board/G2v9/0_hardware.cpp diff --git a/g2core/board/G2v9/board_gpio.cpp b/g2core/board/G2v9/board_gpio.cpp new file mode 100644 index 000000000..4daf011d8 --- /dev/null +++ b/g2core/board/G2v9/board_gpio.cpp @@ -0,0 +1,108 @@ +/* + * gpio.cpp - digital IO handling functions + * This file is part of the g2core project + * + * Copyright (c) 2015 - 2107 Alden S. Hart, Jr. + * Copyright (c) 2015 - 2017 Robert Giseburt + * + * This file ("the software") is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License, version 2 as published by the + * Free Software Foundation. You should have received a copy of the GNU General Public + * License, version 2 along with the software. If not, see . + * + * As a special exception, you may use this file as part of a software library without + * restriction. Specifically, if other files instantiate templates or use macros or + * inline functions from this file, or you compile this file and link it with other + * files to produce an executable, this file does not by itself cause the resulting + * executable to be covered by the GNU General Public License. This exception does not + * however invalidate any other reasons why the executable file might be covered by the + * GNU General Public License. + * + * THE SOFTWARE IS DISTRIBUTED IN THE HOPE THAT IT WILL BE USEFUL, BUT WITHOUT ANY + * WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES + * OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT + * SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF + * OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + */ +/* Switch Modes + * + * The switches are considered to be homing switches when cycle_state is + * CYCLE_HOMING. At all other times they are treated as limit switches: + * - Hitting a homing switch puts the current move into feedhold + * - Hitting a limit switch causes the machine to shut down and go into lockdown until reset + * + * The normally open switch modes (NO) trigger an interrupt on the falling edge + * and lockout subsequent interrupts for the defined lockout period. This approach + * beats doing debouncing as an integration as switches fire immediately. + * + * The normally closed switch modes (NC) trigger an interrupt on the rising edge + * and lockout subsequent interrupts for the defined lockout period. Ditto on the method. + */ + +#include "../../g2core.h" // #1 +#include "config.h" // #2 +#include "gpio.h" +#include "hardware.h" +#include "canonical_machine.h" + +#include "text_parser.h" +#include "controller.h" +#include "util.h" +#include "report.h" +#include "xio.h" + +#include "MotateTimers.h" + +/**** Setup Actual Objects ****/ + +gpioDigitalInputPin> din1 {DI1_MODE, 1}; +gpioDigitalInputPin> din2 {DI2_MODE, 2}; +gpioDigitalInputPin> din3 {DI3_MODE, 3}; +gpioDigitalInputPin> din4 {DI4_MODE, 4}; +gpioDigitalInputPin> din5 {DI5_MODE, 5}; +gpioDigitalInputPin> din6 {DI6_MODE, 6}; +gpioDigitalInputPin> din7 {DI7_MODE, 7}; +gpioDigitalInputPin> din8 {DI8_MODE, 8}; +gpioDigitalInputPin> din9 {DI9_MODE, 9}; +// gpioDigitalInputPin> din10 {DI10_MODE, 10}; +// gpioDigitalInputPin> din11 {DI11_MODE, 11}; +// gpioDigitalInputPin> din12 {DI12_MODE, 12}; + +gpioDigitalOutputPin> dout1 { DO1_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout2 { DO2_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout3 { DO3_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout4 { DO4_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout5 { DO5_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout6 { DO6_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout7 { DO7_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout8 { DO8_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout9 { DO9_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout10 { DO10_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout11 { DO11_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout12 { DO12_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout13 { DO13_MODE, (uint32_t)200000 }; + +/**** Setup Arrays - these are extern and MUST match the board_gpio.h ****/ + +gpioDigitalInput* const d_in[] = {&din1, &din2, &din3, &din4, &din5, &din6, &din7, &din8, &din9}; +gpioDigitalOutput* const d_out[] = {&dout1, &dout2, &dout3, &dout4, &dout5, &dout6, &dout7, &dout8, &dout9, &dout10, &dout11, &dout12, &dout13}; +// not yet used +// gpioAnalogInput* a_in[A_IN_CHANNELS]; +// gpioAnalogOutput* a_out[A_OUT_CHANNELS]; + +/************************************************************************************ + **** CODE ************************************************************************** + ************************************************************************************/ +/* + * gpio_reset() - reset inputs and outputs (no initialization) + */ + + +void outputs_reset(void) { + // nothing to do +} + +void inputs_reset(void) { + // nothing to do +} diff --git a/g2core/board/G2v9/board_gpio.h b/g2core/board/G2v9/board_gpio.h new file mode 100644 index 000000000..25a1cddcd --- /dev/null +++ b/g2core/board/G2v9/board_gpio.h @@ -0,0 +1,90 @@ +/* + * gpio.h - Digital IO handling functions + * This file is part of the g2core project + * + * Copyright (c) 2015 - 2017 Alden S. Hart, Jr. + * Copyright (c) 2015 - 2017 Robert Giseburt + * + * This file ("the software") is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License, version 2 as published by the + * Free Software Foundation. You should have received a copy of the GNU General Public + * License, version 2 along with the software. If not, see . + * + * As a special exception, you may use this file as part of a software library without + * restriction. Specifically, if other files instantiate templates or use macros or + * inline functions from this file, or you compile this file and link it with other + * files to produce an executable, this file does not by itself cause the resulting + * executable to be covered by the GNU General Public License. This exception does not + * however invalidate any other reasons why the executable file might be covered by the + * GNU General Public License. + * + * THE SOFTWARE IS DISTRIBUTED IN THE HOPE THAT IT WILL BE USEFUL, BUT WITHOUT ANY + * WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES + * OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT + * SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF + * OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + */ +#ifndef BOARD_GPIO_H_ONCE +#define BOARD_GPIO_H_ONCE + +// this file is included from the bottom of gpio.h, but we do this for completeness +#include "../../gpio.h" + +/* + * GPIO defines + */ +//--- change as required for board and switch hardware ---// + +#define D_IN_CHANNELS 9 // v9 // number of digital inputs supported +#define D_OUT_CHANNELS 13 // number of digital outputs supported +#define A_IN_CHANNELS 0 // number of analog inputs supported +#define A_OUT_CHANNELS 0 // number of analog outputs supported + +#define INPUT_LOCKOUT_MS 10 // milliseconds to go dead after input firing + +/* + * The GPIO objects themselves - this must match up with board_gpio.cpp! + */ + +extern gpioDigitalInput* const d_in[D_IN_CHANNELS]; +extern gpioDigitalOutput* const d_out[D_OUT_CHANNELS]; +// extern gpioAnalogInput* a_in[A_IN_CHANNELS]; +// extern gpioAnalogOutput* a_out[A_OUT_CHANNELS]; + +// prepare the objects as externs (for config_app to not bloat) +using Motate::IRQPin; +using Motate::PWMOutputPin; +using Motate::PWMLikeOutputPin; +template +using OutputType = typename std::conditional, PWMLikeOutputPin>::type; + +extern gpioDigitalInputPin> din1; +extern gpioDigitalInputPin> din2; +extern gpioDigitalInputPin> din3; +extern gpioDigitalInputPin> din4; +extern gpioDigitalInputPin> din5; +extern gpioDigitalInputPin> din6; +extern gpioDigitalInputPin> din7; +extern gpioDigitalInputPin> din8; +extern gpioDigitalInputPin> din9; +// extern gpioDigitalInputPin> din10; +// extern gpioDigitalInputPin> din11; +// extern gpioDigitalInputPin> din12; + +extern gpioDigitalOutputPin> dout1; +extern gpioDigitalOutputPin> dout2; +extern gpioDigitalOutputPin> dout3; +extern gpioDigitalOutputPin> dout4; +extern gpioDigitalOutputPin> dout5; +extern gpioDigitalOutputPin> dout6; +extern gpioDigitalOutputPin> dout7; +extern gpioDigitalOutputPin> dout8; +extern gpioDigitalOutputPin> dout9; +extern gpioDigitalOutputPin> dout10; +extern gpioDigitalOutputPin> dout11; +extern gpioDigitalOutputPin> dout12; +extern gpioDigitalOutputPin> dout13; + + +#endif // End of include guard: BOARD_GPIO_H_ONCE diff --git a/g2core/board/gquadratic/hardware.cpp b/g2core/board/gquadratic/0_hardware.cpp similarity index 100% rename from g2core/board/gquadratic/hardware.cpp rename to g2core/board/gquadratic/0_hardware.cpp diff --git a/g2core/board/gquadratic/board_gpio.cpp b/g2core/board/gquadratic/board_gpio.cpp new file mode 100644 index 000000000..4daf011d8 --- /dev/null +++ b/g2core/board/gquadratic/board_gpio.cpp @@ -0,0 +1,108 @@ +/* + * gpio.cpp - digital IO handling functions + * This file is part of the g2core project + * + * Copyright (c) 2015 - 2107 Alden S. Hart, Jr. + * Copyright (c) 2015 - 2017 Robert Giseburt + * + * This file ("the software") is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License, version 2 as published by the + * Free Software Foundation. You should have received a copy of the GNU General Public + * License, version 2 along with the software. If not, see . + * + * As a special exception, you may use this file as part of a software library without + * restriction. Specifically, if other files instantiate templates or use macros or + * inline functions from this file, or you compile this file and link it with other + * files to produce an executable, this file does not by itself cause the resulting + * executable to be covered by the GNU General Public License. This exception does not + * however invalidate any other reasons why the executable file might be covered by the + * GNU General Public License. + * + * THE SOFTWARE IS DISTRIBUTED IN THE HOPE THAT IT WILL BE USEFUL, BUT WITHOUT ANY + * WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES + * OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT + * SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF + * OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + */ +/* Switch Modes + * + * The switches are considered to be homing switches when cycle_state is + * CYCLE_HOMING. At all other times they are treated as limit switches: + * - Hitting a homing switch puts the current move into feedhold + * - Hitting a limit switch causes the machine to shut down and go into lockdown until reset + * + * The normally open switch modes (NO) trigger an interrupt on the falling edge + * and lockout subsequent interrupts for the defined lockout period. This approach + * beats doing debouncing as an integration as switches fire immediately. + * + * The normally closed switch modes (NC) trigger an interrupt on the rising edge + * and lockout subsequent interrupts for the defined lockout period. Ditto on the method. + */ + +#include "../../g2core.h" // #1 +#include "config.h" // #2 +#include "gpio.h" +#include "hardware.h" +#include "canonical_machine.h" + +#include "text_parser.h" +#include "controller.h" +#include "util.h" +#include "report.h" +#include "xio.h" + +#include "MotateTimers.h" + +/**** Setup Actual Objects ****/ + +gpioDigitalInputPin> din1 {DI1_MODE, 1}; +gpioDigitalInputPin> din2 {DI2_MODE, 2}; +gpioDigitalInputPin> din3 {DI3_MODE, 3}; +gpioDigitalInputPin> din4 {DI4_MODE, 4}; +gpioDigitalInputPin> din5 {DI5_MODE, 5}; +gpioDigitalInputPin> din6 {DI6_MODE, 6}; +gpioDigitalInputPin> din7 {DI7_MODE, 7}; +gpioDigitalInputPin> din8 {DI8_MODE, 8}; +gpioDigitalInputPin> din9 {DI9_MODE, 9}; +// gpioDigitalInputPin> din10 {DI10_MODE, 10}; +// gpioDigitalInputPin> din11 {DI11_MODE, 11}; +// gpioDigitalInputPin> din12 {DI12_MODE, 12}; + +gpioDigitalOutputPin> dout1 { DO1_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout2 { DO2_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout3 { DO3_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout4 { DO4_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout5 { DO5_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout6 { DO6_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout7 { DO7_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout8 { DO8_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout9 { DO9_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout10 { DO10_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout11 { DO11_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout12 { DO12_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout13 { DO13_MODE, (uint32_t)200000 }; + +/**** Setup Arrays - these are extern and MUST match the board_gpio.h ****/ + +gpioDigitalInput* const d_in[] = {&din1, &din2, &din3, &din4, &din5, &din6, &din7, &din8, &din9}; +gpioDigitalOutput* const d_out[] = {&dout1, &dout2, &dout3, &dout4, &dout5, &dout6, &dout7, &dout8, &dout9, &dout10, &dout11, &dout12, &dout13}; +// not yet used +// gpioAnalogInput* a_in[A_IN_CHANNELS]; +// gpioAnalogOutput* a_out[A_OUT_CHANNELS]; + +/************************************************************************************ + **** CODE ************************************************************************** + ************************************************************************************/ +/* + * gpio_reset() - reset inputs and outputs (no initialization) + */ + + +void outputs_reset(void) { + // nothing to do +} + +void inputs_reset(void) { + // nothing to do +} diff --git a/g2core/board/gquadratic/board_gpio.h b/g2core/board/gquadratic/board_gpio.h new file mode 100644 index 000000000..25a1cddcd --- /dev/null +++ b/g2core/board/gquadratic/board_gpio.h @@ -0,0 +1,90 @@ +/* + * gpio.h - Digital IO handling functions + * This file is part of the g2core project + * + * Copyright (c) 2015 - 2017 Alden S. Hart, Jr. + * Copyright (c) 2015 - 2017 Robert Giseburt + * + * This file ("the software") is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License, version 2 as published by the + * Free Software Foundation. You should have received a copy of the GNU General Public + * License, version 2 along with the software. If not, see . + * + * As a special exception, you may use this file as part of a software library without + * restriction. Specifically, if other files instantiate templates or use macros or + * inline functions from this file, or you compile this file and link it with other + * files to produce an executable, this file does not by itself cause the resulting + * executable to be covered by the GNU General Public License. This exception does not + * however invalidate any other reasons why the executable file might be covered by the + * GNU General Public License. + * + * THE SOFTWARE IS DISTRIBUTED IN THE HOPE THAT IT WILL BE USEFUL, BUT WITHOUT ANY + * WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES + * OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT + * SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF + * OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + */ +#ifndef BOARD_GPIO_H_ONCE +#define BOARD_GPIO_H_ONCE + +// this file is included from the bottom of gpio.h, but we do this for completeness +#include "../../gpio.h" + +/* + * GPIO defines + */ +//--- change as required for board and switch hardware ---// + +#define D_IN_CHANNELS 9 // v9 // number of digital inputs supported +#define D_OUT_CHANNELS 13 // number of digital outputs supported +#define A_IN_CHANNELS 0 // number of analog inputs supported +#define A_OUT_CHANNELS 0 // number of analog outputs supported + +#define INPUT_LOCKOUT_MS 10 // milliseconds to go dead after input firing + +/* + * The GPIO objects themselves - this must match up with board_gpio.cpp! + */ + +extern gpioDigitalInput* const d_in[D_IN_CHANNELS]; +extern gpioDigitalOutput* const d_out[D_OUT_CHANNELS]; +// extern gpioAnalogInput* a_in[A_IN_CHANNELS]; +// extern gpioAnalogOutput* a_out[A_OUT_CHANNELS]; + +// prepare the objects as externs (for config_app to not bloat) +using Motate::IRQPin; +using Motate::PWMOutputPin; +using Motate::PWMLikeOutputPin; +template +using OutputType = typename std::conditional, PWMLikeOutputPin>::type; + +extern gpioDigitalInputPin> din1; +extern gpioDigitalInputPin> din2; +extern gpioDigitalInputPin> din3; +extern gpioDigitalInputPin> din4; +extern gpioDigitalInputPin> din5; +extern gpioDigitalInputPin> din6; +extern gpioDigitalInputPin> din7; +extern gpioDigitalInputPin> din8; +extern gpioDigitalInputPin> din9; +// extern gpioDigitalInputPin> din10; +// extern gpioDigitalInputPin> din11; +// extern gpioDigitalInputPin> din12; + +extern gpioDigitalOutputPin> dout1; +extern gpioDigitalOutputPin> dout2; +extern gpioDigitalOutputPin> dout3; +extern gpioDigitalOutputPin> dout4; +extern gpioDigitalOutputPin> dout5; +extern gpioDigitalOutputPin> dout6; +extern gpioDigitalOutputPin> dout7; +extern gpioDigitalOutputPin> dout8; +extern gpioDigitalOutputPin> dout9; +extern gpioDigitalOutputPin> dout10; +extern gpioDigitalOutputPin> dout11; +extern gpioDigitalOutputPin> dout12; +extern gpioDigitalOutputPin> dout13; + + +#endif // End of include guard: BOARD_GPIO_H_ONCE diff --git a/g2core/board/gquintic/board_gpio.cpp b/g2core/board/gquintic/board_gpio.cpp new file mode 100644 index 000000000..4daf011d8 --- /dev/null +++ b/g2core/board/gquintic/board_gpio.cpp @@ -0,0 +1,108 @@ +/* + * gpio.cpp - digital IO handling functions + * This file is part of the g2core project + * + * Copyright (c) 2015 - 2107 Alden S. Hart, Jr. + * Copyright (c) 2015 - 2017 Robert Giseburt + * + * This file ("the software") is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License, version 2 as published by the + * Free Software Foundation. You should have received a copy of the GNU General Public + * License, version 2 along with the software. If not, see . + * + * As a special exception, you may use this file as part of a software library without + * restriction. Specifically, if other files instantiate templates or use macros or + * inline functions from this file, or you compile this file and link it with other + * files to produce an executable, this file does not by itself cause the resulting + * executable to be covered by the GNU General Public License. This exception does not + * however invalidate any other reasons why the executable file might be covered by the + * GNU General Public License. + * + * THE SOFTWARE IS DISTRIBUTED IN THE HOPE THAT IT WILL BE USEFUL, BUT WITHOUT ANY + * WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES + * OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT + * SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF + * OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + */ +/* Switch Modes + * + * The switches are considered to be homing switches when cycle_state is + * CYCLE_HOMING. At all other times they are treated as limit switches: + * - Hitting a homing switch puts the current move into feedhold + * - Hitting a limit switch causes the machine to shut down and go into lockdown until reset + * + * The normally open switch modes (NO) trigger an interrupt on the falling edge + * and lockout subsequent interrupts for the defined lockout period. This approach + * beats doing debouncing as an integration as switches fire immediately. + * + * The normally closed switch modes (NC) trigger an interrupt on the rising edge + * and lockout subsequent interrupts for the defined lockout period. Ditto on the method. + */ + +#include "../../g2core.h" // #1 +#include "config.h" // #2 +#include "gpio.h" +#include "hardware.h" +#include "canonical_machine.h" + +#include "text_parser.h" +#include "controller.h" +#include "util.h" +#include "report.h" +#include "xio.h" + +#include "MotateTimers.h" + +/**** Setup Actual Objects ****/ + +gpioDigitalInputPin> din1 {DI1_MODE, 1}; +gpioDigitalInputPin> din2 {DI2_MODE, 2}; +gpioDigitalInputPin> din3 {DI3_MODE, 3}; +gpioDigitalInputPin> din4 {DI4_MODE, 4}; +gpioDigitalInputPin> din5 {DI5_MODE, 5}; +gpioDigitalInputPin> din6 {DI6_MODE, 6}; +gpioDigitalInputPin> din7 {DI7_MODE, 7}; +gpioDigitalInputPin> din8 {DI8_MODE, 8}; +gpioDigitalInputPin> din9 {DI9_MODE, 9}; +// gpioDigitalInputPin> din10 {DI10_MODE, 10}; +// gpioDigitalInputPin> din11 {DI11_MODE, 11}; +// gpioDigitalInputPin> din12 {DI12_MODE, 12}; + +gpioDigitalOutputPin> dout1 { DO1_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout2 { DO2_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout3 { DO3_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout4 { DO4_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout5 { DO5_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout6 { DO6_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout7 { DO7_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout8 { DO8_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout9 { DO9_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout10 { DO10_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout11 { DO11_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout12 { DO12_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout13 { DO13_MODE, (uint32_t)200000 }; + +/**** Setup Arrays - these are extern and MUST match the board_gpio.h ****/ + +gpioDigitalInput* const d_in[] = {&din1, &din2, &din3, &din4, &din5, &din6, &din7, &din8, &din9}; +gpioDigitalOutput* const d_out[] = {&dout1, &dout2, &dout3, &dout4, &dout5, &dout6, &dout7, &dout8, &dout9, &dout10, &dout11, &dout12, &dout13}; +// not yet used +// gpioAnalogInput* a_in[A_IN_CHANNELS]; +// gpioAnalogOutput* a_out[A_OUT_CHANNELS]; + +/************************************************************************************ + **** CODE ************************************************************************** + ************************************************************************************/ +/* + * gpio_reset() - reset inputs and outputs (no initialization) + */ + + +void outputs_reset(void) { + // nothing to do +} + +void inputs_reset(void) { + // nothing to do +} diff --git a/g2core/board/gquintic/board_gpio.h b/g2core/board/gquintic/board_gpio.h new file mode 100644 index 000000000..25a1cddcd --- /dev/null +++ b/g2core/board/gquintic/board_gpio.h @@ -0,0 +1,90 @@ +/* + * gpio.h - Digital IO handling functions + * This file is part of the g2core project + * + * Copyright (c) 2015 - 2017 Alden S. Hart, Jr. + * Copyright (c) 2015 - 2017 Robert Giseburt + * + * This file ("the software") is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License, version 2 as published by the + * Free Software Foundation. You should have received a copy of the GNU General Public + * License, version 2 along with the software. If not, see . + * + * As a special exception, you may use this file as part of a software library without + * restriction. Specifically, if other files instantiate templates or use macros or + * inline functions from this file, or you compile this file and link it with other + * files to produce an executable, this file does not by itself cause the resulting + * executable to be covered by the GNU General Public License. This exception does not + * however invalidate any other reasons why the executable file might be covered by the + * GNU General Public License. + * + * THE SOFTWARE IS DISTRIBUTED IN THE HOPE THAT IT WILL BE USEFUL, BUT WITHOUT ANY + * WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES + * OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT + * SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF + * OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + */ +#ifndef BOARD_GPIO_H_ONCE +#define BOARD_GPIO_H_ONCE + +// this file is included from the bottom of gpio.h, but we do this for completeness +#include "../../gpio.h" + +/* + * GPIO defines + */ +//--- change as required for board and switch hardware ---// + +#define D_IN_CHANNELS 9 // v9 // number of digital inputs supported +#define D_OUT_CHANNELS 13 // number of digital outputs supported +#define A_IN_CHANNELS 0 // number of analog inputs supported +#define A_OUT_CHANNELS 0 // number of analog outputs supported + +#define INPUT_LOCKOUT_MS 10 // milliseconds to go dead after input firing + +/* + * The GPIO objects themselves - this must match up with board_gpio.cpp! + */ + +extern gpioDigitalInput* const d_in[D_IN_CHANNELS]; +extern gpioDigitalOutput* const d_out[D_OUT_CHANNELS]; +// extern gpioAnalogInput* a_in[A_IN_CHANNELS]; +// extern gpioAnalogOutput* a_out[A_OUT_CHANNELS]; + +// prepare the objects as externs (for config_app to not bloat) +using Motate::IRQPin; +using Motate::PWMOutputPin; +using Motate::PWMLikeOutputPin; +template +using OutputType = typename std::conditional, PWMLikeOutputPin>::type; + +extern gpioDigitalInputPin> din1; +extern gpioDigitalInputPin> din2; +extern gpioDigitalInputPin> din3; +extern gpioDigitalInputPin> din4; +extern gpioDigitalInputPin> din5; +extern gpioDigitalInputPin> din6; +extern gpioDigitalInputPin> din7; +extern gpioDigitalInputPin> din8; +extern gpioDigitalInputPin> din9; +// extern gpioDigitalInputPin> din10; +// extern gpioDigitalInputPin> din11; +// extern gpioDigitalInputPin> din12; + +extern gpioDigitalOutputPin> dout1; +extern gpioDigitalOutputPin> dout2; +extern gpioDigitalOutputPin> dout3; +extern gpioDigitalOutputPin> dout4; +extern gpioDigitalOutputPin> dout5; +extern gpioDigitalOutputPin> dout6; +extern gpioDigitalOutputPin> dout7; +extern gpioDigitalOutputPin> dout8; +extern gpioDigitalOutputPin> dout9; +extern gpioDigitalOutputPin> dout10; +extern gpioDigitalOutputPin> dout11; +extern gpioDigitalOutputPin> dout12; +extern gpioDigitalOutputPin> dout13; + + +#endif // End of include guard: BOARD_GPIO_H_ONCE diff --git a/g2core/board/gquintic/board_stepper.cpp b/g2core/board/gquintic/board_stepper.cpp index 06028948d..2cd1acde4 100755 --- a/g2core/board/gquintic/board_stepper.cpp +++ b/g2core/board/gquintic/board_stepper.cpp @@ -52,7 +52,7 @@ HOT_DATA Trinamic2130 motor_5; -Stepper* Motors[MOTORS] = {&motor_1, &motor_2, &motor_3, &motor_4, &motor_5}; +Stepper* const Motors[MOTORS] = {&motor_1, &motor_2, &motor_3, &motor_4, &motor_5}; #else HOT_DATA Trinamic2130 motor_6; -Stepper* Motors[MOTORS] = {&motor_1, &motor_2, &motor_3, &motor_4, &motor_5, &motor_6}; +Stepper* const Motors[MOTORS] = {&motor_1, &motor_2, &motor_3, &motor_4, &motor_5, &motor_6}; #endif void board_stepper_init() { diff --git a/g2core/board/gquintic/board_stepper.h b/g2core/board/gquintic/board_stepper.h index 056bccc07..52db83468 100755 --- a/g2core/board/gquintic/board_stepper.h +++ b/g2core/board/gquintic/board_stepper.h @@ -84,7 +84,7 @@ extern Trinamic2130 motor_6; #endif -extern Stepper* Motors[MOTORS]; +extern Stepper* const Motors[MOTORS]; void board_stepper_init(); diff --git a/g2core/board/printrboardg2/board_gpio.cpp b/g2core/board/printrboardg2/board_gpio.cpp new file mode 100644 index 000000000..4daf011d8 --- /dev/null +++ b/g2core/board/printrboardg2/board_gpio.cpp @@ -0,0 +1,108 @@ +/* + * gpio.cpp - digital IO handling functions + * This file is part of the g2core project + * + * Copyright (c) 2015 - 2107 Alden S. Hart, Jr. + * Copyright (c) 2015 - 2017 Robert Giseburt + * + * This file ("the software") is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License, version 2 as published by the + * Free Software Foundation. You should have received a copy of the GNU General Public + * License, version 2 along with the software. If not, see . + * + * As a special exception, you may use this file as part of a software library without + * restriction. Specifically, if other files instantiate templates or use macros or + * inline functions from this file, or you compile this file and link it with other + * files to produce an executable, this file does not by itself cause the resulting + * executable to be covered by the GNU General Public License. This exception does not + * however invalidate any other reasons why the executable file might be covered by the + * GNU General Public License. + * + * THE SOFTWARE IS DISTRIBUTED IN THE HOPE THAT IT WILL BE USEFUL, BUT WITHOUT ANY + * WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES + * OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT + * SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF + * OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + */ +/* Switch Modes + * + * The switches are considered to be homing switches when cycle_state is + * CYCLE_HOMING. At all other times they are treated as limit switches: + * - Hitting a homing switch puts the current move into feedhold + * - Hitting a limit switch causes the machine to shut down and go into lockdown until reset + * + * The normally open switch modes (NO) trigger an interrupt on the falling edge + * and lockout subsequent interrupts for the defined lockout period. This approach + * beats doing debouncing as an integration as switches fire immediately. + * + * The normally closed switch modes (NC) trigger an interrupt on the rising edge + * and lockout subsequent interrupts for the defined lockout period. Ditto on the method. + */ + +#include "../../g2core.h" // #1 +#include "config.h" // #2 +#include "gpio.h" +#include "hardware.h" +#include "canonical_machine.h" + +#include "text_parser.h" +#include "controller.h" +#include "util.h" +#include "report.h" +#include "xio.h" + +#include "MotateTimers.h" + +/**** Setup Actual Objects ****/ + +gpioDigitalInputPin> din1 {DI1_MODE, 1}; +gpioDigitalInputPin> din2 {DI2_MODE, 2}; +gpioDigitalInputPin> din3 {DI3_MODE, 3}; +gpioDigitalInputPin> din4 {DI4_MODE, 4}; +gpioDigitalInputPin> din5 {DI5_MODE, 5}; +gpioDigitalInputPin> din6 {DI6_MODE, 6}; +gpioDigitalInputPin> din7 {DI7_MODE, 7}; +gpioDigitalInputPin> din8 {DI8_MODE, 8}; +gpioDigitalInputPin> din9 {DI9_MODE, 9}; +// gpioDigitalInputPin> din10 {DI10_MODE, 10}; +// gpioDigitalInputPin> din11 {DI11_MODE, 11}; +// gpioDigitalInputPin> din12 {DI12_MODE, 12}; + +gpioDigitalOutputPin> dout1 { DO1_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout2 { DO2_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout3 { DO3_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout4 { DO4_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout5 { DO5_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout6 { DO6_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout7 { DO7_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout8 { DO8_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout9 { DO9_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout10 { DO10_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout11 { DO11_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout12 { DO12_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout13 { DO13_MODE, (uint32_t)200000 }; + +/**** Setup Arrays - these are extern and MUST match the board_gpio.h ****/ + +gpioDigitalInput* const d_in[] = {&din1, &din2, &din3, &din4, &din5, &din6, &din7, &din8, &din9}; +gpioDigitalOutput* const d_out[] = {&dout1, &dout2, &dout3, &dout4, &dout5, &dout6, &dout7, &dout8, &dout9, &dout10, &dout11, &dout12, &dout13}; +// not yet used +// gpioAnalogInput* a_in[A_IN_CHANNELS]; +// gpioAnalogOutput* a_out[A_OUT_CHANNELS]; + +/************************************************************************************ + **** CODE ************************************************************************** + ************************************************************************************/ +/* + * gpio_reset() - reset inputs and outputs (no initialization) + */ + + +void outputs_reset(void) { + // nothing to do +} + +void inputs_reset(void) { + // nothing to do +} diff --git a/g2core/board/printrboardg2/board_gpio.h b/g2core/board/printrboardg2/board_gpio.h new file mode 100644 index 000000000..25a1cddcd --- /dev/null +++ b/g2core/board/printrboardg2/board_gpio.h @@ -0,0 +1,90 @@ +/* + * gpio.h - Digital IO handling functions + * This file is part of the g2core project + * + * Copyright (c) 2015 - 2017 Alden S. Hart, Jr. + * Copyright (c) 2015 - 2017 Robert Giseburt + * + * This file ("the software") is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License, version 2 as published by the + * Free Software Foundation. You should have received a copy of the GNU General Public + * License, version 2 along with the software. If not, see . + * + * As a special exception, you may use this file as part of a software library without + * restriction. Specifically, if other files instantiate templates or use macros or + * inline functions from this file, or you compile this file and link it with other + * files to produce an executable, this file does not by itself cause the resulting + * executable to be covered by the GNU General Public License. This exception does not + * however invalidate any other reasons why the executable file might be covered by the + * GNU General Public License. + * + * THE SOFTWARE IS DISTRIBUTED IN THE HOPE THAT IT WILL BE USEFUL, BUT WITHOUT ANY + * WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES + * OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT + * SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF + * OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + */ +#ifndef BOARD_GPIO_H_ONCE +#define BOARD_GPIO_H_ONCE + +// this file is included from the bottom of gpio.h, but we do this for completeness +#include "../../gpio.h" + +/* + * GPIO defines + */ +//--- change as required for board and switch hardware ---// + +#define D_IN_CHANNELS 9 // v9 // number of digital inputs supported +#define D_OUT_CHANNELS 13 // number of digital outputs supported +#define A_IN_CHANNELS 0 // number of analog inputs supported +#define A_OUT_CHANNELS 0 // number of analog outputs supported + +#define INPUT_LOCKOUT_MS 10 // milliseconds to go dead after input firing + +/* + * The GPIO objects themselves - this must match up with board_gpio.cpp! + */ + +extern gpioDigitalInput* const d_in[D_IN_CHANNELS]; +extern gpioDigitalOutput* const d_out[D_OUT_CHANNELS]; +// extern gpioAnalogInput* a_in[A_IN_CHANNELS]; +// extern gpioAnalogOutput* a_out[A_OUT_CHANNELS]; + +// prepare the objects as externs (for config_app to not bloat) +using Motate::IRQPin; +using Motate::PWMOutputPin; +using Motate::PWMLikeOutputPin; +template +using OutputType = typename std::conditional, PWMLikeOutputPin>::type; + +extern gpioDigitalInputPin> din1; +extern gpioDigitalInputPin> din2; +extern gpioDigitalInputPin> din3; +extern gpioDigitalInputPin> din4; +extern gpioDigitalInputPin> din5; +extern gpioDigitalInputPin> din6; +extern gpioDigitalInputPin> din7; +extern gpioDigitalInputPin> din8; +extern gpioDigitalInputPin> din9; +// extern gpioDigitalInputPin> din10; +// extern gpioDigitalInputPin> din11; +// extern gpioDigitalInputPin> din12; + +extern gpioDigitalOutputPin> dout1; +extern gpioDigitalOutputPin> dout2; +extern gpioDigitalOutputPin> dout3; +extern gpioDigitalOutputPin> dout4; +extern gpioDigitalOutputPin> dout5; +extern gpioDigitalOutputPin> dout6; +extern gpioDigitalOutputPin> dout7; +extern gpioDigitalOutputPin> dout8; +extern gpioDigitalOutputPin> dout9; +extern gpioDigitalOutputPin> dout10; +extern gpioDigitalOutputPin> dout11; +extern gpioDigitalOutputPin> dout12; +extern gpioDigitalOutputPin> dout13; + + +#endif // End of include guard: BOARD_GPIO_H_ONCE diff --git a/g2core/board/sbv300/hardware.cpp b/g2core/board/sbv300/0_hardware.cpp similarity index 100% rename from g2core/board/sbv300/hardware.cpp rename to g2core/board/sbv300/0_hardware.cpp diff --git a/g2core/board/sbv300/board_gpio.cpp b/g2core/board/sbv300/board_gpio.cpp new file mode 100644 index 000000000..4daf011d8 --- /dev/null +++ b/g2core/board/sbv300/board_gpio.cpp @@ -0,0 +1,108 @@ +/* + * gpio.cpp - digital IO handling functions + * This file is part of the g2core project + * + * Copyright (c) 2015 - 2107 Alden S. Hart, Jr. + * Copyright (c) 2015 - 2017 Robert Giseburt + * + * This file ("the software") is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License, version 2 as published by the + * Free Software Foundation. You should have received a copy of the GNU General Public + * License, version 2 along with the software. If not, see . + * + * As a special exception, you may use this file as part of a software library without + * restriction. Specifically, if other files instantiate templates or use macros or + * inline functions from this file, or you compile this file and link it with other + * files to produce an executable, this file does not by itself cause the resulting + * executable to be covered by the GNU General Public License. This exception does not + * however invalidate any other reasons why the executable file might be covered by the + * GNU General Public License. + * + * THE SOFTWARE IS DISTRIBUTED IN THE HOPE THAT IT WILL BE USEFUL, BUT WITHOUT ANY + * WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES + * OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT + * SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF + * OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + */ +/* Switch Modes + * + * The switches are considered to be homing switches when cycle_state is + * CYCLE_HOMING. At all other times they are treated as limit switches: + * - Hitting a homing switch puts the current move into feedhold + * - Hitting a limit switch causes the machine to shut down and go into lockdown until reset + * + * The normally open switch modes (NO) trigger an interrupt on the falling edge + * and lockout subsequent interrupts for the defined lockout period. This approach + * beats doing debouncing as an integration as switches fire immediately. + * + * The normally closed switch modes (NC) trigger an interrupt on the rising edge + * and lockout subsequent interrupts for the defined lockout period. Ditto on the method. + */ + +#include "../../g2core.h" // #1 +#include "config.h" // #2 +#include "gpio.h" +#include "hardware.h" +#include "canonical_machine.h" + +#include "text_parser.h" +#include "controller.h" +#include "util.h" +#include "report.h" +#include "xio.h" + +#include "MotateTimers.h" + +/**** Setup Actual Objects ****/ + +gpioDigitalInputPin> din1 {DI1_MODE, 1}; +gpioDigitalInputPin> din2 {DI2_MODE, 2}; +gpioDigitalInputPin> din3 {DI3_MODE, 3}; +gpioDigitalInputPin> din4 {DI4_MODE, 4}; +gpioDigitalInputPin> din5 {DI5_MODE, 5}; +gpioDigitalInputPin> din6 {DI6_MODE, 6}; +gpioDigitalInputPin> din7 {DI7_MODE, 7}; +gpioDigitalInputPin> din8 {DI8_MODE, 8}; +gpioDigitalInputPin> din9 {DI9_MODE, 9}; +// gpioDigitalInputPin> din10 {DI10_MODE, 10}; +// gpioDigitalInputPin> din11 {DI11_MODE, 11}; +// gpioDigitalInputPin> din12 {DI12_MODE, 12}; + +gpioDigitalOutputPin> dout1 { DO1_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout2 { DO2_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout3 { DO3_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout4 { DO4_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout5 { DO5_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout6 { DO6_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout7 { DO7_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout8 { DO8_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout9 { DO9_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout10 { DO10_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout11 { DO11_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout12 { DO12_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout13 { DO13_MODE, (uint32_t)200000 }; + +/**** Setup Arrays - these are extern and MUST match the board_gpio.h ****/ + +gpioDigitalInput* const d_in[] = {&din1, &din2, &din3, &din4, &din5, &din6, &din7, &din8, &din9}; +gpioDigitalOutput* const d_out[] = {&dout1, &dout2, &dout3, &dout4, &dout5, &dout6, &dout7, &dout8, &dout9, &dout10, &dout11, &dout12, &dout13}; +// not yet used +// gpioAnalogInput* a_in[A_IN_CHANNELS]; +// gpioAnalogOutput* a_out[A_OUT_CHANNELS]; + +/************************************************************************************ + **** CODE ************************************************************************** + ************************************************************************************/ +/* + * gpio_reset() - reset inputs and outputs (no initialization) + */ + + +void outputs_reset(void) { + // nothing to do +} + +void inputs_reset(void) { + // nothing to do +} diff --git a/g2core/board/sbv300/board_gpio.h b/g2core/board/sbv300/board_gpio.h new file mode 100644 index 000000000..25a1cddcd --- /dev/null +++ b/g2core/board/sbv300/board_gpio.h @@ -0,0 +1,90 @@ +/* + * gpio.h - Digital IO handling functions + * This file is part of the g2core project + * + * Copyright (c) 2015 - 2017 Alden S. Hart, Jr. + * Copyright (c) 2015 - 2017 Robert Giseburt + * + * This file ("the software") is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License, version 2 as published by the + * Free Software Foundation. You should have received a copy of the GNU General Public + * License, version 2 along with the software. If not, see . + * + * As a special exception, you may use this file as part of a software library without + * restriction. Specifically, if other files instantiate templates or use macros or + * inline functions from this file, or you compile this file and link it with other + * files to produce an executable, this file does not by itself cause the resulting + * executable to be covered by the GNU General Public License. This exception does not + * however invalidate any other reasons why the executable file might be covered by the + * GNU General Public License. + * + * THE SOFTWARE IS DISTRIBUTED IN THE HOPE THAT IT WILL BE USEFUL, BUT WITHOUT ANY + * WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES + * OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT + * SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF + * OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + */ +#ifndef BOARD_GPIO_H_ONCE +#define BOARD_GPIO_H_ONCE + +// this file is included from the bottom of gpio.h, but we do this for completeness +#include "../../gpio.h" + +/* + * GPIO defines + */ +//--- change as required for board and switch hardware ---// + +#define D_IN_CHANNELS 9 // v9 // number of digital inputs supported +#define D_OUT_CHANNELS 13 // number of digital outputs supported +#define A_IN_CHANNELS 0 // number of analog inputs supported +#define A_OUT_CHANNELS 0 // number of analog outputs supported + +#define INPUT_LOCKOUT_MS 10 // milliseconds to go dead after input firing + +/* + * The GPIO objects themselves - this must match up with board_gpio.cpp! + */ + +extern gpioDigitalInput* const d_in[D_IN_CHANNELS]; +extern gpioDigitalOutput* const d_out[D_OUT_CHANNELS]; +// extern gpioAnalogInput* a_in[A_IN_CHANNELS]; +// extern gpioAnalogOutput* a_out[A_OUT_CHANNELS]; + +// prepare the objects as externs (for config_app to not bloat) +using Motate::IRQPin; +using Motate::PWMOutputPin; +using Motate::PWMLikeOutputPin; +template +using OutputType = typename std::conditional, PWMLikeOutputPin>::type; + +extern gpioDigitalInputPin> din1; +extern gpioDigitalInputPin> din2; +extern gpioDigitalInputPin> din3; +extern gpioDigitalInputPin> din4; +extern gpioDigitalInputPin> din5; +extern gpioDigitalInputPin> din6; +extern gpioDigitalInputPin> din7; +extern gpioDigitalInputPin> din8; +extern gpioDigitalInputPin> din9; +// extern gpioDigitalInputPin> din10; +// extern gpioDigitalInputPin> din11; +// extern gpioDigitalInputPin> din12; + +extern gpioDigitalOutputPin> dout1; +extern gpioDigitalOutputPin> dout2; +extern gpioDigitalOutputPin> dout3; +extern gpioDigitalOutputPin> dout4; +extern gpioDigitalOutputPin> dout5; +extern gpioDigitalOutputPin> dout6; +extern gpioDigitalOutputPin> dout7; +extern gpioDigitalOutputPin> dout8; +extern gpioDigitalOutputPin> dout9; +extern gpioDigitalOutputPin> dout10; +extern gpioDigitalOutputPin> dout11; +extern gpioDigitalOutputPin> dout12; +extern gpioDigitalOutputPin> dout13; + + +#endif // End of include guard: BOARD_GPIO_H_ONCE diff --git a/g2core/config_app.cpp b/g2core/config_app.cpp index d8dc5b69a..ff4179966 100644 --- a/g2core/config_app.cpp +++ b/g2core/config_app.cpp @@ -483,108 +483,109 @@ const cfgItem_t cfgArray[] = { { "c","czb",_fip, 3, cm_print_zb, get_flt, set_flt, (float *)&cm.a[AXIS_C].zero_backoff, C_ZERO_BACKOFF }, // Digital input configs - { "di1","di1mo",_fip, 0, io_print_mo, get_int8,io_set_mo, (float *)&d_in[0].mode, DI1_MODE }, - { "di1","di1ac",_fip, 0, io_print_ac, get_ui8, io_set_ac, (float *)&d_in[0].action, DI1_ACTION }, - { "di1","di1fn",_fip, 0, io_print_fn, get_ui8, io_set_fn, (float *)&d_in[0].function, DI1_FUNCTION }, + { "di1","di1mo",_fip, 0, din_print_mo, din_get_mo, din_set_mo, (float *)&din1, DI1_MODE }, + { "di1","di1ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din1, DI1_ACTION }, + { "di1","di1fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din1, DI1_FUNCTION }, - { "di2","di2mo",_fip, 0, io_print_mo, get_int8,io_set_mo, (float *)&d_in[1].mode, DI2_MODE }, - { "di2","di2ac",_fip, 0, io_print_ac, get_ui8, io_set_ac, (float *)&d_in[1].action, DI2_ACTION }, - { "di2","di2fn",_fip, 0, io_print_fn, get_ui8, io_set_fn, (float *)&d_in[1].function, DI2_FUNCTION }, + { "di2","di2mo",_fip, 0, din_print_mo, din_get_mo, din_set_mo, (float *)&din2, DI2_MODE }, + { "di2","di2ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din2, DI2_ACTION }, + { "di2","di2fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din2, DI2_FUNCTION }, - { "di3","di3mo",_fip, 0, io_print_mo, get_int8,io_set_mo, (float *)&d_in[2].mode, DI3_MODE }, - { "di3","di3ac",_fip, 0, io_print_ac, get_ui8, io_set_ac, (float *)&d_in[2].action, DI3_ACTION }, - { "di3","di3fn",_fip, 0, io_print_fn, get_ui8, io_set_fn, (float *)&d_in[2].function, DI3_FUNCTION }, + { "di3","di3mo",_fip, 0, din_print_mo, din_get_mo, din_set_mo, (float *)&din3, DI3_MODE }, + { "di3","di3ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din3, DI3_ACTION }, + { "di3","di3fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din3, DI3_FUNCTION }, - { "di4","di4mo",_fip, 0, io_print_mo, get_int8,io_set_mo, (float *)&d_in[3].mode, DI4_MODE }, - { "di4","di4ac",_fip, 0, io_print_ac, get_ui8, io_set_ac, (float *)&d_in[3].action, DI4_ACTION }, - { "di4","di4fn",_fip, 0, io_print_fn, get_ui8, io_set_fn, (float *)&d_in[3].function, DI4_FUNCTION }, + { "di4","di4mo",_fip, 0, din_print_mo, din_get_mo, din_set_mo, (float *)&din4, DI4_MODE }, + { "di4","di4ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din4, DI4_ACTION }, + { "di4","di4fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din4, DI4_FUNCTION }, - { "di5","di5mo",_fip, 0, io_print_mo, get_int8,io_set_mo, (float *)&d_in[4].mode, DI5_MODE }, - { "di5","di5ac",_fip, 0, io_print_ac, get_ui8, io_set_ac, (float *)&d_in[4].action, DI5_ACTION }, - { "di5","di5fn",_fip, 0, io_print_fn, get_ui8, io_set_fn, (float *)&d_in[4].function, DI5_FUNCTION }, + { "di5","di5mo",_fip, 0, din_print_mo, din_get_mo, din_set_mo, (float *)&din5, DI5_MODE }, + { "di5","di5ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din5, DI5_ACTION }, + { "di5","di5fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din5, DI5_FUNCTION }, - { "di6","di6mo",_fip, 0, io_print_mo, get_int8,io_set_mo, (float *)&d_in[5].mode, DI6_MODE }, - { "di6","di6ac",_fip, 0, io_print_ac, get_ui8, io_set_ac, (float *)&d_in[5].action, DI6_ACTION }, - { "di6","di6fn",_fip, 0, io_print_fn, get_ui8, io_set_fn, (float *)&d_in[5].function, DI6_FUNCTION }, + { "di6","di6mo",_fip, 0, din_print_mo, din_get_mo, din_set_mo, (float *)&din6, DI6_MODE }, + { "di6","di6ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din6, DI6_ACTION }, + { "di6","di6fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din6, DI6_FUNCTION }, - { "di7","di7mo",_fip, 0, io_print_mo, get_int8,io_set_mo, (float *)&d_in[6].mode, DI7_MODE }, - { "di7","di7ac",_fip, 0, io_print_ac, get_ui8, io_set_ac, (float *)&d_in[6].action, DI7_ACTION }, - { "di7","di7fn",_fip, 0, io_print_fn, get_ui8, io_set_fn, (float *)&d_in[6].function, DI7_FUNCTION }, + { "di7","di7mo",_fip, 0, din_print_mo, din_get_mo, din_set_mo, (float *)&din7, DI7_MODE }, + { "di7","di7ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din7, DI7_ACTION }, + { "di7","di7fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din7, DI7_FUNCTION }, - { "di8","di8mo",_fip, 0, io_print_mo, get_int8,io_set_mo, (float *)&d_in[7].mode, DI8_MODE }, - { "di8","di8ac",_fip, 0, io_print_ac, get_ui8, io_set_ac, (float *)&d_in[7].action, DI8_ACTION }, - { "di8","di8fn",_fip, 0, io_print_fn, get_ui8, io_set_fn, (float *)&d_in[7].function, DI8_FUNCTION }, + { "di8","di8mo",_fip, 0, din_print_mo, din_get_mo, din_set_mo, (float *)&din8, DI8_MODE }, + { "di8","di8ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din8, DI8_ACTION }, + { "di8","di8fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din8, DI8_FUNCTION }, #if (D_IN_CHANNELS >= 9) - { "di9","di9mo",_fip, 0, io_print_mo, get_int8,io_set_mo, (float *)&d_in[8].mode, DI9_MODE }, - { "di9","di9ac",_fip, 0, io_print_ac, get_ui8, io_set_ac, (float *)&d_in[8].action, DI9_ACTION }, - { "di9","di9fn",_fip, 0, io_print_fn, get_ui8, io_set_fn, (float *)&d_in[8].function, DI9_FUNCTION }, + { "di9","di9mo",_fip, 0, din_print_mo, din_get_mo, din_set_mo, (float *)&din9, DI9_MODE }, + { "di9","di9ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din9, DI9_ACTION }, + { "di9","di9fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din9, DI9_FUNCTION }, #endif #if (D_IN_CHANNELS >= 10) - { "di10","di10mo",_fip, 0, io_print_mo, get_int8,io_set_mo, (float *)&d_in[9].mode, DI10_MODE }, - { "di10","di10ac",_fip, 0, io_print_ac, get_ui8, io_set_ac, (float *)&d_in[9].action, DI10_ACTION }, - { "di10","di10fn",_fip, 0, io_print_fn, get_ui8, io_set_fn, (float *)&d_in[9].function, DI10_FUNCTION }, + { "di10","di10mo",_fip, 0, din_print_mo, din_get_mo, din_set_mo, (float *)&din10, DI10_MODE }, + { "di10","di10ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din10, DI10_ACTION }, + { "di10","di10fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din10, DI10_FUNCTION }, #endif #if (D_IN_CHANNELS >= 11) - { "di11","di11mo",_fip, 0, io_print_mo, get_int8,io_set_mo, (float *)&d_in[10].mode, DI11_MODE }, - { "di11","di11ac",_fip, 0, io_print_ac, get_ui8, io_set_ac, (float *)&d_in[10].action, DI11_ACTION }, - { "di11","di11fn",_fip, 0, io_print_fn, get_ui8, io_set_fn, (float *)&d_in[10].function, DI11_FUNCTION }, + { "di11","di11mo",_fip, 0, din_print_mo, din_get_mo, din_set_mo, (float *)&din11, DI11_MODE }, + { "di11","di11ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din11, DI11_ACTION }, + { "di11","di11fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din11, DI11_FUNCTION }, #endif #if (D_IN_CHANNELS >= 12) - { "di12","di12mo",_fip, 0, io_print_mo, get_int8,io_set_mo, (float *)&d_in[11].mode, DI12_MODE }, - { "di12","di12ac",_fip, 0, io_print_ac, get_ui8, io_set_ac, (float *)&d_in[11].action, DI12_ACTION }, - { "di12","di12fn",_fip, 0, io_print_fn, get_ui8, io_set_fn, (float *)&d_in[11].function, DI12_FUNCTION }, + { "di12","di12mo",_fip, 0, din_print_mo, din_get_mo, din_set_mo, (float *)&din12, DI12_MODE }, + { "di12","di12ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din12, DI12_ACTION }, + { "di12","di12fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din12, DI12_FUNCTION }, #endif // Digital input state readers - { "in","in1", _f0, 0, io_print_in, io_get_input, set_ro, (float *)&cs.null, 0 }, - { "in","in2", _f0, 0, io_print_in, io_get_input, set_ro, (float *)&cs.null, 0 }, - { "in","in3", _f0, 0, io_print_in, io_get_input, set_ro, (float *)&cs.null, 0 }, - { "in","in4", _f0, 0, io_print_in, io_get_input, set_ro, (float *)&cs.null, 0 }, - { "in","in5", _f0, 0, io_print_in, io_get_input, set_ro, (float *)&cs.null, 0 }, - { "in","in6", _f0, 0, io_print_in, io_get_input, set_ro, (float *)&cs.null, 0 }, - { "in","in7", _f0, 0, io_print_in, io_get_input, set_ro, (float *)&cs.null, 0 }, - { "in","in8", _f0, 0, io_print_in, io_get_input, set_ro, (float *)&cs.null, 0 }, + { "in","in1", _f0, 0, din_print_in, din_get_input, set_ro, (float *)&din1, 0 }, + { "in","in2", _f0, 0, din_print_in, din_get_input, set_ro, (float *)&din2, 0 }, + { "in","in3", _f0, 0, din_print_in, din_get_input, set_ro, (float *)&din3, 0 }, + { "in","in4", _f0, 0, din_print_in, din_get_input, set_ro, (float *)&din4, 0 }, + { "in","in5", _f0, 0, din_print_in, din_get_input, set_ro, (float *)&din5, 0 }, + { "in","in6", _f0, 0, din_print_in, din_get_input, set_ro, (float *)&din6, 0 }, + { "in","in7", _f0, 0, din_print_in, din_get_input, set_ro, (float *)&din7, 0 }, + { "in","in8", _f0, 0, din_print_in, din_get_input, set_ro, (float *)&din8, 0 }, #if (D_IN_CHANNELS >= 9) - { "in","in9", _f0, 0, io_print_in, io_get_input, set_ro, (float *)&cs.null, 0 }, + { "in","in9", _f0, 0, din_print_in, din_get_input, set_ro, (float *)&din9, 0 }, #endif #if (D_IN_CHANNELS >= 10) - { "in","in10", _f0, 0, io_print_in, io_get_input, set_ro, (float *)&cs.null, 0 }, + { "in","in10", _f0, 0, din_print_in, din_get_input, set_ro, (float *)&din10,0 }, #endif #if (D_IN_CHANNELS >= 11) - { "in","in11", _f0, 0, io_print_in, io_get_input, set_ro, (float *)&cs.null, 0 }, + { "in","in11", _f0, 0, din_print_in, din_get_input, set_ro, (float *)&din11,0 }, #endif #if (D_IN_CHANNELS >= 12) - { "in","in12", _f0, 0, io_print_in, io_get_input, set_ro, (float *)&cs.null, 0 }, + { "in","in12", _f0, 0, din_print_in, din_get_input, set_ro, (float *)&din12,0 }, #endif // digital output configs - { "do1", "do1mo", _fip, 0, io_print_domode, get_int8, io_set_domode, (float *)&d_out[0].mode, DO1_MODE }, - { "do2", "do2mo", _fip, 0, io_print_domode, get_int8, io_set_domode, (float *)&d_out[1].mode, DO2_MODE }, - { "do3", "do3mo", _fip, 0, io_print_domode, get_int8, io_set_domode, (float *)&d_out[2].mode, DO3_MODE }, - { "do4", "do4mo", _fip, 0, io_print_domode, get_int8, io_set_domode, (float *)&d_out[3].mode, DO4_MODE }, - { "do5", "do5mo", _fip, 0, io_print_domode, get_int8, io_set_domode, (float *)&d_out[4].mode, DO5_MODE }, - { "do6", "do6mo", _fip, 0, io_print_domode, get_int8, io_set_domode, (float *)&d_out[5].mode, DO6_MODE }, - { "do7", "do7mo", _fip, 0, io_print_domode, get_int8, io_set_domode, (float *)&d_out[6].mode, DO7_MODE }, - { "do8", "do8mo", _fip, 0, io_print_domode, get_int8, io_set_domode, (float *)&d_out[7].mode, DO8_MODE }, - { "do9", "do9mo", _fip, 0, io_print_domode, get_int8, io_set_domode, (float *)&d_out[8].mode, DO9_MODE }, - { "do10","do10mo",_fip, 0, io_print_domode, get_int8, io_set_domode, (float *)&d_out[9].mode, DO10_MODE }, - { "do11","do11mo",_fip, 0, io_print_domode, get_int8, io_set_domode, (float *)&d_out[10].mode, DO11_MODE }, - { "do12","do12mo",_fip, 0, io_print_domode, get_int8, io_set_domode, (float *)&d_out[11].mode, DO12_MODE }, - { "do13","do13mo",_fip, 0, io_print_domode, get_int8, io_set_domode, (float *)&d_out[12].mode, DO13_MODE }, + { "do1", "do1mo", _fip, 0, dout_print_mo, dout_get_mo, dout_set_mo, (float *)&dout1, DO1_MODE }, + { "do2", "do2mo", _fip, 0, dout_print_mo, dout_get_mo, dout_set_mo, (float *)&dout2, DO2_MODE }, + { "do3", "do3mo", _fip, 0, dout_print_mo, dout_get_mo, dout_set_mo, (float *)&dout3, DO3_MODE }, + { "do4", "do4mo", _fip, 0, dout_print_mo, dout_get_mo, dout_set_mo, (float *)&dout4, DO4_MODE }, + { "do5", "do5mo", _fip, 0, dout_print_mo, dout_get_mo, dout_set_mo, (float *)&dout5, DO5_MODE }, + { "do6", "do6mo", _fip, 0, dout_print_mo, dout_get_mo, dout_set_mo, (float *)&dout6, DO6_MODE }, + { "do7", "do7mo", _fip, 0, dout_print_mo, dout_get_mo, dout_set_mo, (float *)&dout7, DO7_MODE }, + { "do8", "do8mo", _fip, 0, dout_print_mo, dout_get_mo, dout_set_mo, (float *)&dout8, DO8_MODE }, + { "do9", "do9mo", _fip, 0, dout_print_mo, dout_get_mo, dout_set_mo, (float *)&dout9, DO9_MODE }, + { "do10","do10mo",_fip, 0, dout_print_mo, dout_get_mo, dout_set_mo, (float *)&dout10, DO10_MODE }, + { "do11","do11mo",_fip, 0, dout_print_mo, dout_get_mo, dout_set_mo, (float *)&dout11, DO11_MODE }, + { "do12","do12mo",_fip, 0, dout_print_mo, dout_get_mo, dout_set_mo, (float *)&dout12, DO12_MODE }, + { "do13","do13mo",_fip, 0, dout_print_mo, dout_get_mo, dout_set_mo, (float *)&dout13, DO13_MODE }, // Digital output state readers (default to non-active) - { "out","out1", _f0, 2, io_print_out, io_get_output, io_set_output, (float *)&cs.null, 0 }, - { "out","out2", _f0, 2, io_print_out, io_get_output, io_set_output, (float *)&cs.null, 0 }, - { "out","out3", _f0, 2, io_print_out, io_get_output, io_set_output, (float *)&cs.null, 0 }, - { "out","out4", _f0, 2, io_print_out, io_get_output, io_set_output, (float *)&cs.null, 0 }, - { "out","out5", _f0, 2, io_print_out, io_get_output, io_set_output, (float *)&cs.null, 0 }, - { "out","out6", _f0, 2, io_print_out, io_get_output, io_set_output, (float *)&cs.null, 0 }, - { "out","out7", _f0, 2, io_print_out, io_get_output, io_set_output, (float *)&cs.null, 0 }, - { "out","out8", _f0, 2, io_print_out, io_get_output, io_set_output, (float *)&cs.null, 0 }, - { "out","out9", _f0, 2, io_print_out, io_get_output, io_set_output, (float *)&cs.null, 0 }, - { "out","out10", _f0, 2, io_print_out, io_get_output, io_set_output, (float *)&cs.null, 0 }, - { "out","out11", _f0, 2, io_print_out, io_get_output, io_set_output, (float *)&cs.null, 0 }, - { "out","out12", _f0, 2, io_print_out, io_get_output, io_set_output, (float *)&cs.null, 0 }, + { "out","out1", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&dout1, 0 }, + { "out","out2", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&dout2, 0 }, + { "out","out3", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&dout3, 0 }, + { "out","out4", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&dout4, 0 }, + { "out","out5", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&dout5, 0 }, + { "out","out6", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&dout6, 0 }, + { "out","out7", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&dout7, 0 }, + { "out","out8", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&dout8, 0 }, + { "out","out9", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&dout9, 0 }, + { "out","out10", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&dout10, 0 }, + { "out","out11", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&dout11, 0 }, + { "out","out12", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&dout12, 0 }, + { "out","out13", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&dout13, 0 }, // PWM settings { "p1","p1frq",_fip, 0, pwm_print_p1frq, get_flt, pwm_set_pwm,(float *)&pwm.c[PWM_1].frequency, P1_PWM_FREQUENCY }, @@ -983,8 +984,8 @@ const cfgItem_t cfgArray[] = { { "sys","mfo", _fipn,3, cm_print_mfo, get_flt,cm_set_mfo,(float *)&cm.gmx.mfo_factor, FEED_OVERRIDE_FACTOR}, { "sys","mtoe",_fipn,0, cm_print_mtoe,get_ui8, set_01, (float *)&cm.gmx.mto_enable, TRAVERSE_OVERRIDE_ENABLE}, { "sys","mto", _fipn,3, cm_print_mto, get_flt,cm_set_mto,(float *)&cm.gmx.mto_factor, TRAVERSE_OVERRIDE_FACTOR}, - - // Power management + + // Power management { "sys","mt", _fipn,2, st_print_mt, get_flt, st_set_mt, (float *)&st_cfg.motor_power_timeout, MOTOR_POWER_TIMEOUT}, { "", "me", _f0, 0, st_print_me, st_set_me, st_set_me,(float *)&cs.null, 0 }, // SET to enable motors (null value sets to maintain compatability) { "", "md", _f0, 0, st_print_md, st_set_md, st_set_md,(float *)&cs.null, 0 }, // SET to disable motors (null value sets to maintain compatability) diff --git a/g2core/gpio.cpp b/g2core/gpio.cpp index e731386ca..132a7aad4 100644 --- a/g2core/gpio.cpp +++ b/g2core/gpio.cpp @@ -57,245 +57,13 @@ #include "MotateTimers.h" using namespace Motate; -/**** Allocate structures ****/ - -d_in_t d_in[D_IN_CHANNELS]; -d_out_t d_out[D_OUT_CHANNELS]; -a_in_t a_in[A_IN_CHANNELS]; -a_out_t a_out[A_OUT_CHANNELS]; - -/**** Extended DI structure ****/ - -// To be merged with ioDigitalInput later. -// For now, we use a pointer to the correct d_in, since the old code did. -// input_pin_num is the Motate pin number. -// ext_pin_number is the JSON ("external") pin number, as in "di1". -template -struct ioDigitalInputExt { - IRQPin input_pin; - - /* Priority only needs set once in the system during startup. - * However, if we wish to switch the interrupt trigger, here are other options: - * kPinInterruptOnRisingEdge - * kPinInterruptOnFallingEdge - * - * To change the trigger or priority provide a third paramater intValue that will - * be called as pin.setInterrupts(intValue), or call pin.setInterrupts at any point. - * Note that it may cause an interrupt to fire *immediately*! - * intValue defaults to kPinInterruptOnChange|kPinInterruptPriorityMedium if not specified. - */ - ioDigitalInputExt() : input_pin {kPullUp|kDebounce, [&]{this->pin_changed();}} { - }; - - ioDigitalInputExt(const ioDigitalInputExt&) = delete; // delete copy - ioDigitalInputExt(ioDigitalInputExt&&) = delete; // delete move - - static constexpr d_in_t *in = &d_in[ext_pin_number-1]; - - void reset() { - if (D_IN_CHANNELS < ext_pin_number) { return; } - - if (in->mode == IO_MODE_DISABLED) { - in->state = INPUT_DISABLED; - return; - } - - bool pin_value = (bool)input_pin; - int8_t pin_value_corrected = (pin_value ^ ((int)in->mode ^ 1)); // correct for NO or NC mode - in->state = (ioState)pin_value_corrected; - } - - void pin_changed() { - if (D_IN_CHANNELS < ext_pin_number) { return; } - - // return if input is disabled (not supposed to happen) - if (in->mode == IO_MODE_DISABLED) { - in->state = INPUT_DISABLED; - return; - } - - // return if the input is in lockout period (take no action) - if (in->lockout_timer.isSet() && !in->lockout_timer.isPast()) { - return; - } - - // return if no change in state - bool pin_value = (bool)input_pin; - int8_t pin_value_corrected = (pin_value ^ ((int)in->mode ^ 1)); // correct for NO or NC mode - if (in->state == (ioState)pin_value_corrected) { - return; - } - - // lockout the pin for lockout_ms - in->lockout_timer.set(in->lockout_ms); - - // record the changed state - in->state = (ioState)pin_value_corrected; - if (pin_value_corrected == INPUT_ACTIVE) { - in->edge = INPUT_EDGE_LEADING; - } else { - in->edge = INPUT_EDGE_TRAILING; - } - - // perform homing operations if in homing mode - if (in->homing_mode) { - if (in->edge == INPUT_EDGE_LEADING) { // we only want the leading edge to fire - en_take_encoder_snapshot(); - cm_start_hold(); - } - return; - } - - // perform probing operations if in probing mode - if (in->probing_mode) { - // We want to capture either way. - // Probing tests the start condition for the correct direction ahead of time. - // If we see any edge, it's the right one. - en_take_encoder_snapshot(); - cm_start_hold(); - return; - } +/**** + * + * Important: Do not directly allocate or access pins here! + * Do that in board_gpio.cpp! + * + ****/ - // *** NOTE: From this point on all conditionals assume we are NOT in homing or probe mode *** - - // trigger the action on leading edges - if (in->edge == INPUT_EDGE_LEADING) { - if (in->action == INPUT_ACTION_STOP) { - cm_start_hold(); - } - if (in->action == INPUT_ACTION_FAST_STOP) { - cm_start_hold(); // for now is same as STOP - } - if (in->action == INPUT_ACTION_HALT) { - cm_halt_all(); // hard stop, including spindle and coolant - } - if (in->action == INPUT_ACTION_ALARM) { - char msg[10]; - sprintf(msg, "input %d", ext_pin_number); - cm_alarm(STAT_ALARM, msg); - } - if (in->action == INPUT_ACTION_SHUTDOWN) { - char msg[10]; - sprintf(msg, "input %d", ext_pin_number); - cm_shutdown(STAT_SHUTDOWN, msg); - } - if (in->action == INPUT_ACTION_PANIC) { - char msg[10]; - sprintf(msg, "input %d", ext_pin_number); - cm_panic(STAT_PANIC, msg); - } - if (in->action == INPUT_ACTION_RESET) { - hw_hard_reset(); - } - - // these functions also trigger on the leading edge - - if (in->function == INPUT_FUNCTION_LIMIT) { - cm.limit_requested = ext_pin_number; - - } else if (in->function == INPUT_FUNCTION_SHUTDOWN) { - cm.shutdown_requested = ext_pin_number; - - } else if (in->function == INPUT_FUNCTION_INTERLOCK) { - cm.safety_interlock_disengaged = ext_pin_number; - } - } // if (in->edge == INPUT_EDGE_LEADING) - - // trigger interlock release on trailing edge - if (in->edge == INPUT_EDGE_TRAILING) { - if (in->function == INPUT_FUNCTION_INTERLOCK) { - cm.safety_interlock_reengaged = ext_pin_number; - } - } - - sr_request_status_report(SR_REQUEST_TIMED); //+++++ Put this one back in. - }; -}; - -/**** Setup Low Level Stuff ****/ - -ioDigitalInputExt _din1; -ioDigitalInputExt _din2; -ioDigitalInputExt _din3; -ioDigitalInputExt _din4; -ioDigitalInputExt _din5; -ioDigitalInputExt _din6; -ioDigitalInputExt _din7; -ioDigitalInputExt _din8; -ioDigitalInputExt _din9; -ioDigitalInputExt _din10; -ioDigitalInputExt _din11; -ioDigitalInputExt _din12; - -// Generated with: -// perl -e 'for($i=1;$i<14;$i++) { print "#if OUTPUT${i}_PWM == 1\nstatic PWMOutputPin output_${i}_pin;\n#else\nstatic PWMLikeOutputPin output_${i}_pin;\n#endif\n";}' -// BEGIN generated -#if OUTPUT1_PWM == 1 -static PWMOutputPin output_1_pin {(DO1_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; -#else -static PWMLikeOutputPin output_1_pin {(DO1_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; -#endif -#if OUTPUT2_PWM == 1 -static PWMOutputPin output_2_pin {(DO2_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; -#else -static PWMLikeOutputPin output_2_pin {(DO2_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; -#endif -#if OUTPUT3_PWM == 1 -static PWMOutputPin output_3_pin {(DO3_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; -#else -static PWMLikeOutputPin output_3_pin {(DO3_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; -#endif -#if OUTPUT4_PWM == 1 -static PWMOutputPin output_4_pin {(DO4_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; -#else -static PWMLikeOutputPin output_4_pin {(DO4_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; -#endif -#if OUTPUT5_PWM == 1 -static PWMOutputPin output_5_pin {(DO5_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; -#else -static PWMLikeOutputPin output_5_pin {(DO5_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; -#endif -#if OUTPUT6_PWM == 1 -static PWMOutputPin output_6_pin {(DO6_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; -#else -static PWMLikeOutputPin output_6_pin {(DO6_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; -#endif -#if OUTPUT7_PWM == 1 -static PWMOutputPin output_7_pin {(DO7_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; -#else -static PWMLikeOutputPin output_7_pin {(DO7_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; -#endif -#if OUTPUT8_PWM == 1 -static PWMOutputPin output_8_pin {(DO8_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; -#else -static PWMLikeOutputPin output_8_pin {(DO8_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; -#endif -#if OUTPUT9_PWM == 1 -static PWMOutputPin output_9_pin {(DO9_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; -#else -static PWMLikeOutputPin output_9_pin {(DO9_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; -#endif -#if OUTPUT10_PWM == 1 -static PWMOutputPin output_10_pin {(DO10_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; -#else -static PWMLikeOutputPin output_10_pin {(DO10_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; -#endif -#if OUTPUT11_PWM == 1 -static PWMOutputPin output_11_pin {(DO11_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; -#else -static PWMLikeOutputPin output_11_pin {(DO11_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; -#endif -#if OUTPUT12_PWM == 1 -static PWMOutputPin output_12_pin {(DO12_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; -#else -static PWMLikeOutputPin output_12_pin {(DO12_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; -#endif -#if OUTPUT13_PWM == 1 -static PWMOutputPin output_13_pin {(DO13_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; -#else -static PWMLikeOutputPin output_13_pin {(DO13_MODE == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow, 200000}; -#endif -// END generated /************************************************************************************ **** CODE ************************************************************************** @@ -307,99 +75,11 @@ static PWMLikeOutputPin output_13_pin {(DO13_MODE == IO_AC void gpio_init(void) { - // These are here due to an unfound glitch where for Timer-based pins the frequency isn't getting set. - - // Generated with: - // perl -e 'for($i=1;$i<14;$i++) { print "output_${i}_pin.setFrequency(200000);\n";}' - // BEGIN generated -// output_1_pin.setFrequency(200000); -// output_2_pin.setFrequency(200000); -// output_3_pin.setFrequency(200000); -// output_4_pin.setFrequency(200000); -// output_5_pin.setFrequency(200000); -// output_6_pin.setFrequency(200000); -// output_7_pin.setFrequency(200000); -// output_8_pin.setFrequency(200000); -// output_9_pin.setFrequency(200000); -// output_10_pin.setFrequency(200000); -// output_11_pin.setFrequency(200000); -// output_12_pin.setFrequency(200000); -// output_13_pin.setFrequency(200000); - // END generated - return(gpio_reset()); } -void outputs_reset(void) { - // If the output is ACTIVE_LOW set it to 1. ACTIVE_HIGH gets set to 0. -#if D_OUT_CHANNELS >= 1 - if (d_out[1-1].mode != IO_MODE_DISABLED) { (output_1_pin = (d_out[1-1].mode == IO_ACTIVE_LOW) ? 1.0 : 0.0); } -#endif -#if D_OUT_CHANNELS >= 2 - if (d_out[2-1].mode != IO_MODE_DISABLED) { (output_2_pin = (d_out[2-1].mode == IO_ACTIVE_LOW) ? 1.0 : 0.0); } -#endif -#if D_OUT_CHANNELS >= 3 - if (d_out[3-1].mode != IO_MODE_DISABLED) { (output_3_pin = (d_out[3-1].mode == IO_ACTIVE_LOW) ? 1.0 : 0.0); } -#endif -#if D_OUT_CHANNELS >= 4 - if (d_out[4-1].mode != IO_MODE_DISABLED) { (output_4_pin = (d_out[4-1].mode == IO_ACTIVE_LOW) ? 1.0 : 0.0); } -#endif -#if D_OUT_CHANNELS >= 5 - if (d_out[5-1].mode != IO_MODE_DISABLED) { (output_5_pin = (d_out[5-1].mode == IO_ACTIVE_LOW) ? 1.0 : 0.0); } -#endif -#if D_OUT_CHANNELS >= 6 - if (d_out[6-1].mode != IO_MODE_DISABLED) { (output_6_pin = (d_out[6-1].mode == IO_ACTIVE_LOW) ? 1.0 : 0.0); } -#endif -#if D_OUT_CHANNELS >= 7 - if (d_out[7-1].mode != IO_MODE_DISABLED) { (output_7_pin = (d_out[7-1].mode == IO_ACTIVE_LOW) ? 1.0 : 0.0); } -#endif -#if D_OUT_CHANNELS >= 8 - if (d_out[8-1].mode != IO_MODE_DISABLED) { (output_8_pin = (d_out[8-1].mode == IO_ACTIVE_LOW) ? 1.0 : 0.0); } -#endif -#if D_OUT_CHANNELS >= 9 - if (d_out[9-1].mode != IO_MODE_DISABLED) { (output_9_pin = (d_out[9-1].mode == IO_ACTIVE_LOW) ? 1.0 : 0.0); } -#endif -#if D_OUT_CHANNELS >= 10 - if (d_out[10-1].mode != IO_MODE_DISABLED) { (output_10_pin = (d_out[10-1].mode == IO_ACTIVE_LOW) ? 1.0 : 0.0); } -#endif -#if D_OUT_CHANNELS >= 11 - if (d_out[11-1].mode != IO_MODE_DISABLED) { (output_11_pin = (d_out[11-1].mode == IO_ACTIVE_LOW) ? 1.0 : 0.0); } -#endif -#if D_OUT_CHANNELS >= 12 - if (d_out[12-1].mode != IO_MODE_DISABLED) { (output_12_pin = (d_out[12-1].mode == IO_ACTIVE_LOW) ? 1.0 : 0.0); } -#endif -#if D_OUT_CHANNELS >= 13 - if (d_out[13-1].mode != IO_MODE_DISABLED) { (output_13_pin = (d_out[13-1].mode == IO_ACTIVE_LOW) ? 1.0 : 0.0); } -#endif -} - -void inputs_reset(void) { - d_in_t *in; - - for (uint8_t i=0; imode == IO_MODE_DISABLED) { - in->state = INPUT_DISABLED; - continue; - } - in->lockout_ms = INPUT_LOCKOUT_MS; - in->lockout_timer.clear(); - } - - _din1.reset(); - _din2.reset(); - _din3.reset(); - _din4.reset(); - _din5.reset(); - _din6.reset(); - _din7.reset(); - _din8.reset(); - _din9.reset(); - _din10.reset(); - _din11.reset(); - _din12.reset(); - -} +// implement void outputs_reset(void) in board_gpio.cpp +// implement void inputs_reset(void) in board_gpio.cpp void gpio_reset(void) { @@ -407,24 +87,9 @@ void gpio_reset(void) outputs_reset(); } -/****************************** - * Interrupt Service Routines * - ******************************/ -/* - * ARM pin change interrupts are setup above when defining the IRQPins (inside the ioDigitalInputExt). - */ - /******************************************** **** Digital Input Supporting Functions **** ********************************************/ -/* - * switch_rtc_callback() - called from RTC for each RTC tick. - * - * Each switch has a counter which is initially set to negative SW_DEGLITCH_TICKS. - * When a switch closure is DETECTED the count increments for each RTC tick. - * When the count reaches zero the switch is tripped and action occurs. - * The counter continues to increment positive until the lockout is exceeded. - */ /* * gpio_set_homing_mode() - set/clear input to homing mode @@ -432,14 +97,15 @@ void gpio_reset(void) * gpio_get_probing_input() - get probing input * gpio_read_input() - read conditioned input * - (* Note: input_num_ext means EXTERNAL input number -- 1-based + * Note: input_num_ext means EXTERNAL input number -- 1-based + * TODO: lookup the external number to find the internal input, don't assume */ void gpio_set_homing_mode(const uint8_t input_num_ext, const bool is_homing) { if (input_num_ext == 0) { return; } - d_in[input_num_ext-1].homing_mode = is_homing; + d_in[input_num_ext-1]->setIsHoming(is_homing); } void gpio_set_probing_mode(const uint8_t input_num_ext, const bool is_probing) @@ -447,13 +113,13 @@ void gpio_set_probing_mode(const uint8_t input_num_ext, const bool is_probing) if (input_num_ext == 0) { return; } - d_in[input_num_ext-1].probing_mode = is_probing; + d_in[input_num_ext-1]->setIsProbing(is_probing); } -int8_t gpio_get_probing_input(void) +int8_t gpio_get_probing_input(void) { for (uint8_t i = 0; i <= D_IN_CHANNELS; i++) { - if (d_in[i-1].function == INPUT_FUNCTION_PROBE) { + if (d_in[i-1]->getFunction() == INPUT_FUNCTION_PROBE) { return (i); } } @@ -465,7 +131,7 @@ bool gpio_read_input(const uint8_t input_num_ext) if (input_num_ext == 0) { return false; } - return (d_in[input_num_ext-1].state); + return (d_in[input_num_ext-1]->getState()); } @@ -475,207 +141,107 @@ bool gpio_read_input(const uint8_t input_num_ext) * These functions are not part of the NIST defined functions ***********************************************************************************/ -static stat_t _input_set_helper(nvObj_t *nv, const int8_t lower_bound, const int8_t upper_bound) -{ - if ((nv->value < lower_bound) || (nv->value >= upper_bound)) { - return (STAT_INPUT_VALUE_RANGE_ERROR); - } - set_ui8(nv); // will this work in -1 is a valid value? - if (cm_get_machine_state() != MACHINE_INITIALIZING) { - inputs_reset(); - } - return (STAT_OK); -} +// internal helpers to get input and output object from the cfgArray target +// specified by an nv pointer + +template +type* _io(const nvObj_t *nv) { + return reinterpret_cast(cfgArray[nv->index].target); +}; + +gpioDigitalInput* _i(const nvObj_t *nv) { return _io(nv); } +gpioDigitalOutput* _o(const nvObj_t *nv) { return _io(nv); } + + +// static stat_t _input_set_helper(nvObj_t *nv, const int8_t lower_bound, const int8_t upper_bound) +// { +// if ((nv->value < lower_bound) || (nv->value >= upper_bound)) { +// return (STAT_INPUT_VALUE_RANGE_ERROR); +// } +// set_ui8(nv); // will this work in -1 is a valid value? +// if (cm_get_machine_state() != MACHINE_INITIALIZING) { +// inputs_reset(); +// } +// return (STAT_OK); +// } +// +// static stat_t _output_set_helper(nvObj_t *nv, const int8_t lower_bound, const int8_t upper_bound) +// { +// if ((nv->value < lower_bound) || (nv->value >= upper_bound)) { +// return (STAT_INPUT_VALUE_RANGE_ERROR); +// } +// set_ui8(nv); // will this work in -1 is a valid value? +// if (cm_get_machine_state() != MACHINE_INITIALIZING) { +// outputs_reset(); +// } +// return (STAT_OK); +// } -static stat_t _output_set_helper(nvObj_t *nv, const int8_t lower_bound, const int8_t upper_bound) +/* + * Get/set input mode + */ +stat_t din_get_mo(nvObj_t *nv) { - if ((nv->value < lower_bound) || (nv->value >= upper_bound)) { - return (STAT_INPUT_VALUE_RANGE_ERROR); - } - set_ui8(nv); // will this work in -1 is a valid value? - if (cm_get_machine_state() != MACHINE_INITIALIZING) { - outputs_reset(); - } - return (STAT_OK); + return _i(nv)->getMode(nv); } - -stat_t io_set_mo(nvObj_t *nv) // input type or disabled +stat_t din_set_mo(nvObj_t *nv) { -// return (_io_set_helper(nv, IO_MODE_DISABLED, IO_MODE_MAX)); - return (_input_set_helper(nv, IO_ACTIVE_LOW, IO_MODE_MAX)); + return _i(nv)->setMode(nv); } -stat_t io_set_ac(nvObj_t *nv) // input action +/* + * Get/set input action + */ +stat_t din_get_ac(nvObj_t *nv) { - return (_input_set_helper(nv, INPUT_ACTION_NONE, INPUT_ACTION_MAX)); + return _i(nv)->getAction(nv); } - -stat_t io_set_fn(nvObj_t *nv) // input function +stat_t din_set_ac(nvObj_t *nv) { - return (_input_set_helper(nv, INPUT_FUNCTION_NONE, INPUT_FUNCTION_MAX)); + return _i(nv)->setAction(nv); } /* - * io_get_input() - return input state given an nv object + * Get/set input function */ -stat_t io_get_input(nvObj_t *nv) +stat_t din_get_fn(nvObj_t *nv) { - char *num_start = nv->token; - if (*(nv->group) == 0) { - // if we don't have a group, then the group name is in the token - // skip over "in" - num_start+=2; - } - nv->value = d_in[strtol(num_start, NULL, 10)-1].state; - - if (nv->value > 1.1) { - nv->valuetype = TYPE_NULL; - } else { - nv->valuetype = TYPE_BOOL; - } - return (STAT_OK); + return _i(nv)->getFunction(nv); } - -stat_t io_set_domode(nvObj_t *nv) // output function +stat_t din_set_fn(nvObj_t *nv) { - char *num_start = nv->token; - if (*(nv->group) == 0) { - // if we don't have a group, then the group name is in the token - // skip over "out" - num_start+=3; - } - // the token has been stripped down to an ASCII digit string - use it as an index - uint8_t output_num = strtol(num_start, NULL, 10); - - if (output_num > D_OUT_CHANNELS) { - nv->valuetype = TYPE_NULL; - return(STAT_NO_GPIO); - } - - // Force pins that aren't available to be "disabled" - switch (output_num) { - case 1: if (output_1_pin.isNull()) { nv->value = IO_MODE_DISABLED; } break; - case 2: if (output_2_pin.isNull()) { nv->value = IO_MODE_DISABLED; } break; - case 3: if (output_3_pin.isNull()) { nv->value = IO_MODE_DISABLED; } break; - case 4: if (output_4_pin.isNull()) { nv->value = IO_MODE_DISABLED; } break; - case 5: if (output_5_pin.isNull()) { nv->value = IO_MODE_DISABLED; } break; - case 6: if (output_6_pin.isNull()) { nv->value = IO_MODE_DISABLED; } break; - case 7: if (output_7_pin.isNull()) { nv->value = IO_MODE_DISABLED; } break; - case 8: if (output_8_pin.isNull()) { nv->value = IO_MODE_DISABLED; } break; - case 9: if (output_9_pin.isNull()) { nv->value = IO_MODE_DISABLED; } break; - case 10: if (output_10_pin.isNull()) { nv->value = IO_MODE_DISABLED; } break; - case 11: if (output_11_pin.isNull()) { nv->value = IO_MODE_DISABLED; } break; - case 12: if (output_12_pin.isNull()) { nv->value = IO_MODE_DISABLED; } break; - case 13: if (output_13_pin.isNull()) { nv->value = IO_MODE_DISABLED; } break; - - default: - break; - } - - return (_output_set_helper(nv, IO_ACTIVE_LOW, IO_MODE_MAX)); + return _i(nv)->setFunction(nv); } /* - * io_get_output() - return output state given an nv object + * io_get_input() - return input state given an nv object + * Note: if the input is disabled, it returns NULL. */ -stat_t io_get_output(nvObj_t *nv) +stat_t din_get_input(nvObj_t *nv) { - char *num_start = nv->token; - if (*(nv->group) == 0) { - // if we don't have a group, then the group name is in the token - // skip over "out" - num_start+=3; - } - // the token has been stripped down to an ASCII digit string - use it as an index - uint8_t output_num = strtol(num_start, NULL, 10); + return _i(nv)->getState(nv); +} - if (output_num > D_OUT_CHANNELS) { - nv->valuetype = TYPE_NULL; - return(STAT_NO_GPIO); - } - ioMode outMode = d_out[output_num-1].mode; - if (outMode == IO_MODE_DISABLED) { -// nv->value = 0; - nv->valuetype = TYPE_NULL; // reports back as NULL - } else { - nv->valuetype = TYPE_FLOAT; - nv->precision = 2; - bool invert = (outMode == 0); - // Note: !! forces a value to boolean 0 or 1 - switch (output_num) { - case 1: { nv->value = (float)output_1_pin; } break; - case 2: { nv->value = (float)output_2_pin; } break; - case 3: { nv->value = (float)output_3_pin; } break; - case 4: { nv->value = (float)output_4_pin; } break; - case 5: { nv->value = (float)output_5_pin; } break; - case 6: { nv->value = (float)output_6_pin; } break; - case 7: { nv->value = (float)output_7_pin; } break; - case 8: { nv->value = (float)output_8_pin; } break; - case 9: { nv->value = (float)output_9_pin; } break; - case 10: { nv->value = (float)output_10_pin; } break; - case 11: { nv->value = (float)output_11_pin; } break; - case 12: { nv->value = (float)output_12_pin; } break; - case 13: { nv->value = (float)output_13_pin; } break; - - default: - { -// nv->value = 0; // inactive - nv->valuetype = TYPE_NULL; // reports back as NULL - } - } - if (invert) { - nv->value = 1.0 - nv->value; - } - } - return (STAT_OK); +stat_t dout_get_mo(nvObj_t *nv) +{ + return _i(nv)->getMode(nv); +} +stat_t dout_set_mo(nvObj_t *nv) +{ + return _i(nv)->setMode(nv); } /* - * io_set_output() - return input state given an nv object + * io_get_output()/io_set_output() - get/set output state given an nv object */ -stat_t io_set_output(nvObj_t *nv) +stat_t dout_get_output(nvObj_t *nv) { - char *num_start = nv->token; - if (*(nv->group) == 0) { - // if we don't have a group, then the group name is in the token - // skip over "out" - num_start+=3; - } - // the token has been stripped down to an ASCII digit string - use it as an index - uint8_t output_num = strtol(num_start, NULL, 10); - - ioMode outMode = d_out[output_num-1].mode; - if (outMode == IO_MODE_DISABLED) { - nv->value = 0; // Inactive? - } else { - bool invert = (outMode == 0); - float value = nv->value; - if (invert) { - value = 1.0 - value; - } - switch (output_num) { - // Generated with: - // perl -e 'for($i=1;$i<14;$i++) { print "case ${i}: { output_${i}_pin = value; } break;\n";}' - // BEGIN generated - case 1: { output_1_pin = value; } break; - case 2: { output_2_pin = value; } break; - case 3: { output_3_pin = value; } break; - case 4: { output_4_pin = value; } break; - case 5: { output_5_pin = value; } break; - case 6: { output_6_pin = value; } break; - case 7: { output_7_pin = value; } break; - case 8: { output_8_pin = value; } break; - case 9: { output_9_pin = value; } break; - case 10: { output_10_pin = value; } break; - case 11: { output_11_pin = value; } break; - case 12: { output_12_pin = value; } break; - case 13: { output_13_pin = value; } break; - // END generated - default: { nv->value = 0; } // inactive - } - } - return (STAT_OK); + return _o(nv)->getValue(nv); +} +stat_t dout_set_output(nvObj_t *nv) +{ + return _o(nv)->setValue(nv); } /*********************************************************************************** @@ -698,16 +264,16 @@ stat_t io_set_output(nvObj_t *nv) sprintf(cs.out_buf, format, nv->group, (int)nv->value); xio_writeline(cs.out_buf); } - void io_print_mo(nvObj_t *nv) {_print_di(nv, fmt_gpio_mo);} - void io_print_ac(nvObj_t *nv) {_print_di(nv, fmt_gpio_ac);} - void io_print_fn(nvObj_t *nv) {_print_di(nv, fmt_gpio_fn);} - void io_print_in(nvObj_t *nv) { + void din_print_mo(nvObj_t *nv) {_print_di(nv, fmt_gpio_mo);} + void din_print_ac(nvObj_t *nv) {_print_di(nv, fmt_gpio_ac);} + void din_print_fn(nvObj_t *nv) {_print_di(nv, fmt_gpio_fn);} + void din_print_in(nvObj_t *nv) { sprintf(cs.out_buf, fmt_gpio_in, nv->token, (int)nv->value); xio_writeline(cs.out_buf); } - void io_print_domode(nvObj_t *nv) {_print_di(nv, fmt_gpio_domode);} - void io_print_out(nvObj_t *nv) { + void dout_print_mo(nvObj_t *nv) {_print_di(nv, fmt_gpio_domode);} + void dout_print_out(nvObj_t *nv) { sprintf(cs.out_buf, fmt_gpio_out, nv->token, (int)nv->value); xio_writeline(cs.out_buf); } diff --git a/g2core/gpio.h b/g2core/gpio.h index 9a44623a8..32844a846 100644 --- a/g2core/gpio.h +++ b/g2core/gpio.h @@ -25,33 +25,42 @@ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF * OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ + #ifndef GPIO_H_ONCE #define GPIO_H_ONCE +#include "g2core.h" // #1 +#include "config.h" // #2 +#include "encoder.h" // for post-probe/homing encoder grabbing +#include "report.h" // for sr triggering +#include "canonical_machine.h" // for pin-change function/action handling + +// Note: "board_gpio.h" is inlcluded at the end of this file + +#include // for std::forward + +#include "MotatePins.h" +using Motate::kPullUp; +using Motate::kDebounce; +using Motate::kStartLow; +using Motate::kPWMPinInverted; + /* * GPIO defines */ -//--- change as required for board and switch hardware ---// -#define D_IN_CHANNELS 9 // v9 // number of digital inputs supported -#define D_OUT_CHANNELS 13 // number of digital outputs supported -//#define D_OUT_CHANNELS 9 // number of digital outputs supported -#define A_IN_CHANNELS 0 // number of analog inputs supported -#define A_OUT_CHANNELS 0 // number of analog outputs supported - -//#define INPUT_LOCKOUT_MS 50 // milliseconds to go dead after input firing -#define INPUT_LOCKOUT_MS 10 // milliseconds to go dead after input firing +// moved to board_gpio.h, which is copied for each board in subfolders of board/ //--- do not change from here down ---// typedef enum { - IO_ACTIVE_LOW = 0, // input is active low (aka normally open) - IO_ACTIVE_HIGH = 1, // input is active high (aka normally closed) - IO_MODE_DISABLED = 2, // input is disabled - IO_MODE_MAX // unused. Just for range checking + IO_ACTIVE_LOW = 0, // input/output is active low (aka normally open) + IO_ACTIVE_HIGH = 1, // input/output is active high (aka normally closed) + IO_MODE_DISABLED = 2 // input/output is disabled } ioMode; #define NORMALLY_OPEN IO_ACTIVE_LOW // equivalent #define NORMALLY_CLOSED IO_ACTIVE_HIGH // equivalent +#define IO_MODE_MAX IO_MODE_DISABLED // for range checking typedef enum { // actions are initiated from within the input's ISR INPUT_ACTION_NONE = 0, @@ -63,8 +72,8 @@ typedef enum { // actions are initiated from within the INPUT_ACTION_SHUTDOWN, // initiate a shutdown. stops everything immediately - does not preserve position INPUT_ACTION_PANIC, // initiate a panic. stops everything immediately - does not preserve position INPUT_ACTION_RESET, // reset system - INPUT_ACTION_MAX // unused. Just for range checking } inputAction; +#define INPUT_ACTION_MAX INPUT_ACTION_RESET // for range checking typedef enum { // functions are requested from the ISR, run from the main loop INPUT_FUNCTION_NONE = 0, @@ -72,8 +81,8 @@ typedef enum { // functions are requested from the ISR, INPUT_FUNCTION_INTERLOCK = 2, // interlock processing INPUT_FUNCTION_SHUTDOWN = 3, // shutdown in support of external emergency stop INPUT_FUNCTION_PROBE = 4, // assign input as probe input - INPUT_FUNCTION_MAX // unused. Just for range checking } inputFunc; +#define INPUT_FUNCTION_MAX INPUT_FUNCTION_PROBE typedef enum { INPUT_INACTIVE = 0, // aka switch open, also read as 'false' @@ -90,34 +99,430 @@ typedef enum { /* * GPIO structures */ -typedef struct ioDigitalInput { // one struct per digital input - ioMode mode; // -1=disabled, 0=active low (NO), 1= active high (NC) +struct gpioDigitalInput { + // this is the implementation for a non-existant pin - see gpioDigitalInputPin for a real pin + + // functions for use by other parts of the code + + virtual bool getState(); + + virtual inputFunc getFunction(); + virtual bool setFunction(const inputFunc); + + virtual inputAction getAction(); + virtual bool setAction(const inputAction); + + virtual ioMode getMode(); + virtual bool setMode(const ioMode); + + virtual void setExternalNumber(const uint8_t); + virtual void setIsHoming(const bool); + virtual void setIsProbing(const bool); + + + // functions that take nvObj_t* and return stat_t, NOT overridden + + stat_t getState(nvObj_t *nv) + { + if (getMode() == IO_MODE_DISABLED) { + nv->value = IO_MODE_DISABLED; // historical consistency + nv->valuetype = TYPE_NULL; + return (STAT_OK); + } + nv->value = getState(); + nv->valuetype = TYPE_BOOL; + return (STAT_OK); + }; + // no setState + + stat_t getMode(nvObj_t *nv) + { + nv->value = getMode(); + nv->valuetype = TYPE_INT; + return (STAT_OK); + }; + stat_t setMode(nvObj_t *nv) + { + if ((nv->value < IO_ACTIVE_LOW) || (nv->value >= IO_MODE_MAX)) { + return (STAT_INPUT_VALUE_RANGE_ERROR); + } + if (!setMode((ioMode)nv->value)) { + return STAT_PARAMETER_IS_READ_ONLY; + } + return (STAT_OK); + }; + + stat_t getAction(nvObj_t *nv) + { + nv->value = getAction(); + nv->valuetype = TYPE_INT; + return (STAT_OK); + }; + stat_t setAction(nvObj_t *nv) + { + if ((nv->value < INPUT_ACTION_NONE) || (nv->value >= INPUT_ACTION_MAX)) { + return (STAT_INPUT_VALUE_RANGE_ERROR); + } + if (!setAction((inputAction)nv->value)) { + return STAT_PARAMETER_IS_READ_ONLY; + } + return (STAT_OK); + }; + + stat_t getFunction(nvObj_t *nv) + { + nv->value = getFunction(); + nv->valuetype = TYPE_INT; + return (STAT_OK); + }; + stat_t setFunction(nvObj_t *nv) + { + if ((nv->value < INPUT_FUNCTION_NONE) || (nv->value >= INPUT_FUNCTION_MAX)) { + return (STAT_INPUT_VALUE_RANGE_ERROR); + } + if (!setFunction((inputFunc)nv->value)) { + return STAT_PARAMETER_IS_READ_ONLY; + } + return (STAT_OK); + }; +}; + +template +struct gpioDigitalInputPin : gpioDigitalInput { +protected: // so we know if anyone tries to reach in + ioMode mode; // 0=active low (NO), 1= active high (NC), 2=disabled inputAction action; // 0=none, 1=stop, 2=halt, 3=stop_steps, 4=reset inputFunc function; // function to perform when activated / deactivated - ioState state; // input state 0=inactive, 1=active, -1=disabled + inputEdgeFlag edge; // keeps a transient record of edges for immediate inquiry + bool homing_mode; // set true when input is in homing mode. bool probing_mode; // set true when input is in probing mode. + + uint8_t ext_pin_number; // the number used externally for this pin ("in" + ext_pin_number) + uint16_t lockout_ms; // number of milliseconds for debounce lockout Motate::Timeout lockout_timer; // time to expire current debounce lockout, or 0 if no lockout -} d_in_t; -typedef struct gpioDigitalOutput { // one struct per digital output - ioMode mode; -} d_out_t; + pinType pin; // the actual pin object itself -typedef struct gpioAnalogInput { // one struct per analog input - ioMode mode; -} a_in_t; +public: + // In constructor, simply forward all values to the pinType + // To get a different behavior, override this object. + template + gpioDigitalInputPin(const ioMode _mode, const uint8_t _ext_pin_number, T&&... V) : + gpioDigitalInput{}, + mode{_mode}, + ext_pin_number{_ext_pin_number}, + pin{((mode == IO_ACTIVE_LOW) ? kPullUp|kDebounce : kDebounce), [&]{this->pin_changed();}, std::forward(V)...} + {}; + + // gpioDigitalInputPin(const ioMode _mode, const uint8_t _ext_pin_number) : + // gpioDigitalInput{}, + // mode{_mode}, + // ext_pin_number{_ext_pin_number}, + // pin{((mode == IO_ACTIVE_LOW) ? kPullUp|kDebounce : kDebounce), [&]{this->pin_changed();}} + // {}; + + // functions for use by other parts of the code, and are overridden + + bool getState() override + { + if (mode == IO_MODE_DISABLED) { + return false; + } + const bool v = (const bool)pin; + return (mode == IO_ACTIVE_HIGH) ? v : !v; + }; + + inputFunc getFunction() override + { + return function; + } + bool setFunction(const inputFunc f) override + { + function = f; + return true; + }; + + inputAction getAction() override + { + return action; + }; + bool setAction(const inputAction a) override + { + action = a; + return true; + }; + + ioMode getMode() override + { + return mode; + }; + bool setMode(const ioMode m) override + { + mode = m; + pin.setOptions((mode == IO_ACTIVE_LOW) ? kPullUp|kDebounce : kDebounce); + return true; + }; + + void setExternalNumber(const uint8_t e) override + { + ext_pin_number = e; + } + + virtual void setIsHoming(const bool m) + { + homing_mode = m; + } + + virtual void setIsProbing(const bool m) + { + probing_mode = m; + } + + + // support function for pin change interrupt handling + + void pin_changed() + { + // return if input is disabled + if (mode == IO_MODE_DISABLED) { + return; + } + + // return if the input is in lockout period (take no action) + if (lockout_timer.isSet() && !lockout_timer.isPast()) { + return; + } -typedef struct gpioAnalogOutput { // one struct per analog output + ioState pin_value = (ioState)(bool)pin; + ioState pin_value_corrected = (ioState)(pin_value ^ ((bool)mode ^ 1)); // correct for NO or NC mode + + // This shouldn't be necessary - the processor shouldn't call without an edge + // if (state == (ioState)pin_value_corrected) { + // return; + // } + + // lockout the pin for lockout_ms + lockout_timer.set(lockout_ms); + + // record the changed state + if (pin_value_corrected == INPUT_ACTIVE) { + edge = INPUT_EDGE_LEADING; + } else { + edge = INPUT_EDGE_TRAILING; + } + + // TODO - refactor homing_mode and probing_mode out to use a dynamically + // configured linked list of functions + + // perform homing operations if in homing mode + if (homing_mode) { + if (edge == INPUT_EDGE_LEADING) { // we only want the leading edge to fire + en_take_encoder_snapshot(); + cm_start_hold(); + } + return; + } + + // perform probing operations if in probing mode + if (probing_mode) { + // We want to capture either way. + // Probing tests the start condition for the correct direction ahead of time. + // If we see any edge, it's the right one. + en_take_encoder_snapshot(); + cm_start_hold(); + return; + } + + // *** NOTE: From this point on all conditionals assume we are NOT in homing or probe mode *** + + // trigger the action on leading edges + if (edge == INPUT_EDGE_LEADING) { + if (action == INPUT_ACTION_STOP) { + cm_start_hold(); + } + if (action == INPUT_ACTION_FAST_STOP) { + cm_start_hold(); // for now is same as STOP + } + if (action == INPUT_ACTION_HALT) { + cm_halt_all(); // hard stop, including spindle and coolant + } + if (action == INPUT_ACTION_ALARM) { + char msg[10]; + sprintf(msg, "input %d", ext_pin_number); + cm_alarm(STAT_ALARM, msg); + } + if (action == INPUT_ACTION_SHUTDOWN) { + char msg[10]; + sprintf(msg, "input %d", ext_pin_number); + cm_shutdown(STAT_SHUTDOWN, msg); + } + if (action == INPUT_ACTION_PANIC) { + char msg[10]; + sprintf(msg, "input %d", ext_pin_number); + cm_panic(STAT_PANIC, msg); + } + if (action == INPUT_ACTION_RESET) { + hw_hard_reset(); + } + + // these functions also trigger on the leading edge + + if (function == INPUT_FUNCTION_LIMIT) { + cm.limit_requested = ext_pin_number; + + } else if (function == INPUT_FUNCTION_SHUTDOWN) { + cm.shutdown_requested = ext_pin_number; + + } else if (function == INPUT_FUNCTION_INTERLOCK) { + cm.safety_interlock_disengaged = ext_pin_number; + } + } // if (edge == INPUT_EDGE_LEADING) + + // trigger interlock release on trailing edge + if (edge == INPUT_EDGE_TRAILING) { + if (function == INPUT_FUNCTION_INTERLOCK) { + cm.safety_interlock_reengaged = ext_pin_number; + } + } + + sr_request_status_report(SR_REQUEST_TIMED); //+++++ Put this one back in. + }; + +}; + +struct gpioDigitalOutput { + + // functions for use by other parts of the code, and are what to override + virtual ioMode getMode() + { + return IO_MODE_DISABLED; + }; + virtual bool setMode(const ioMode) + { + return false; + }; + + virtual float getValue() + { + return -1; + }; + virtual bool setValue(const float) + { + return false; + }; + + + // functions that take nvObj_t* and return stat_t, NOT overridden + + virtual stat_t getMode(nvObj_t *nv) + { + nv->value = getMode(); + nv->valuetype = TYPE_INT; + return (STAT_OK); + }; + virtual stat_t setMode(nvObj_t *nv) + { + if ((nv->value < IO_ACTIVE_LOW) || (nv->value >= IO_MODE_MAX)) { + return (STAT_INPUT_VALUE_RANGE_ERROR); + } + if (!setMode((ioMode)nv->value)) { + return STAT_INPUT_VALUE_RANGE_ERROR; + } + return (STAT_OK); + }; + + virtual stat_t getValue(nvObj_t *nv) + { + auto mode = getMode(); + if (mode == IO_MODE_DISABLED) { + nv->value = 0; + nv->valuetype = TYPE_NULL; // reports back as NULL + } else { + nv->valuetype = TYPE_FLOAT; + nv->precision = 2; + nv->value = getValue(); // read it as a float + + bool invert = (mode == 0); + if (invert) { + nv->value = 1.0 - nv->value; + } + } + return (STAT_OK); + }; + virtual stat_t setValue(nvObj_t *nv) + { + auto mode = getMode(); + if (mode == IO_MODE_DISABLED) { + nv->valuetype = TYPE_NULL; // reports back as NULL + } else { + float value = nv->value; // read it as a float + + bool invert = (mode == 0); + if (invert) { + value = 1.0 - value; + } + + if (!setValue(value)) { + return STAT_INPUT_VALUE_RANGE_ERROR; + } + } + return (STAT_OK); + }; + +}; + +template +struct gpioDigitalOutputPin : gpioDigitalOutput { + ioMode mode; // 0=active low (NO), 1= active high (NC), 2=disabled + pinType pin; + + // In constructor, simply forward all values to the pinType + template + gpioDigitalOutputPin(const ioMode _mode, T&&... V) : + gpioDigitalOutput{}, + mode{ _mode }, + pin{((mode == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow), std::forward(V)...} + {}; + + // functions for use by other parts of the code, and are overridden + + ioMode getMode() override + { + return mode; + }; + bool setMode(const ioMode m) override + { + mode = m; + pin.setOptions((mode == IO_ACTIVE_LOW) ? kPullUp|kDebounce : kDebounce); + return true; + }; + + + float getValue() override + { + return (const float)pin; + }; + bool setValue(const float v) override + { + if (pin.isNull()) { + return false; + } + pin = v; + return true; + }; + +}; + +struct gpioAnalogInput { // one struct per analog input ioMode mode; -} a_out_t; +}; -extern d_in_t d_in[D_IN_CHANNELS]; -extern d_out_t d_out[D_OUT_CHANNELS]; -extern a_in_t a_in[A_IN_CHANNELS]; -extern a_out_t a_out[A_OUT_CHANNELS]; +struct gpioAnalogOutput { // one struct per analog output + ioMode mode; +}; /* * GPIO function prototypes @@ -125,40 +530,44 @@ extern a_out_t a_out[A_OUT_CHANNELS]; void gpio_init(void); void gpio_reset(void); -void input_reset(void); -void output_reset(void); +void inputs_reset(void); +void outputs_reset(void); bool gpio_read_input(const uint8_t input_num); void gpio_set_homing_mode(const uint8_t input_num, const bool is_homing); void gpio_set_probing_mode(const uint8_t input_num, const bool is_probing); int8_t gpio_get_probing_input(void); -stat_t io_set_mo(nvObj_t *nv); -stat_t io_set_ac(nvObj_t *nv); -stat_t io_set_fn(nvObj_t *nv); +stat_t din_get_mo(nvObj_t *nv); +stat_t din_set_mo(nvObj_t *nv); +stat_t din_get_ac(nvObj_t *nv); +stat_t din_set_ac(nvObj_t *nv); +stat_t din_get_fn(nvObj_t *nv); +stat_t din_set_fn(nvObj_t *nv); -stat_t io_get_input(nvObj_t *nv); +stat_t din_get_input(nvObj_t *nv); - -stat_t io_set_domode(nvObj_t *nv); // output sense -stat_t io_get_output(nvObj_t *nv); -stat_t io_set_output(nvObj_t *nv); +stat_t dout_get_mo(nvObj_t *nv); // output sense +stat_t dout_set_mo(nvObj_t *nv); // output sense +stat_t dout_get_output(nvObj_t *nv); +stat_t dout_set_output(nvObj_t *nv); #ifdef __TEXT_MODE - void io_print_mo(nvObj_t *nv); - void io_print_ac(nvObj_t *nv); - void io_print_fn(nvObj_t *nv); - void io_print_in(nvObj_t *nv); - void io_print_domode(nvObj_t *nv); - void io_print_out(nvObj_t *nv); + void din_print_mo(nvObj_t *nv); + void din_print_ac(nvObj_t *nv); + void din_print_fn(nvObj_t *nv); + void din_print_in(nvObj_t *nv); + void dout_print_mo(nvObj_t *nv); + void dout_print_out(nvObj_t *nv); #else - #define io_print_mo tx_print_stub - #define io_print_ac tx_print_stub - #define io_print_fn tx_print_stub - #define io_print_in tx_print_stub - #define io_print_st tx_print_stub - #define io_print_domode tx_print_stub - #define io_print_out tx_print_stub + #define din_print_mo tx_print_stub + #define din_print_ac tx_print_stub + #define din_print_fn tx_print_stub + #define din_print_in tx_print_stub + #define dout_print_mo tx_print_stub + #define dout_print_out tx_print_stub #endif // __TEXT_MODE +#include "board_gpio.h" + #endif // End of include guard: GPIO_H_ONCE diff --git a/g2core/stepper.h b/g2core/stepper.h index b8bc2c96f..29f12ac2c 100644 --- a/g2core/stepper.h +++ b/g2core/stepper.h @@ -245,19 +245,18 @@ * degrees of phase angle results in a step being generated. */ -// These includes must be BEFORE the STEPPER_H_ONCE is defined -#include "g2core.h" -#include "report.h" -#include "board_stepper.h" // include board specific stuff, in particular the Stepper objects - -// NOW we can do this: #ifndef STEPPER_H_ONCE #define STEPPER_H_ONCE +#include "g2core.h" +#include "report.h" + #include "MotateUtilities.h" // for HOT_DATA and HOT_FUNC #include "planner.h" // planner.h must precede stepper.h for moveType typedef +// Note: "board_stepper.h" is inlcluded at the end of this file + /********************************* * Stepper configs and constants * *********************************/ @@ -467,7 +466,7 @@ struct Stepper { } if (_power_state == MOTOR_IDLE) { return (0.0); - } + } return (st_cfg.mot[motor].power_level); }; @@ -475,7 +474,7 @@ struct Stepper { // { // return (_power_mode == MOTOR_DISABLED); // }; - + // turn on motor in all cases unless it's disabled // this version is called from the loader, and explicitly does NOT have floating point computations // HOT - called from the DDA interrupt @@ -519,7 +518,7 @@ struct Stepper { _motor_disable_timeout.clear(); _power_state = MOTOR_IDLE; // or MOTOR_OFF }; - + // turn off motor is only powered when moving // HOT - called from the DDA interrupt void motionStopped() //HOT_FUNC @@ -533,7 +532,7 @@ struct Stepper { } } }; - + virtual void periodicCheck(bool have_actually_stopped) // can be overridden { if (_was_enabled) { @@ -644,4 +643,6 @@ stat_t st_set_me(nvObj_t *nv); #endif // __TEXT_MODE +#include "board_stepper.h" // include board specific stuff, in particular the Stepper objects + #endif // End of include guard: STEPPER_H_ONCE From 7ee5850b85047fb2e33ec70bfed8efa11b774832 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Wed, 13 Dec 2017 17:22:02 -0600 Subject: [PATCH 164/193] Fixing GPIO bugs from last commit. --- g2core/gpio.cpp | 4 ++-- g2core/gpio.h | 3 ++- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/g2core/gpio.cpp b/g2core/gpio.cpp index 132a7aad4..02d1b480b 100644 --- a/g2core/gpio.cpp +++ b/g2core/gpio.cpp @@ -225,11 +225,11 @@ stat_t din_get_input(nvObj_t *nv) stat_t dout_get_mo(nvObj_t *nv) { - return _i(nv)->getMode(nv); + return _o(nv)->getMode(nv); } stat_t dout_set_mo(nvObj_t *nv) { - return _i(nv)->setMode(nv); + return _o(nv)->setMode(nv); } /* diff --git a/g2core/gpio.h b/g2core/gpio.h index 32844a846..cc5390b07 100644 --- a/g2core/gpio.h +++ b/g2core/gpio.h @@ -496,7 +496,8 @@ struct gpioDigitalOutputPin : gpioDigitalOutput { bool setMode(const ioMode m) override { mode = m; - pin.setOptions((mode == IO_ACTIVE_LOW) ? kPullUp|kDebounce : kDebounce); + pin.setOptions((mode == IO_ACTIVE_LOW) ? kPullUp|kDebounce : kDebounce); // prepare the pin + pin = ((mode == IO_ACTIVE_LOW) ? true : false); // set the output to inactive return true; }; From cebdab7eb821fbcc7c38ba5e035efc813da98efe Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Mon, 19 Feb 2018 10:09:01 -0600 Subject: [PATCH 165/193] Update reference to Motate for SamS70 fixes --- Motate | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Motate b/Motate index 76fc94edc..f7e3cddc2 160000 --- a/Motate +++ b/Motate @@ -1 +1 @@ -Subproject commit 76fc94edcab42d03f713e08786dea935ee9a560e +Subproject commit f7e3cddc2188a39fd831ac6ce508f5006df7aceb From 7dc5b96eebcde6378c19733556aa0c4a90f6d61c Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Mon, 19 Feb 2018 10:16:43 -0600 Subject: [PATCH 166/193] Adjusted for latest Motate changes to SamS70 USB --- g2core/board/Archim/board_xio.h | 4 ++-- g2core/board/ArduinoDue/board_xio.h | 4 ++-- g2core/board/G2v9/board_xio.h | 4 ++-- g2core/board/gquadratic/board_xio.h | 6 ++++-- g2core/board/gquintic/board_xio.cpp | 1 + g2core/board/gquintic/board_xio.h | 6 ++++-- g2core/board/gquintic/gquintic-c-pinout.h | 2 +- g2core/board/gquintic/gquintic-d-pinout.h | 2 +- g2core/board/gquintic/hardware.h | 15 +++++++-------- g2core/board/gquintic/motate_pin_assignments.h | 5 +++-- g2core/board/printrboardg2/board_xio.h | 4 ++-- g2core/board/sbv300/board_xio.h | 4 ++-- 12 files changed, 31 insertions(+), 26 deletions(-) diff --git a/g2core/board/Archim/board_xio.h b/g2core/board/Archim/board_xio.h index 09f20fef8..ea0a3fa7b 100755 --- a/g2core/board/Archim/board_xio.h +++ b/g2core/board/Archim/board_xio.h @@ -37,10 +37,10 @@ #include "MotateUSBCDC.h" #if USB_SERIAL_PORTS_EXPOSED == 1 -typedef Motate::USBDevice< Motate::USBCDC > XIOUSBDevice_t; +typedef Motate::USBDevice< USBDeviceHardware, Motate::USBCDC > XIOUSBDevice_t; #endif #if USB_SERIAL_PORTS_EXPOSED == 2 -typedef Motate::USBDevice XIOUSBDevice_t; +typedef Motate::USBDevice< USBDeviceHardware, Motate::USBCDC, Motate::USBCDC > XIOUSBDevice_t; #endif extern XIOUSBDevice_t usb; diff --git a/g2core/board/ArduinoDue/board_xio.h b/g2core/board/ArduinoDue/board_xio.h index 09f20fef8..ea0a3fa7b 100755 --- a/g2core/board/ArduinoDue/board_xio.h +++ b/g2core/board/ArduinoDue/board_xio.h @@ -37,10 +37,10 @@ #include "MotateUSBCDC.h" #if USB_SERIAL_PORTS_EXPOSED == 1 -typedef Motate::USBDevice< Motate::USBCDC > XIOUSBDevice_t; +typedef Motate::USBDevice< USBDeviceHardware, Motate::USBCDC > XIOUSBDevice_t; #endif #if USB_SERIAL_PORTS_EXPOSED == 2 -typedef Motate::USBDevice XIOUSBDevice_t; +typedef Motate::USBDevice< USBDeviceHardware, Motate::USBCDC, Motate::USBCDC > XIOUSBDevice_t; #endif extern XIOUSBDevice_t usb; diff --git a/g2core/board/G2v9/board_xio.h b/g2core/board/G2v9/board_xio.h index 09f20fef8..ea0a3fa7b 100755 --- a/g2core/board/G2v9/board_xio.h +++ b/g2core/board/G2v9/board_xio.h @@ -37,10 +37,10 @@ #include "MotateUSBCDC.h" #if USB_SERIAL_PORTS_EXPOSED == 1 -typedef Motate::USBDevice< Motate::USBCDC > XIOUSBDevice_t; +typedef Motate::USBDevice< USBDeviceHardware, Motate::USBCDC > XIOUSBDevice_t; #endif #if USB_SERIAL_PORTS_EXPOSED == 2 -typedef Motate::USBDevice XIOUSBDevice_t; +typedef Motate::USBDevice< USBDeviceHardware, Motate::USBCDC, Motate::USBCDC > XIOUSBDevice_t; #endif extern XIOUSBDevice_t usb; diff --git a/g2core/board/gquadratic/board_xio.h b/g2core/board/gquadratic/board_xio.h index 09f20fef8..6055d4611 100755 --- a/g2core/board/gquadratic/board_xio.h +++ b/g2core/board/gquadratic/board_xio.h @@ -36,11 +36,13 @@ #include "MotateUSB.h" #include "MotateUSBCDC.h" +typedef Motate::USBDeviceHardwareBus> USBDeviceHardware_t; + #if USB_SERIAL_PORTS_EXPOSED == 1 -typedef Motate::USBDevice< Motate::USBCDC > XIOUSBDevice_t; +typedef Motate::USBDevice< USBDeviceHardware_t, Motate::USBCDC > XIOUSBDevice_t; #endif #if USB_SERIAL_PORTS_EXPOSED == 2 -typedef Motate::USBDevice XIOUSBDevice_t; +typedef Motate::USBDevice< USBDeviceHardware_t, Motate::USBCDC, Motate::USBCDC > XIOUSBDevice_t; #endif extern XIOUSBDevice_t usb; diff --git a/g2core/board/gquintic/board_xio.cpp b/g2core/board/gquintic/board_xio.cpp index 551e7a10d..3fc7a7512 100755 --- a/g2core/board/gquintic/board_xio.cpp +++ b/g2core/board/gquintic/board_xio.cpp @@ -71,6 +71,7 @@ void board_hardware_init(void) // called 1st #if XIO_HAS_USB // Init USB usb.attach(); + usb.handleVbusChange(true); #endif // XIO_HAS_USB } diff --git a/g2core/board/gquintic/board_xio.h b/g2core/board/gquintic/board_xio.h index 09f20fef8..659f68a4a 100755 --- a/g2core/board/gquintic/board_xio.h +++ b/g2core/board/gquintic/board_xio.h @@ -36,11 +36,13 @@ #include "MotateUSB.h" #include "MotateUSBCDC.h" +typedef Motate::USBDeviceHardwareVBus> USBDeviceHardware_t; + #if USB_SERIAL_PORTS_EXPOSED == 1 -typedef Motate::USBDevice< Motate::USBCDC > XIOUSBDevice_t; +typedef Motate::USBDevice< USBDeviceHardware_t, Motate::USBCDC > XIOUSBDevice_t; #endif #if USB_SERIAL_PORTS_EXPOSED == 2 -typedef Motate::USBDevice XIOUSBDevice_t; +typedef Motate::USBDevice< USBDeviceHardware_t, Motate::USBCDC, Motate::USBCDC > XIOUSBDevice_t; #endif extern XIOUSBDevice_t usb; diff --git a/g2core/board/gquintic/gquintic-c-pinout.h b/g2core/board/gquintic/gquintic-c-pinout.h index d1c1659c4..08ccf5509 100755 --- a/g2core/board/gquintic/gquintic-c-pinout.h +++ b/g2core/board/gquintic/gquintic-c-pinout.h @@ -171,7 +171,7 @@ _MAKE_MOTATE_PIN(kLED_USBRXPinNumber, 'B', 13); // LED_1 (Heartbeat _MAKE_MOTATE_PIN(kSocket4_SPISlaveSelectPinNumber, 'B', 14); // NOT CONNECTED -//_MAKE_MOTATE_PIN( 'D', 0); // USB_VBUS +_MAKE_MOTATE_PIN(kUSBVBUS_PinNumber 'D', 0); // USB_VBUS _MAKE_MOTATE_PIN(kInput9_PinNumber, 'D', 1); // _MAKE_MOTATE_PIN(kInput10_PinNumber, 'D', 2); // _MAKE_MOTATE_PIN(kInput8_PinNumber, 'D', 3); // diff --git a/g2core/board/gquintic/gquintic-d-pinout.h b/g2core/board/gquintic/gquintic-d-pinout.h index 72180b124..faf2acead 100755 --- a/g2core/board/gquintic/gquintic-d-pinout.h +++ b/g2core/board/gquintic/gquintic-d-pinout.h @@ -171,7 +171,7 @@ _MAKE_MOTATE_PIN(kLED_USBRXPinNumber, 'B', 13); // LED_1 (Heartbeat _MAKE_MOTATE_PIN(kUnassigned6, 'B', 14); // NOT CONNECTED -//_MAKE_MOTATE_PIN( 'D', 0); // USB_VBUS +_MAKE_MOTATE_PIN(kUSBVBUS_PinNumber, 'D', 0); // USB_VBUS _MAKE_MOTATE_PIN(kInput9_PinNumber, 'D', 1); // _MAKE_MOTATE_PIN(kInput10_PinNumber, 'D', 2); // _MAKE_MOTATE_PIN(kInput8_PinNumber, 'D', 3); // diff --git a/g2core/board/gquintic/hardware.h b/g2core/board/gquintic/hardware.h index 349818f9a..8d86f9d32 100644 --- a/g2core/board/gquintic/hardware.h +++ b/g2core/board/gquintic/hardware.h @@ -59,7 +59,7 @@ enum hwPlatform { #define AXES 6 // number of axes supported in this version #define HOMING_AXES 4 // number of axes that can be homed (assumes Zxyabc sequence) -#if defined(USING_A_MAX31865) && USING_A_MAX31865 == 1 +#if QUINTIC_REVISION == 'C' #define MOTORS 5 // number of motors on the board - 4 Trinamics + 1 servo #else #define MOTORS 6 // number of motors on the board - 5 Trinamics + 1 servo @@ -72,8 +72,7 @@ enum hwPlatform { #define MOTOR_2_IS_TRINAMIC #define MOTOR_3_IS_TRINAMIC #define MOTOR_4_IS_TRINAMIC -#if defined(USING_A_MAX31865) && USING_A_MAX31865 == 1 -#else +#if QUINTIC_REVISION == 'D' #define MOTOR_5_IS_TRINAMIC #endif //////////////////////////// @@ -154,7 +153,7 @@ Motate::service_call_number kSPI_ServiceCallNumber = 3; typedef Motate::SPIBus SPIBus_used_t; extern SPIBus_used_t spiBus; -typedef Motate::SPIChipSelectPinMux SPI_CS_PinMux_used_t; +typedef Motate::SPIChipSelectPinMux SPI_CS_PinMux_used_t; extern SPI_CS_PinMux_used_t spiCSPinMux; /**** Motate Global Pin Allocations ****/ @@ -169,13 +168,13 @@ static OutputPin grbl_feedhold_pin; static OutputPin grbl_cycle_start_pin; static OutputPin motor_common_enable_pin; -static OutputPin spindle_enable_pin; -static OutputPin spindle_dir_pin; +//static OutputPin spindle_enable_pin; +//static OutputPin spindle_dir_pin; // NOTE: In the v9 and the Due the flood and mist coolants are mapped to a the same pin //static OutputPin coolant_enable_pin; -static OutputPin flood_enable_pin; -static OutputPin mist_enable_pin; +//static OutputPin flood_enable_pin; +//static OutputPin mist_enable_pin; // Input pins are defined in gpio.cpp diff --git a/g2core/board/gquintic/motate_pin_assignments.h b/g2core/board/gquintic/motate_pin_assignments.h index 4be5c1dbb..cca19cd66 100755 --- a/g2core/board/gquintic/motate_pin_assignments.h +++ b/g2core/board/gquintic/motate_pin_assignments.h @@ -162,8 +162,9 @@ pin_number kDebug4_PinNumber = -1; // 114; pin_number kLED_USBRXPinNumber = 117; pin_number kLED_USBTXPinNumber = 118; -pin_number kSD_CardDetectPinNumber = 119; -pin_number kSD_ChipSelectPinNumber = 120; +pin_number kSD_CardDetectPinNumber = -1; +pin_number kSD_ChipSelectPinNumber = -1; +pin_number kUSBVBUS_PinNumber = 119; pin_number kInterlock_InPinNumber = 121; pin_number kOutputSAFE_PinNumber = 122; // SAFE signal pin_number kLEDPWM_PinNumber = 123; diff --git a/g2core/board/printrboardg2/board_xio.h b/g2core/board/printrboardg2/board_xio.h index 75184f19a..50b69107c 100755 --- a/g2core/board/printrboardg2/board_xio.h +++ b/g2core/board/printrboardg2/board_xio.h @@ -38,10 +38,10 @@ #include "MotateUSBCDC.h" #if USB_SERIAL_PORTS_EXPOSED == 1 -typedef Motate::USBDevice< Motate::USBCDC > XIOUSBDevice_t; +typedef Motate::USBDevice< USBDeviceHardware, Motate::USBCDC > XIOUSBDevice_t; #endif #if USB_SERIAL_PORTS_EXPOSED == 2 -typedef Motate::USBDevice XIOUSBDevice_t; +typedef Motate::USBDevice< USBDeviceHardware, Motate::USBCDC, Motate::USBCDC > XIOUSBDevice_t; #endif extern XIOUSBDevice_t usb; diff --git a/g2core/board/sbv300/board_xio.h b/g2core/board/sbv300/board_xio.h index 6bc4421f4..04af83fd8 100755 --- a/g2core/board/sbv300/board_xio.h +++ b/g2core/board/sbv300/board_xio.h @@ -37,10 +37,10 @@ #include "MotateUSBCDC.h" #if USB_SERIAL_PORTS_EXPOSED == 1 -typedef Motate::USBDevice< Motate::USBCDC > XIOUSBDevice_t; +typedef Motate::USBDevice< USBDeviceHardware, , Motate::USBCDC > XIOUSBDevice_t; #endif #if USB_SERIAL_PORTS_EXPOSED == 2 -typedef Motate::USBDevice XIOUSBDevice_t; +typedef Motate::USBDevice< USBDeviceHardware, Motate::USBCDC, Motate::USBCDC > XIOUSBDevice_t; #endif extern XIOUSBDevice_t usb; From 70a3f309e2cd0a50c211e213e5640c059ac15adf Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Mon, 19 Feb 2018 10:18:13 -0600 Subject: [PATCH 167/193] Major GOIO refactor --- g2core/board/gquadratic/board_gpio.cpp | 50 +- g2core/board/gquintic/board_gpio.cpp | 101 ++-- g2core/board/gquintic/board_gpio.h | 103 +++- g2core/config.cpp | 30 +- g2core/config.h | 4 +- g2core/config_app.cpp | 131 ++++- g2core/coolant.cpp | 53 +- g2core/device/max31865/max31865.h | 104 ++++ g2core/gpio.cpp | 170 ++++-- g2core/gpio.h | 778 +++++++++++++++++++++---- g2core/pwm.cpp | 50 +- g2core/settings/settings_default.h | 277 +++++++-- g2core/spindle.cpp | 54 +- g2core/temperature.cpp | 2 +- 14 files changed, 1559 insertions(+), 348 deletions(-) diff --git a/g2core/board/gquadratic/board_gpio.cpp b/g2core/board/gquadratic/board_gpio.cpp index 4daf011d8..5033c3f10 100644 --- a/g2core/board/gquadratic/board_gpio.cpp +++ b/g2core/board/gquadratic/board_gpio.cpp @@ -56,32 +56,32 @@ /**** Setup Actual Objects ****/ -gpioDigitalInputPin> din1 {DI1_MODE, 1}; -gpioDigitalInputPin> din2 {DI2_MODE, 2}; -gpioDigitalInputPin> din3 {DI3_MODE, 3}; -gpioDigitalInputPin> din4 {DI4_MODE, 4}; -gpioDigitalInputPin> din5 {DI5_MODE, 5}; -gpioDigitalInputPin> din6 {DI6_MODE, 6}; -gpioDigitalInputPin> din7 {DI7_MODE, 7}; -gpioDigitalInputPin> din8 {DI8_MODE, 8}; -gpioDigitalInputPin> din9 {DI9_MODE, 9}; -// gpioDigitalInputPin> din10 {DI10_MODE, 10}; -// gpioDigitalInputPin> din11 {DI11_MODE, 11}; -// gpioDigitalInputPin> din12 {DI12_MODE, 12}; +gpioDigitalInputPin> din1 {DI1_ENABLED, DI1_POLARITY, 1}; +gpioDigitalInputPin> din2 {DI2_ENABLED, DI2_POLARITY, 2}; +gpioDigitalInputPin> din3 {DI3_ENABLED, DI3_POLARITY, 3}; +gpioDigitalInputPin> din4 {DI4_ENABLED, DI4_POLARITY, 4}; +gpioDigitalInputPin> din5 {DI5_ENABLED, DI5_POLARITY, 5}; +gpioDigitalInputPin> din6 {DI6_ENABLED, DI6_POLARITY, 6}; +gpioDigitalInputPin> din7 {DI7_ENABLED, DI7_POLARITY, 7}; +gpioDigitalInputPin> din8 {DI8_ENABLED, DI8_POLARITY, 8}; +gpioDigitalInputPin> din9 {DI9_ENABLED, DI9_POLARITY, 9}; +// gpioDigitalInputPin> din10 {DI10ENABLEDE, DI10_POLARITY, 10}; +// gpioDigitalInputPin> din11 {DI11ENABLEDE, DI11_POLARITY, 11}; +// gpioDigitalInputPin> din12 {DI12ENABLEDE, DI12_POLARITY, 12}; -gpioDigitalOutputPin> dout1 { DO1_MODE, (uint32_t)200000 }; -gpioDigitalOutputPin> dout2 { DO2_MODE, (uint32_t)200000 }; -gpioDigitalOutputPin> dout3 { DO3_MODE, (uint32_t)200000 }; -gpioDigitalOutputPin> dout4 { DO4_MODE, (uint32_t)200000 }; -gpioDigitalOutputPin> dout5 { DO5_MODE, (uint32_t)200000 }; -gpioDigitalOutputPin> dout6 { DO6_MODE, (uint32_t)200000 }; -gpioDigitalOutputPin> dout7 { DO7_MODE, (uint32_t)200000 }; -gpioDigitalOutputPin> dout8 { DO8_MODE, (uint32_t)200000 }; -gpioDigitalOutputPin> dout9 { DO9_MODE, (uint32_t)200000 }; -gpioDigitalOutputPin> dout10 { DO10_MODE, (uint32_t)200000 }; -gpioDigitalOutputPin> dout11 { DO11_MODE, (uint32_t)200000 }; -gpioDigitalOutputPin> dout12 { DO12_MODE, (uint32_t)200000 }; -gpioDigitalOutputPin> dout13 { DO13_MODE, (uint32_t)200000 }; +gpioDigitalOutputPin> dout1 { DO1_ENABLED, DO1_POLARITY, (uint32_t)200000 }; +gpioDigitalOutputPin> dout2 { DO2_ENABLED, DO2_POLARITY, (uint32_t)200000 }; +gpioDigitalOutputPin> dout3 { DO3_ENABLED, DO3_POLARITY, (uint32_t)200000 }; +gpioDigitalOutputPin> dout4 { DO4_ENABLED, DO4_POLARITY, (uint32_t)200000 }; +gpioDigitalOutputPin> dout5 { DO5_ENABLED, DO5_POLARITY, (uint32_t)200000 }; +gpioDigitalOutputPin> dout6 { DO6_ENABLED, DO6_POLARITY, (uint32_t)200000 }; +gpioDigitalOutputPin> dout7 { DO7_ENABLED, DO7_POLARITY, (uint32_t)200000 }; +gpioDigitalOutputPin> dout8 { DO8_ENABLED, DO8_POLARITY, (uint32_t)200000 }; +gpioDigitalOutputPin> dout9 { DO9_ENABLED, DO9_POLARITY, (uint32_t)200000 }; +gpioDigitalOutputPin> dout10 { DO10_ENABLED, DO10_POLARITY, (uint32_t)200000 }; +gpioDigitalOutputPin> dout11 { DO11_ENABLED, DO11_POLARITY, (uint32_t)200000 }; +gpioDigitalOutputPin> dout12 { DO12_ENABLED, DO12_POLARITY, (uint32_t)200000 }; +gpioDigitalOutputPin> dout13 { DO13_ENABLED, DO13_POLARITY, (uint32_t)200000 }; /**** Setup Arrays - these are extern and MUST match the board_gpio.h ****/ diff --git a/g2core/board/gquintic/board_gpio.cpp b/g2core/board/gquintic/board_gpio.cpp index 4daf011d8..1ee6d9a95 100644 --- a/g2core/board/gquintic/board_gpio.cpp +++ b/g2core/board/gquintic/board_gpio.cpp @@ -56,53 +56,88 @@ /**** Setup Actual Objects ****/ -gpioDigitalInputPin> din1 {DI1_MODE, 1}; -gpioDigitalInputPin> din2 {DI2_MODE, 2}; -gpioDigitalInputPin> din3 {DI3_MODE, 3}; -gpioDigitalInputPin> din4 {DI4_MODE, 4}; -gpioDigitalInputPin> din5 {DI5_MODE, 5}; -gpioDigitalInputPin> din6 {DI6_MODE, 6}; -gpioDigitalInputPin> din7 {DI7_MODE, 7}; -gpioDigitalInputPin> din8 {DI8_MODE, 8}; -gpioDigitalInputPin> din9 {DI9_MODE, 9}; -// gpioDigitalInputPin> din10 {DI10_MODE, 10}; -// gpioDigitalInputPin> din11 {DI11_MODE, 11}; -// gpioDigitalInputPin> din12 {DI12_MODE, 12}; - -gpioDigitalOutputPin> dout1 { DO1_MODE, (uint32_t)200000 }; -gpioDigitalOutputPin> dout2 { DO2_MODE, (uint32_t)200000 }; -gpioDigitalOutputPin> dout3 { DO3_MODE, (uint32_t)200000 }; -gpioDigitalOutputPin> dout4 { DO4_MODE, (uint32_t)200000 }; -gpioDigitalOutputPin> dout5 { DO5_MODE, (uint32_t)200000 }; -gpioDigitalOutputPin> dout6 { DO6_MODE, (uint32_t)200000 }; -gpioDigitalOutputPin> dout7 { DO7_MODE, (uint32_t)200000 }; -gpioDigitalOutputPin> dout8 { DO8_MODE, (uint32_t)200000 }; -gpioDigitalOutputPin> dout9 { DO9_MODE, (uint32_t)200000 }; -gpioDigitalOutputPin> dout10 { DO10_MODE, (uint32_t)200000 }; -gpioDigitalOutputPin> dout11 { DO11_MODE, (uint32_t)200000 }; -gpioDigitalOutputPin> dout12 { DO12_MODE, (uint32_t)200000 }; -gpioDigitalOutputPin> dout13 { DO13_MODE, (uint32_t)200000 }; - -/**** Setup Arrays - these are extern and MUST match the board_gpio.h ****/ +gpioDigitalInputPin> din1 {DI1_ENABLED, DI1_POLARITY, 1}; +gpioDigitalInputPin> din2 {DI2_ENABLED, DI2_POLARITY, 2}; +gpioDigitalInputPin> din3 {DI3_ENABLED, DI3_POLARITY, 3}; +gpioDigitalInputPin> din4 {DI4_ENABLED, DI4_POLARITY, 4}; +gpioDigitalInputPin> din5 {DI5_ENABLED, DI5_POLARITY, 5}; +gpioDigitalInputPin> din6 {DI6_ENABLED, DI6_POLARITY, 6}; +gpioDigitalInputPin> din7 {DI7_ENABLED, DI7_POLARITY, 7}; +gpioDigitalInputPin> din8 {DI8_ENABLED, DI8_POLARITY, 8}; +gpioDigitalInputPin> din9 {DI9_ENABLED, DI9_POLARITY, 9}; +// gpioDigitalInputPin> din10 {DI10ENABLEDE, DI10_POLARITY, 10}; +// gpioDigitalInputPin> din11 {DI11ENABLEDE, DI11_POLARITY, 11}; +// gpioDigitalInputPin> din12 {DI12ENABLEDE, DI12_POLARITY, 12}; gpioDigitalInput* const d_in[] = {&din1, &din2, &din3, &din4, &din5, &din6, &din7, &din8, &din9}; + + +gpioDigitalOutputPin> dout1 { DO1_ENABLED, DO1_POLARITY, (uint32_t)200000 }; +gpioDigitalOutputPin> dout2 { DO2_ENABLED, DO2_POLARITY, (uint32_t)200000 }; +gpioDigitalOutputPin> dout3 { DO3_ENABLED, DO3_POLARITY, (uint32_t)200000 }; +gpioDigitalOutputPin> dout4 { DO4_ENABLED, DO4_POLARITY, (uint32_t)200000 }; +gpioDigitalOutputPin> dout5 { DO5_ENABLED, DO5_POLARITY, (uint32_t)200000 }; +gpioDigitalOutputPin> dout6 { DO6_ENABLED, DO6_POLARITY, (uint32_t)200000 }; +gpioDigitalOutputPin> dout7 { DO7_ENABLED, DO7_POLARITY, (uint32_t)200000 }; +gpioDigitalOutputPin> dout8 { DO8_ENABLED, DO8_POLARITY, (uint32_t)200000 }; +gpioDigitalOutputPin> dout9 { DO9_ENABLED, DO9_POLARITY, (uint32_t)200000 }; +gpioDigitalOutputPin> dout10 { DO10_ENABLED, DO10_POLARITY, (uint32_t)200000 }; +gpioDigitalOutputPin> dout11 { DO11_ENABLED, DO11_POLARITY, (uint32_t)200000 }; +gpioDigitalOutputPin> dout12 { DO12_ENABLED, DO12_POLARITY, (uint32_t)200000 }; +gpioDigitalOutputPin> dout13 { DO13_ENABLED, DO13_POLARITY, (uint32_t)200000 }; + gpioDigitalOutput* const d_out[] = {&dout1, &dout2, &dout3, &dout4, &dout5, &dout6, &dout7, &dout8, &dout9, &dout10, &dout11, &dout12, &dout13}; -// not yet used -// gpioAnalogInput* a_in[A_IN_CHANNELS]; -// gpioAnalogOutput* a_out[A_OUT_CHANNELS]; + + +#if QUINTIC_REVISION == 'C' + +gpioAnalogInputPin> ain1 {gpioAnalogInput::AIN_TYPE_EXTERNAL, 1, spiBus, spiCSPinMux.getCS(5)}; +gpioAnalogInputPin> ain2 {gpioAnalogInput::AIN_TYPE_EXTERNAL, 2, spiBus, spiCSPinMux.getCS(6)}; +gpioAnalogInputPin> ain3 {gpioAnalogInput::AIN_TYPE_INTERNAL, 3}; +gpioAnalogInputPin> ain4 {gpioAnalogInput::AIN_TYPE_INTERNAL, 4}; + +gpioAnalogInput* const a_in[] = {&ain1, &ain2, &ain3, &ain4}; + +#endif // 'C' + +#if QUINTIC_REVISION == 'D' + +gpioAnalogInputPin> ain1 {gpioAnalogInput::AIN_TYPE_INTERNAL, 1}; +gpioAnalogInputPin> ain2 {gpioAnalogInput::AIN_TYPE_INTERNAL, 2}; +gpioAnalogInputPin> ain3 {gpioAnalogInput::AIN_TYPE_INTERNAL, 3}; +gpioAnalogInputPin> ain4 {gpioAnalogInput::AIN_TYPE_INTERNAL, 4}; + +gpioAnalogInput* const a_in[] = {&ain1, &ain2, &ain3, &ain4}; + +#endif // 'D' + /************************************************************************************ **** CODE ************************************************************************** ************************************************************************************/ + + + // Register a SysTick event to call start_sampling every temperature_sample_freq ms + const int16_t ain_sample_freq = 10; + int16_t ain_sample_counter = ain_sample_freq; + Motate::SysTickEvent ain_tick_event {[&] { + if (!--ain_sample_counter) { + ain1.startSampling(); + ain2.startSampling(); + ain3.startSampling(); + ain4.startSampling(); + ain_sample_counter = ain_sample_freq; + } + }, nullptr}; + /* * gpio_reset() - reset inputs and outputs (no initialization) */ - void outputs_reset(void) { // nothing to do } void inputs_reset(void) { - // nothing to do + SysTickTimer.registerEvent(&ain_tick_event); } diff --git a/g2core/board/gquintic/board_gpio.h b/g2core/board/gquintic/board_gpio.h index 25a1cddcd..ea4182464 100644 --- a/g2core/board/gquintic/board_gpio.h +++ b/g2core/board/gquintic/board_gpio.h @@ -30,35 +30,30 @@ // this file is included from the bottom of gpio.h, but we do this for completeness #include "../../gpio.h" +#include "hardware.h" /* * GPIO defines */ //--- change as required for board and switch hardware ---// -#define D_IN_CHANNELS 9 // v9 // number of digital inputs supported -#define D_OUT_CHANNELS 13 // number of digital outputs supported -#define A_IN_CHANNELS 0 // number of analog inputs supported -#define A_OUT_CHANNELS 0 // number of analog outputs supported - #define INPUT_LOCKOUT_MS 10 // milliseconds to go dead after input firing /* * The GPIO objects themselves - this must match up with board_gpio.cpp! */ -extern gpioDigitalInput* const d_in[D_IN_CHANNELS]; -extern gpioDigitalOutput* const d_out[D_OUT_CHANNELS]; -// extern gpioAnalogInput* a_in[A_IN_CHANNELS]; -// extern gpioAnalogOutput* a_out[A_OUT_CHANNELS]; - // prepare the objects as externs (for config_app to not bloat) using Motate::IRQPin; using Motate::PWMOutputPin; using Motate::PWMLikeOutputPin; +using Motate::ADCPin; +using Motate::ADCDifferentialPair; template using OutputType = typename std::conditional, PWMLikeOutputPin>::type; +#define D_IN_CHANNELS 9 // number of digital inputs supported + extern gpioDigitalInputPin> din1; extern gpioDigitalInputPin> din2; extern gpioDigitalInputPin> din3; @@ -72,6 +67,11 @@ extern gpioDigitalInputPin> din9; // extern gpioDigitalInputPin> din11; // extern gpioDigitalInputPin> din12; +extern gpioDigitalInput* const d_in[D_IN_CHANNELS]; + + +#define D_OUT_CHANNELS 13 // number of digital outputs supported + extern gpioDigitalOutputPin> dout1; extern gpioDigitalOutputPin> dout2; extern gpioDigitalOutputPin> dout3; @@ -86,5 +86,88 @@ extern gpioDigitalOutputPin> dout12; extern gpioDigitalOutputPin> dout13; +extern gpioDigitalOutput* const d_out[D_OUT_CHANNELS]; + + +#if QUINTIC_REVISION == 'C' + +#define A_IN_CHANNELS 4 // number of analog inputs supported + +#include "device/max31865/max31865.h" +#define USING_A_MAX31865 1 + +#ifndef AI1_TYPE +#define AI1_TYPE gpioAnalogInput::AIN_TYPE_EXTERNAL +#endif +#ifndef AI1_CIRCUIT +#define AI1_CIRCUIT gpioAnalogInput::AIN_CIRCUIT_EXTERNAL +#endif +extern gpioAnalogInputPin> ain1; + +#ifndef AI2_TYPE +#define AI2_TYPE gpioAnalogInput::AIN_TYPE_EXTERNAL +#endif +#ifndef AI2_CIRCUIT +#define AI2_CIRCUIT gpioAnalogInput::AIN_CIRCUIT_EXTERNAL +#endif +extern gpioAnalogInputPin> ain2; + +#ifndef AI3_TYPE +#define AI3_TYPE gpioAnalogInput::AIN_TYPE_INTERNAL +#endif +#ifndef AI3_CIRCUIT +#define AI3_CIRCUIT gpioAnalogInput::AIN_CIRCUIT_PULLUP +#endif +extern gpioAnalogInputPin> ain3; + +#ifndef AI4_TYPE +#define AI4_TYPE gpioAnalogInput::AIN_TYPE_INTERNAL +#endif +#ifndef AI4_CIRCUIT +#define AI4_CIRCUIT gpioAnalogInput::AIN_CIRCUIT_PULLUP +#endif +extern gpioAnalogInputPin> ain4; + +#endif // 'C' + +#if QUINTIC_REVISION == 'D' + +#define A_IN_CHANNELS 4 // number of analog inputs supported + +#ifndef AI1_TYPE +#define AI1_TYPE gpioAnalogInput::AIN_TYPE_INTERNAL +#endif +#ifndef AI1_CIRCUIT +#define AI1_CIRCUIT gpioAnalogInput::AIN_CIRCUIT_CC_INV_OPAMP +#endif +extern gpioAnalogInputPin> ain1; + +#ifndef AI2_TYPE +#define AI2_TYPE gpioAnalogInput::AIN_TYPE_INTERNAL +#endif +#ifndef AI2_CIRCUIT +#define AI2_CIRCUIT gpioAnalogInput::AIN_CIRCUIT_CC_INV_OPAMP +#endif +extern gpioAnalogInputPin> ain2; + +#ifndef AI3_TYPE +#define AI3_TYPE gpioAnalogInput::AIN_TYPE_INTERNAL +#endif +#ifndef AI3_CIRCUIT +#define AI3_CIRCUIT gpioAnalogInput::AIN_CIRCUIT_INV_OPAMP +#endif +extern gpioAnalogInputPin> ain3; + +#ifndef AI4_TYPE +#define AI4_TYPE gpioAnalogInput::AIN_TYPE_INTERNAL +#endif +#ifndef AI4_CIRCUIT +#define AI4_CIRCUIT gpioAnalogInput::AIN_CIRCUIT_INV_OPAMP +#endif +extern gpioAnalogInputPin> ain4; + +#endif // 'D' + +extern gpioAnalogInput* const a_in[A_IN_CHANNELS]; #endif // End of include guard: BOARD_GPIO_H_ONCE diff --git a/g2core/config.cpp b/g2core/config.cpp index 596d34fb3..26335686a 100644 --- a/g2core/config.cpp +++ b/g2core/config.cpp @@ -256,7 +256,7 @@ stat_t set_noop(nvObj_t *nv) { return (STAT_OK); // hack until JSON is refactored } -stat_t set_nul(nvObj_t *nv) { +stat_t set_nul(nvObj_t *nv) { // nv->valuetype = TYPE_NULL; // return (STAT_PARAMETER_IS_READ_ONLY); // this is what it should be return (STAT_OK); // hack until JSON is refactored @@ -264,11 +264,11 @@ stat_t set_nul(nvObj_t *nv) { stat_t set_ro(nvObj_t *nv) { // hack. If setting an SR it doesn't fail - if (strcmp(nv_body->token, "sr") == 0) { - return (STAT_OK); + if (strcmp(nv_body->token, "sr") == 0) { + return (STAT_OK); } nv->valuetype = TYPE_NULL; - return (STAT_PARAMETER_IS_READ_ONLY); + return (STAT_PARAMETER_IS_READ_ONLY); } stat_t set_ui8(nvObj_t *nv) @@ -465,6 +465,14 @@ index_t nv_get_index(const char *group, const char *token) if (c != str[3]) continue; // 4th character mismatch if ((c = GET_TOKEN_BYTE(token[4])) == NUL) { if (str[4] == NUL) return(i);} // four character match if (c != str[4]) continue; // 5th character mismatch + if ((c = GET_TOKEN_BYTE(token[5])) == NUL) { if (str[5] == NUL) return(i);} // four character match + if (c != str[5]) continue; // 6th character mismatch + if ((c = GET_TOKEN_BYTE(token[6])) == NUL) { if (str[6] == NUL) return(i);} // four character match + if (c != str[6]) continue; // 7th character mismatch + if ((c = GET_TOKEN_BYTE(token[7])) == NUL) { if (str[7] == NUL) return(i);} // four character match + if (c != str[7]) continue; // 8th character mismatch + if ((c = GET_TOKEN_BYTE(token[8])) == NUL) { if (str[8] == NUL) return(i);} // four character match + if (c != str[8]) continue; // 9th character mismatch return (i); // five character match } return (NO_MATCH); @@ -617,7 +625,7 @@ nvObj_t *nv_add_object(const char *token) // add an object to the body usi if (nv->valuetype != TYPE_EMPTY) { if ((nv = nv->nx) == NULL) { // not supposed to find a NULL; here for safety return(NULL); - } + } continue; } // load the index from the token or die trying @@ -634,7 +642,7 @@ nvObj_t *nv_add_integer(const char *token, const uint32_t value)// add an intege for (uint8_t i=0; ivaluetype != TYPE_EMPTY) { if ((nv = nv->nx) == NULL) { // not supposed to find a NULL; here for safety - return(NULL); + return(NULL); } continue; } @@ -652,8 +660,8 @@ nvObj_t *nv_add_data(const char *token, const uint32_t value)// add an integer o for (uint8_t i=0; ivaluetype != TYPE_EMPTY) { if ((nv = nv->nx) == NULL) { // not supposed to find a NULL; here for safety - return(NULL); - } + return(NULL); + } continue; } strcpy(nv->token, token); @@ -672,7 +680,7 @@ nvObj_t *nv_add_float(const char *token, const float value) // add a float ob if (nv->valuetype != TYPE_EMPTY) { if ((nv = nv->nx) == NULL) { // not supposed to find a NULL; here for safety return(NULL); - } + } continue; } strncpy(nv->token, token, TOKEN_LEN); @@ -689,8 +697,8 @@ nvObj_t *nv_add_string(const char *token, const char *string) // add a string ob for (uint8_t i=0; ivaluetype != TYPE_EMPTY) { if ((nv = nv->nx) == NULL) { // not supposed to find a NULL; here for safety - return(NULL); - } + return(NULL); + } continue; } strncpy(nv->token, token, TOKEN_LEN); diff --git a/g2core/config.h b/g2core/config.h index a8b1ebddb..9fc566453 100644 --- a/g2core/config.h +++ b/g2core/config.h @@ -185,8 +185,8 @@ typedef uint32_t index_t; // use this because set/get_int is expec // Stuff you probably don't want to change -#define GROUP_LEN 4 // max length of group prefix -#define TOKEN_LEN 6 // mnemonic token string: group prefix + short token +#define GROUP_LEN 6 // max length of group prefix +#define TOKEN_LEN 9 // mnemonic token string: group prefix + short token #define NV_FOOTER_LEN 18 // sufficient space to contain a JSON footer array #define NV_LIST_LEN (NV_BODY_LEN+2) // +2 allows for a header and a footer #define NV_EXEC_FIRST (NV_BODY_LEN+2) // index of the first EXEC nv diff --git a/g2core/config_app.cpp b/g2core/config_app.cpp index ff4179966..412217e10 100644 --- a/g2core/config_app.cpp +++ b/g2core/config_app.cpp @@ -483,54 +483,66 @@ const cfgItem_t cfgArray[] = { { "c","czb",_fip, 3, cm_print_zb, get_flt, set_flt, (float *)&cm.a[AXIS_C].zero_backoff, C_ZERO_BACKOFF }, // Digital input configs - { "di1","di1mo",_fip, 0, din_print_mo, din_get_mo, din_set_mo, (float *)&din1, DI1_MODE }, + { "di1","di1en",_fip, 0, din_print_en, din_get_en, din_set_en, (float *)&din1, DI1_ENABLED }, + { "di1","di1po",_fip, 0, din_print_po, din_get_po, din_set_po, (float *)&din1, DI1_POLARITY }, { "di1","di1ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din1, DI1_ACTION }, { "di1","di1fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din1, DI1_FUNCTION }, - { "di2","di2mo",_fip, 0, din_print_mo, din_get_mo, din_set_mo, (float *)&din2, DI2_MODE }, + { "di2","di2en",_fip, 0, din_print_en, din_get_en, din_set_en, (float *)&din2, DI2_ENABLED }, + { "di2","di2po",_fip, 0, din_print_po, din_get_po, din_set_po, (float *)&din2, DI2_POLARITY }, { "di2","di2ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din2, DI2_ACTION }, { "di2","di2fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din2, DI2_FUNCTION }, - { "di3","di3mo",_fip, 0, din_print_mo, din_get_mo, din_set_mo, (float *)&din3, DI3_MODE }, + { "di3","di3en",_fip, 0, din_print_en, din_get_en, din_set_en, (float *)&din3, DI3_ENABLED }, + { "di3","di3po",_fip, 0, din_print_po, din_get_po, din_set_po, (float *)&din3, DI3_POLARITY }, { "di3","di3ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din3, DI3_ACTION }, { "di3","di3fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din3, DI3_FUNCTION }, - { "di4","di4mo",_fip, 0, din_print_mo, din_get_mo, din_set_mo, (float *)&din4, DI4_MODE }, + { "di4","di4en",_fip, 0, din_print_en, din_get_en, din_set_en, (float *)&din4, DI4_ENABLED }, + { "di4","di4po",_fip, 0, din_print_po, din_get_po, din_set_po, (float *)&din4, DI4_POLARITY }, { "di4","di4ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din4, DI4_ACTION }, { "di4","di4fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din4, DI4_FUNCTION }, - { "di5","di5mo",_fip, 0, din_print_mo, din_get_mo, din_set_mo, (float *)&din5, DI5_MODE }, + { "di5","di5en",_fip, 0, din_print_en, din_get_en, din_set_en, (float *)&din5, DI5_ENABLED }, + { "di5","di5po",_fip, 0, din_print_po, din_get_po, din_set_po, (float *)&din5, DI5_POLARITY }, { "di5","di5ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din5, DI5_ACTION }, { "di5","di5fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din5, DI5_FUNCTION }, - { "di6","di6mo",_fip, 0, din_print_mo, din_get_mo, din_set_mo, (float *)&din6, DI6_MODE }, + { "di6","di6en",_fip, 0, din_print_en, din_get_en, din_set_en, (float *)&din6, DI6_ENABLED }, + { "di6","di6po",_fip, 0, din_print_po, din_get_po, din_set_po, (float *)&din6, DI6_POLARITY }, { "di6","di6ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din6, DI6_ACTION }, { "di6","di6fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din6, DI6_FUNCTION }, - { "di7","di7mo",_fip, 0, din_print_mo, din_get_mo, din_set_mo, (float *)&din7, DI7_MODE }, + { "di7","di7en",_fip, 0, din_print_en, din_get_en, din_set_en, (float *)&din7, DI7_ENABLED }, + { "di7","di7po",_fip, 0, din_print_po, din_get_po, din_set_po, (float *)&din7, DI7_POLARITY }, { "di7","di7ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din7, DI7_ACTION }, { "di7","di7fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din7, DI7_FUNCTION }, - { "di8","di8mo",_fip, 0, din_print_mo, din_get_mo, din_set_mo, (float *)&din8, DI8_MODE }, + { "di8","di8en",_fip, 0, din_print_en, din_get_en, din_set_en, (float *)&din8, DI8_ENABLED }, + { "di3","di8po",_fip, 0, din_print_po, din_get_po, din_set_po, (float *)&din8, DI8_POLARITY }, { "di8","di8ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din8, DI8_ACTION }, { "di8","di8fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din8, DI8_FUNCTION }, #if (D_IN_CHANNELS >= 9) - { "di9","di9mo",_fip, 0, din_print_mo, din_get_mo, din_set_mo, (float *)&din9, DI9_MODE }, + { "di9","di9en",_fip, 0, din_print_en, din_get_en, din_set_en, (float *)&din9, DI9_ENABLED }, + { "di9","di9po",_fip, 0, din_print_po, din_get_po, din_set_po, (float *)&din9, DI9_POLARITY }, { "di9","di9ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din9, DI9_ACTION }, { "di9","di9fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din9, DI9_FUNCTION }, #endif #if (D_IN_CHANNELS >= 10) - { "di10","di10mo",_fip, 0, din_print_mo, din_get_mo, din_set_mo, (float *)&din10, DI10_MODE }, + { "di10","di10en",_fip, 0, din_print_en, din_get_en, din_set_en, (float *)&din10, DI10_ENABLED }, + { "di10","di10po",_fip, 0, din_print_po, din_get_po, din_set_po, (float *)&din10, DI10_POLARITY }, { "di10","di10ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din10, DI10_ACTION }, { "di10","di10fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din10, DI10_FUNCTION }, #endif #if (D_IN_CHANNELS >= 11) - { "di11","di11mo",_fip, 0, din_print_mo, din_get_mo, din_set_mo, (float *)&din11, DI11_MODE }, + { "di11","di11en",_fip, 0, din_print_en, din_get_en, din_set_en, (float *)&din11, DI11_ENABLED }, + { "di11","di11po",_fip, 0, din_print_po, din_get_po, din_set_po, (float *)&din11, DI11_POLARITY }, { "di11","di11ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din11, DI11_ACTION }, { "di11","di11fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din11, DI11_FUNCTION }, #endif #if (D_IN_CHANNELS >= 12) - { "di12","di12mo",_fip, 0, din_print_mo, din_get_mo, din_set_mo, (float *)&din12, DI12_MODE }, + { "di12","di12en",_fip, 0, din_print_en, din_get_en, din_set_en, (float *)&din12, DI12_ENABLED }, + { "di12","di12po",_fip, 0, din_print_po, din_get_po, din_set_po, (float *)&din12, DI12_POLARITY }, { "di12","di12ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din12, DI12_ACTION }, { "di12","di12fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din12, DI12_FUNCTION }, #endif @@ -558,19 +570,30 @@ const cfgItem_t cfgArray[] = { #endif // digital output configs - { "do1", "do1mo", _fip, 0, dout_print_mo, dout_get_mo, dout_set_mo, (float *)&dout1, DO1_MODE }, - { "do2", "do2mo", _fip, 0, dout_print_mo, dout_get_mo, dout_set_mo, (float *)&dout2, DO2_MODE }, - { "do3", "do3mo", _fip, 0, dout_print_mo, dout_get_mo, dout_set_mo, (float *)&dout3, DO3_MODE }, - { "do4", "do4mo", _fip, 0, dout_print_mo, dout_get_mo, dout_set_mo, (float *)&dout4, DO4_MODE }, - { "do5", "do5mo", _fip, 0, dout_print_mo, dout_get_mo, dout_set_mo, (float *)&dout5, DO5_MODE }, - { "do6", "do6mo", _fip, 0, dout_print_mo, dout_get_mo, dout_set_mo, (float *)&dout6, DO6_MODE }, - { "do7", "do7mo", _fip, 0, dout_print_mo, dout_get_mo, dout_set_mo, (float *)&dout7, DO7_MODE }, - { "do8", "do8mo", _fip, 0, dout_print_mo, dout_get_mo, dout_set_mo, (float *)&dout8, DO8_MODE }, - { "do9", "do9mo", _fip, 0, dout_print_mo, dout_get_mo, dout_set_mo, (float *)&dout9, DO9_MODE }, - { "do10","do10mo",_fip, 0, dout_print_mo, dout_get_mo, dout_set_mo, (float *)&dout10, DO10_MODE }, - { "do11","do11mo",_fip, 0, dout_print_mo, dout_get_mo, dout_set_mo, (float *)&dout11, DO11_MODE }, - { "do12","do12mo",_fip, 0, dout_print_mo, dout_get_mo, dout_set_mo, (float *)&dout12, DO12_MODE }, - { "do13","do13mo",_fip, 0, dout_print_mo, dout_get_mo, dout_set_mo, (float *)&dout13, DO13_MODE }, + { "do1", "do1en", _fip, 0, dout_print_en, dout_get_en, dout_set_en, (float *)&dout1, DO1_ENABLED }, + { "do1", "do1po", _fip, 0, dout_print_po, dout_get_po, dout_set_po, (float *)&dout1, DO1_POLARITY }, + { "do2", "do2en", _fip, 0, dout_print_en, dout_get_en, dout_set_en, (float *)&dout2, DO2_ENABLED }, + { "do2", "do2po", _fip, 0, dout_print_po, dout_get_po, dout_set_po, (float *)&dout2, DO2_POLARITY }, + { "do3", "do3en", _fip, 0, dout_print_en, dout_get_en, dout_set_en, (float *)&dout3, DO3_ENABLED }, + { "do3", "do3po", _fip, 0, dout_print_po, dout_get_po, dout_set_po, (float *)&dout3, DO3_POLARITY }, + { "do4", "do4en", _fip, 0, dout_print_en, dout_get_en, dout_set_en, (float *)&dout4, DO4_ENABLED }, + { "do5", "do5po", _fip, 0, dout_print_po, dout_get_po, dout_set_po, (float *)&dout5, DO5_POLARITY }, + { "do5", "do5en", _fip, 0, dout_print_en, dout_get_en, dout_set_en, (float *)&dout5, DO5_ENABLED }, + { "do6", "do6po", _fip, 0, dout_print_po, dout_get_po, dout_set_po, (float *)&dout6, DO6_POLARITY }, + { "do7", "do7en", _fip, 0, dout_print_en, dout_get_en, dout_set_en, (float *)&dout7, DO7_ENABLED }, + { "do7", "do7po", _fip, 0, dout_print_po, dout_get_po, dout_set_po, (float *)&dout7, DO7_POLARITY }, + { "do8", "do8en", _fip, 0, dout_print_en, dout_get_en, dout_set_en, (float *)&dout8, DO8_ENABLED }, + { "do8", "do8po", _fip, 0, dout_print_po, dout_get_po, dout_set_po, (float *)&dout8, DO8_POLARITY }, + { "do9", "do9en", _fip, 0, dout_print_en, dout_get_en, dout_set_en, (float *)&dout9, DO9_ENABLED }, + { "do9", "do9po", _fip, 0, dout_print_po, dout_get_po, dout_set_po, (float *)&dout9, DO9_POLARITY }, + { "do10","do10en",_fip, 0, dout_print_en, dout_get_en, dout_set_en, (float *)&dout10, DO10_ENABLED }, + { "do10","do10po",_fip, 0, dout_print_po, dout_get_po, dout_set_po, (float *)&dout10, DO10_POLARITY }, + { "do11","do11en",_fip, 0, dout_print_en, dout_get_en, dout_set_en, (float *)&dout11, DO11_ENABLED }, + { "do11","do11po",_fip, 0, dout_print_po, dout_get_po, dout_set_po, (float *)&dout11, DO11_POLARITY }, + { "do12","do12en",_fip, 0, dout_print_en, dout_get_en, dout_set_en, (float *)&dout12, DO12_ENABLED }, + { "do12","do12po",_fip, 0, dout_print_po, dout_get_po, dout_set_po, (float *)&dout12, DO12_POLARITY }, + { "do13","do13en",_fip, 0, dout_print_en, dout_get_en, dout_set_en, (float *)&dout13, DO13_ENABLED }, + { "do13","do13po",_fip, 0, dout_print_po, dout_get_po, dout_set_po, (float *)&dout13, DO13_POLARITY }, // Digital output state readers (default to non-active) { "out","out1", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&dout1, 0 }, @@ -587,6 +610,47 @@ const cfgItem_t cfgArray[] = { { "out","out12", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&dout12, 0 }, { "out","out13", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&dout13, 0 }, + // Analog input configs + { "ain1","ain1ty",_fip, 0, ain_print_type, ain_get_type, ain_set_type, (float *)&ain1, AI1_TYPE }, + { "ain1","ain1ct",_fip, 0, ain_print_circuit, ain_get_circuit, ain_set_circuit, (float *)&ain1, AI1_CIRCUIT }, + { "ain1","ain1p1",_fip, 4, ain_print_p, ain_get_p1, ain_set_p1, (float *)&ain1, AI1_P1 }, + { "ain1","ain1p2",_fip, 4, ain_print_p, ain_get_p2, ain_set_p2, (float *)&ain1, AI1_P2 }, + { "ain1","ain1p3",_fip, 4, ain_print_p, ain_get_p3, ain_set_p3, (float *)&ain1, AI1_P3 }, + { "ain1","ain1p4",_fip, 4, ain_print_p, ain_get_p4, ain_set_p4, (float *)&ain1, AI1_P4 }, + { "ain1","ain1p5",_fip, 4, ain_print_p, ain_get_p5, ain_set_p5, (float *)&ain1, AI1_P5 }, + { "ain1","ain1vv",_f0, 4, ain_print_value, ain_get_value, set_ro, (float *)&ain1, 0 }, + { "ain1","ain1rv",_f0, 2, ain_print_resistance, ain_get_resistance, set_ro, (float *)&ain1, 0 }, + + { "ain2","ain2ty",_fip, 0, ain_print_type, ain_get_type, ain_set_type, (float *)&ain2, AI2_TYPE }, + { "ain2","ain2ct",_fip, 0, ain_print_circuit, ain_get_circuit, ain_set_circuit, (float *)&ain2, AI2_CIRCUIT }, + { "ain2","ain2p1",_fip, 4, ain_print_p, ain_get_p1, ain_set_p1, (float *)&ain2, AI2_P1 }, + { "ain2","ain2p2",_fip, 4, ain_print_p, ain_get_p2, ain_set_p2, (float *)&ain2, AI2_P2 }, + { "ain2","ain2p3",_fip, 4, ain_print_p, ain_get_p3, ain_set_p3, (float *)&ain2, AI2_P3 }, + { "ain2","ain2p4",_fip, 4, ain_print_p, ain_get_p4, ain_set_p4, (float *)&ain2, AI2_P4 }, + { "ain2","ain2p5",_fip, 4, ain_print_p, ain_get_p5, ain_set_p5, (float *)&ain2, AI2_P5 }, + { "ain2","ain2vv",_f0, 4, ain_print_value, ain_get_value, set_ro, (float *)&ain2, 0 }, + { "ain2","ain2rv",_f0, 2, ain_print_resistance, ain_get_resistance, set_ro, (float *)&ain2, 0 }, + + { "ain3","ain3ty",_fip, 0, ain_print_type, ain_get_type, ain_set_type, (float *)&ain3, AI3_TYPE }, + { "ain3","ain3ct",_fip, 0, ain_print_circuit, ain_get_circuit, ain_set_circuit, (float *)&ain3, AI3_CIRCUIT }, + { "ain3","ain3p1",_fip, 4, ain_print_p, ain_get_p1, ain_set_p1, (float *)&ain3, AI3_P1 }, + { "ain3","ain3p2",_fip, 4, ain_print_p, ain_get_p2, ain_set_p2, (float *)&ain3, AI3_P2 }, + { "ain3","ain3p3",_fip, 4, ain_print_p, ain_get_p3, ain_set_p3, (float *)&ain3, AI3_P3 }, + { "ain3","ain3p4",_fip, 4, ain_print_p, ain_get_p4, ain_set_p4, (float *)&ain3, AI3_P4 }, + { "ain3","ain3p5",_fip, 4, ain_print_p, ain_get_p5, ain_set_p5, (float *)&ain3, AI3_P5 }, + { "ain3","ain3vv",_f0, 4, ain_print_value, ain_get_value, set_ro, (float *)&ain3, 0 }, + { "ain3","ain3rv",_f0, 2, ain_print_resistance, ain_get_resistance, set_ro, (float *)&ain3, 0 }, + + { "ain4","ain4ty",_fip, 0, ain_print_type, ain_get_type, ain_set_type, (float *)&ain4, AI4_TYPE }, + { "ain4","ain4ct",_fip, 0, ain_print_circuit, ain_get_circuit, ain_set_circuit, (float *)&ain4, AI4_CIRCUIT }, + { "ain4","ain4p1",_fip, 4, ain_print_p, ain_get_p1, ain_set_p1, (float *)&ain4, AI4_P1 }, + { "ain4","ain4p2",_fip, 4, ain_print_p, ain_get_p2, ain_set_p2, (float *)&ain4, AI4_P2 }, + { "ain4","ain4p3",_fip, 4, ain_print_p, ain_get_p3, ain_set_p3, (float *)&ain4, AI4_P3 }, + { "ain4","ain4p4",_fip, 4, ain_print_p, ain_get_p4, ain_set_p4, (float *)&ain4, AI4_P4 }, + { "ain4","ain4p5",_fip, 4, ain_print_p, ain_get_p5, ain_set_p5, (float *)&ain4, AI4_P5 }, + { "ain4","ain4vv",_f0, 4, ain_print_value, ain_get_value, set_ro, (float *)&ain4, 0 }, + { "ain4","ain4rv",_f0, 2, ain_print_resistance, ain_get_resistance, set_ro, (float *)&ain4, 0 }, + // PWM settings { "p1","p1frq",_fip, 0, pwm_print_p1frq, get_flt, pwm_set_pwm,(float *)&pwm.c[PWM_1].frequency, P1_PWM_FREQUENCY }, { "p1","p1csl",_fip, 0, pwm_print_p1csl, get_flt, pwm_set_pwm,(float *)&pwm.c[PWM_1].cw_speed_lo, P1_CW_SPEED_LO }, @@ -1244,6 +1308,11 @@ const cfgItem_t cfgArray[] = { { "","do12", _f0, 0, tx_print_nul, get_grp, set_grp,(float *)&cs.null,0 }, { "","do13", _f0, 0, tx_print_nul, get_grp, set_grp,(float *)&cs.null,0 }, // +14 = 36 + { "","ain1", _f0, 0, tx_print_nul, get_grp, set_grp,(float *)&cs.null,0 }, // analog input configs + { "","ain2", _f0, 0, tx_print_nul, get_grp, set_grp,(float *)&cs.null,0 }, + { "","ain3", _f0, 0, tx_print_nul, get_grp, set_grp,(float *)&cs.null,0 }, + { "","ain4", _f0, 0, tx_print_nul, get_grp, set_grp,(float *)&cs.null,0 }, + // +4 = 40 { "","g54",_f0, 0, tx_print_nul, get_grp, set_grp,(float *)&cs.null,0 }, // coord offset groups { "","g55",_f0, 0, tx_print_nul, get_grp, set_grp,(float *)&cs.null,0 }, { "","g56",_f0, 0, tx_print_nul, get_grp, set_grp,(float *)&cs.null,0 }, @@ -1253,7 +1322,7 @@ const cfgItem_t cfgArray[] = { { "","g92",_f0, 0, tx_print_nul, get_grp, set_grp,(float *)&cs.null,0 }, // origin offsets { "","g28",_f0, 0, tx_print_nul, get_grp, set_grp,(float *)&cs.null,0 }, // g28 home position { "","g30",_f0, 0, tx_print_nul, get_grp, set_grp,(float *)&cs.null,0 }, // g30 home position - // +9 = 45 + // +9 = 49 { "","tof",_f0, 0, tx_print_nul, get_grp, set_grp,(float *)&cs.null,0 }, // tool offsets { "","tt1",_f0, 0, tx_print_nul, get_grp, set_grp,(float *)&cs.null,0 }, // tt offsets { "","tt2",_f0, 0, tx_print_nul, get_grp, set_grp,(float *)&cs.null,0 }, // tt offsets @@ -1271,7 +1340,7 @@ const cfgItem_t cfgArray[] = { { "","tt14",_f0, 0, tx_print_nul, get_grp, set_grp,(float *)&cs.null,0 }, // tt offsets { "","tt15",_f0, 0, tx_print_nul, get_grp, set_grp,(float *)&cs.null,0 }, // tt offsets { "","tt16",_f0, 0, tx_print_nul, get_grp, set_grp,(float *)&cs.null,0 }, // tt offsets - // +17 = 62 + // +17 = 66 { "","mpo",_f0, 0, tx_print_nul, get_grp, set_grp,(float *)&cs.null,0 }, // machine position group { "","pos",_f0, 0, tx_print_nul, get_grp, set_grp,(float *)&cs.null,0 }, // work position group { "","ofs",_f0, 0, tx_print_nul, get_grp, set_grp,(float *)&cs.null,0 }, // work offset group @@ -1280,14 +1349,14 @@ const cfgItem_t cfgArray[] = { { "","pwr",_f0, 0, tx_print_nul, get_grp, set_grp,(float *)&cs.null,0 }, // motor power enagled group { "","jog",_f0, 0, tx_print_nul, get_grp, set_grp,(float *)&cs.null,0 }, // axis jogging state group { "","jid",_f0, 0, tx_print_nul, get_grp, set_grp,(float *)&cs.null,0 }, // job ID group - // +8 = 70 + // +8 = 74 { "","he1", _f0, 0, tx_print_nul, get_grp, set_grp,(float *)&cs.null,0 }, // heater 1 group { "","he2", _f0, 0, tx_print_nul, get_grp, set_grp,(float *)&cs.null,0 }, // heater 2 group { "","he3", _f0, 0, tx_print_nul, get_grp, set_grp,(float *)&cs.null,0 }, // heater 3 group { "","pid1",_f0, 0, tx_print_nul, get_grp, set_grp,(float *)&cs.null,0 }, // PID 1 group { "","pid2",_f0, 0, tx_print_nul, get_grp, set_grp,(float *)&cs.null,0 }, // PID 2 group { "","pid3",_f0, 0, tx_print_nul, get_grp, set_grp,(float *)&cs.null,0 }, // PID 3 group - // +6 = 76 + // +6 = 80 #ifdef __USER_DATA { "","uda", _f0, 0, tx_print_nul, get_grp, set_grp,(float *)&cs.null,0 }, // user data group @@ -1524,6 +1593,10 @@ static stat_t _do_inputs(nvObj_t *nv) // print parameters for all input groups sprintf(group, "di%d", i); _do_group(nv, group); } + for (uint8_t i=1; i < A_IN_CHANNELS+1; i++) { + sprintf(group, "ain%d", i); + _do_group(nv, group); + } return (STAT_COMPLETE); // STAT_COMPLETE suppresses the normal response line } diff --git a/g2core/coolant.cpp b/g2core/coolant.cpp index f19cea957..c553c6a6b 100755 --- a/g2core/coolant.cpp +++ b/g2core/coolant.cpp @@ -30,6 +30,7 @@ #include "canonical_machine.h" // #3 #include "text_parser.h" // #4 +#include "gpio.h" #include "coolant.h" #include "planner.h" #include "hardware.h" @@ -39,6 +40,17 @@ cmCoolantSingleton_t coolant; +gpioDigitalOutput *mist_enable_output = nullptr; +gpioDigitalOutput *flood_enable_output = nullptr; + +#ifndef MIST_ENABLE_OUTPUT_NUMBER +#define MIST_ENABLE_OUTPUT_NUMBER 6 +#endif + +#ifndef FLOOD_ENABLE_OUTPUT_NUMBER +#define FLOOD_ENABLE_OUTPUT_NUMBER 7 +#endif + /**** Static functions ****/ static void _exec_coolant_control(float* value, bool* flags); @@ -48,6 +60,17 @@ static void _exec_coolant_control(float* value, bool* flags); * coolant_reset() */ void coolant_init() { + if (MIST_ENABLE_OUTPUT_NUMBER > 0) { + mist_enable_output = d_out[MIST_ENABLE_OUTPUT_NUMBER-1]; + mist_enable_output->setEnabled(IO_ENABLED); + mist_enable_output->setPolarity((ioPolarity)COOLANT_MIST_POLARITY); + } + if (FLOOD_ENABLE_OUTPUT_NUMBER > 0) { + flood_enable_output = d_out[FLOOD_ENABLE_OUTPUT_NUMBER-1]; + flood_enable_output->setEnabled(IO_ENABLED); + flood_enable_output->setPolarity((ioPolarity)COOLANT_FLOOD_POLARITY); + } + coolant.mist_enable = COOLANT_OFF; coolant.flood_enable = COOLANT_OFF; } @@ -129,26 +152,32 @@ stat_t cm_mist_coolant_control(uint8_t mist_enable) { } // NOTE: flood and mist coolants are mapped to the same pin - see hardware.h -#define _set_flood_enable_bit_hi() flood_enable_pin.set() -#define _set_flood_enable_bit_lo() flood_enable_pin.clear() -#define _set_mist_enable_bit_hi() mist_enable_pin.set() -#define _set_mist_enable_bit_lo() mist_enable_pin.clear() +//#define _set_flood_enable_bit_hi() flood_enable_pin.set() +//#define _set_flood_enable_bit_lo() flood_enable_pin.clear() +//#define _set_mist_enable_bit_hi() mist_enable_pin.set() +//#define _set_mist_enable_bit_lo() mist_enable_pin.clear() static void _exec_coolant_control(float* value, bool* flags) { if (flags[COOLANT_FLOOD]) { coolant.flood_enable = (cmCoolantEnable)value[COOLANT_FLOOD]; - if (!((coolant.flood_enable & 0x01) ^ coolant.flood_polarity)) { // inverted XOR - _set_flood_enable_bit_hi(); - } else { - _set_flood_enable_bit_lo(); +// if (!((coolant.flood_enable & 0x01) ^ coolant.flood_polarity)) { // inverted XOR +// _set_flood_enable_bit_hi(); +// } else { +// _set_flood_enable_bit_lo(); +// } + if (flood_enable_output != nullptr) { + flood_enable_output->setValue(coolant.flood_enable); } } if (flags[COOLANT_MIST]) { coolant.mist_enable = (cmCoolantEnable)value[COOLANT_MIST]; - if (!((coolant.mist_enable & 0x01) ^ coolant.mist_polarity)) { - _set_mist_enable_bit_hi(); - } else { - _set_mist_enable_bit_lo(); +// if (!((coolant.mist_enable & 0x01) ^ coolant.mist_polarity)) { +// _set_mist_enable_bit_hi(); +// } else { +// _set_mist_enable_bit_lo(); +// } + if (mist_enable_output != nullptr) { + mist_enable_output->setValue(coolant.mist_enable); } } } diff --git a/g2core/device/max31865/max31865.h b/g2core/device/max31865/max31865.h index 9908860f0..4f89144c2 100644 --- a/g2core/device/max31865/max31865.h +++ b/g2core/device/max31865/max31865.h @@ -405,6 +405,13 @@ struct MAX31865 final { return _rtd_value; }; + float getPullupResistance() { + return _pullup_resistance; + } + void setPullupResistance(const float r) { + _pullup_resistance = r; + } + // getValue is supposed to request a new value, block, and then return the result // PUNT - return the same as getRaw() int32_t getValue() { @@ -463,4 +470,101 @@ struct MAX31865 final { }; + +// A gpioAnalogInputPin subclass for the MAX31865 + +template +struct gpioAnalogInputPin> : gpioAnalogInput { +protected: // so we know if anyone tries to reach in + AnalogInputType_t type; + + uint8_t ext_pin_number; // the number used externally for this pin ("in" + ext_pin_number) + + using ADCPin_t = MAX31865; + + ADCPin_t pin; // the actual pin object itself + +public: + // In constructor, simply forward all values to the pin + // To get a different behavior, override this object. + template + gpioAnalogInputPin(const AnalogInputType_t _type, const uint8_t _ext_pin_number, T&&... additional_values) : + gpioAnalogInput{}, + type{_type}, + ext_pin_number{_ext_pin_number}, + pin{Motate::kNormal, [&](bool e){this->adc_has_new_value(e);}, additional_values...} + { + // nothing to do here + }; + + // functions for use by other parts of the code, and are overridden + + float getValue() override + { + if (type == AIN_TYPE_DISABLED) { + return 0; + } + return pin.getVoltage(); + }; + float getResistance() override + { + if (type == AIN_TYPE_DISABLED) { + return -1; + } + return pin.getResistance(); + }; + + AnalogInputType_t getType() override + { + return type; + }; + bool setType(const AnalogInputType_t t) override + { + // NOTE: Only AIN_TYPE_EXTERNAL and AIN_TYPE_DISABLED are handled here! + if (t == AIN_TYPE_INTERNAL) { + return false; + } + type = t; + return true; + }; + + AnalogCircuit_t getCircuit() override + { + return AIN_CIRCUIT_EXTERNAL; + }; + bool setCircuit(const AnalogCircuit_t c) override + { + // prevent setting circuit - it's always AIN_CIRCUIT_EXTERNAL + return false; + }; + + float getParameter(const uint8_t p) override + { + if (p == 0) { + return pin.getPullupResistance(); + } + return 0; + }; + bool setParameter(const uint8_t p, const float v) override + { + if (p == 0) { + pin.setPullupResistance(v); + return true; + } + return false; + }; + + + void startSampling() override { + pin.startSampling(); + }; + + // support function for pin value update interrupt handling + + void adc_has_new_value(bool err) { +// float raw_adc_value = pin.getRaw(); +// history.add_sample(raw_adc_value); + }; +}; + #endif // max31865_h diff --git a/g2core/gpio.cpp b/g2core/gpio.cpp index 02d1b480b..0cb6e9aef 100644 --- a/g2core/gpio.cpp +++ b/g2core/gpio.cpp @@ -118,7 +118,7 @@ void gpio_set_probing_mode(const uint8_t input_num_ext, const bool is_probing) int8_t gpio_get_probing_input(void) { - for (uint8_t i = 0; i <= D_IN_CHANNELS; i++) { + for (uint8_t i = 1; i <= D_IN_CHANNELS; i++) { if (d_in[i-1]->getFunction() == INPUT_FUNCTION_PROBE) { return (i); } @@ -151,42 +151,31 @@ type* _io(const nvObj_t *nv) { gpioDigitalInput* _i(const nvObj_t *nv) { return _io(nv); } gpioDigitalOutput* _o(const nvObj_t *nv) { return _io(nv); } +gpioAnalogInput* _ai(const nvObj_t *nv) { return _io(nv); } -// static stat_t _input_set_helper(nvObj_t *nv, const int8_t lower_bound, const int8_t upper_bound) -// { -// if ((nv->value < lower_bound) || (nv->value >= upper_bound)) { -// return (STAT_INPUT_VALUE_RANGE_ERROR); -// } -// set_ui8(nv); // will this work in -1 is a valid value? -// if (cm_get_machine_state() != MACHINE_INITIALIZING) { -// inputs_reset(); -// } -// return (STAT_OK); -// } -// -// static stat_t _output_set_helper(nvObj_t *nv, const int8_t lower_bound, const int8_t upper_bound) -// { -// if ((nv->value < lower_bound) || (nv->value >= upper_bound)) { -// return (STAT_INPUT_VALUE_RANGE_ERROR); -// } -// set_ui8(nv); // will this work in -1 is a valid value? -// if (cm_get_machine_state() != MACHINE_INITIALIZING) { -// outputs_reset(); -// } -// return (STAT_OK); -// } +/* + * Get/set enabled + */ +stat_t din_get_en(nvObj_t *nv) +{ + return _i(nv)->getEnabled(nv); +} +stat_t din_set_en(nvObj_t *nv) +{ + return _i(nv)->setEnabled(nv); +} /* - * Get/set input mode + * Get/set input polarity */ -stat_t din_get_mo(nvObj_t *nv) +stat_t din_get_po(nvObj_t *nv) { - return _i(nv)->getMode(nv); + return _i(nv)->getPolarity(nv); } -stat_t din_set_mo(nvObj_t *nv) +stat_t din_set_po(nvObj_t *nv) { - return _i(nv)->setMode(nv); + return _i(nv)->setPolarity(nv); } /* @@ -223,13 +212,28 @@ stat_t din_get_input(nvObj_t *nv) } -stat_t dout_get_mo(nvObj_t *nv) +/* + * Get/set enabled + */ +stat_t dout_get_en(nvObj_t *nv) +{ + return _o(nv)->getEnabled(nv); +} +stat_t dout_set_en(nvObj_t *nv) +{ + return _o(nv)->setEnabled(nv); +} + +/* + * Get/set input polarity + */ +stat_t dout_get_po(nvObj_t *nv) { - return _o(nv)->getMode(nv); + return _o(nv)->getPolarity(nv); } -stat_t dout_set_mo(nvObj_t *nv) +stat_t dout_set_po(nvObj_t *nv) { - return _o(nv)->setMode(nv); + return _o(nv)->setPolarity(nv); } /* @@ -244,6 +248,59 @@ stat_t dout_set_output(nvObj_t *nv) return _o(nv)->setValue(nv); } + +/* + * ain_get_value() - get the measured voltage level of the analog input + */ +stat_t ain_get_value(nvObj_t *nv) { + return _ai(nv)->getValue(nv); +} +// no ain_set_value + +/* + * ain_get_resistance() - get the measured resistance of the analog input + * NOTE: Requires the circuit type to be configured and the relevant parameters set + */ +stat_t ain_get_resistance(nvObj_t *nv) { + return _ai(nv)->getResistance(nv); +} +// no ain_set_resistance + +/* + * ain_get_type() - get the measured voltage level of the analog input + */ +stat_t ain_get_type(nvObj_t *nv) { + return _ai(nv)->getType(nv); +} +stat_t ain_set_type(nvObj_t *nv) { + return _ai(nv)->setType(nv); +} + +stat_t ain_get_circuit(nvObj_t *nv) { + return _ai(nv)->getCircuit(nv); +} +stat_t ain_set_circuit(nvObj_t *nv) { + return _ai(nv)->setCircuit(nv); +} + +stat_t ain_get_parameter(nvObj_t *nv, const uint8_t p) { + return _ai(nv)->getParameter(nv, p); +} +stat_t ain_set_parameter(nvObj_t *nv, const uint8_t p) { + return _ai(nv)->setParameter(nv, p); +} + +stat_t ain_get_p1(nvObj_t *nv) { return ain_get_parameter(nv, 0); }; +stat_t ain_set_p1(nvObj_t *nv) { return ain_set_parameter(nv, 0); }; +stat_t ain_get_p2(nvObj_t *nv) { return ain_get_parameter(nv, 1); }; +stat_t ain_set_p2(nvObj_t *nv) { return ain_set_parameter(nv, 1); }; +stat_t ain_get_p3(nvObj_t *nv) { return ain_get_parameter(nv, 2); }; +stat_t ain_set_p3(nvObj_t *nv) { return ain_set_parameter(nv, 2); }; +stat_t ain_get_p4(nvObj_t *nv) { return ain_get_parameter(nv, 3); }; +stat_t ain_set_p4(nvObj_t *nv) { return ain_set_parameter(nv, 3); }; +stat_t ain_get_p5(nvObj_t *nv) { return ain_get_parameter(nv, 4); }; +stat_t ain_set_p5(nvObj_t *nv) { return ain_set_parameter(nv, 4); }; + /*********************************************************************************** * TEXT MODE SUPPORT * Functions to print variables from the cfgArray table @@ -251,20 +308,29 @@ stat_t dout_set_output(nvObj_t *nv) #ifdef __TEXT_MODE - static const char fmt_gpio_mo[] = "[%smo] input mode%17d [0=active-low,1=active-hi,2=disabled]\n"; + static const char fmt_gpio_in_en[] = "[%smo] input enabled%13d [-1=unavailable,0=disabled,1=enabled]\n"; + static const char fmt_gpio_in_po[] = "[%smo] input polarity%13d [0=normal/active-high,1=inverted/active-low]\n"; static const char fmt_gpio_ac[] = "[%sac] input action%15d [0=none,1=stop,2=fast_stop,3=halt,4=alarm,5=shutdown,6=panic,7=reset]\n"; static const char fmt_gpio_fn[] = "[%sfn] input function%13d [0=none,1=limit,2=interlock,3=shutdown,4=probe]\n"; static const char fmt_gpio_in[] = "Input %s state: %5d\n"; - static const char fmt_gpio_domode[] = "[%smo] output mode%16d [0=active low,1=active high,2=disabled]\n"; + static const char fmt_gpio_out_en[] = "[%smo] output enabled%12d [-1=unavailable,0=disabled,1=enabled]\n"; + static const char fmt_gpio_out_po[] = "[%smo] output polarity%12d [0=normal/active-high,1=inverted/active-low]\n"; static const char fmt_gpio_out[] = "Output %s state: %5d\n"; + static const char fmt_ain_value[] = "Analog input %s voltage: %5.2fV\n"; + static const char fmt_ain_resistance[] = "Analog input %s resistance: %5.2fohm\n"; + static const char fmt_ain_type[] = "[%s] input type%17d [0=disabled,1=internal,2=external]\n"; + static const char fmt_ain_circuit[] = "[%s] analog circuit%13d [0=disabled,1=pull-up,2=external,3=inverted op-amp,4=constant current inverted op-amp]\n"; + static const char fmt_ain_parameter[] = "[%s] circuit parameter%6.4f [usage varies by circuit type]\n"; + static void _print_di(nvObj_t *nv, const char *format) { sprintf(cs.out_buf, format, nv->group, (int)nv->value); xio_writeline(cs.out_buf); } - void din_print_mo(nvObj_t *nv) {_print_di(nv, fmt_gpio_mo);} + void din_print_en(nvObj_t *nv) {_print_di(nv, fmt_gpio_in_en);} + void din_print_po(nvObj_t *nv) {_print_di(nv, fmt_gpio_in_po);} void din_print_ac(nvObj_t *nv) {_print_di(nv, fmt_gpio_ac);} void din_print_fn(nvObj_t *nv) {_print_di(nv, fmt_gpio_fn);} void din_print_in(nvObj_t *nv) { @@ -272,9 +338,39 @@ stat_t dout_set_output(nvObj_t *nv) xio_writeline(cs.out_buf); } - void dout_print_mo(nvObj_t *nv) {_print_di(nv, fmt_gpio_domode);} + void dout_print_en(nvObj_t *nv) {_print_di(nv, fmt_gpio_out_en);} + void dout_print_po(nvObj_t *nv) {_print_di(nv, fmt_gpio_out_po);} void dout_print_out(nvObj_t *nv) { sprintf(cs.out_buf, fmt_gpio_out, nv->token, (int)nv->value); xio_writeline(cs.out_buf); } + + void ain_print_value(nvObj_t *nv) + { + sprintf(cs.out_buf, fmt_ain_value, nv->token, (float)nv->value); + xio_writeline(cs.out_buf); + } + void ain_print_resistance(nvObj_t *nv) + { + sprintf(cs.out_buf, fmt_ain_resistance, nv->token, (float)nv->value); + xio_writeline(cs.out_buf); + } + void ain_print_type(nvObj_t *nv) + { + sprintf(cs.out_buf, fmt_ain_type, nv->token, (int)nv->value); + xio_writeline(cs.out_buf); + } + + void ain_print_circuit(nvObj_t *nv) + { + sprintf(cs.out_buf, fmt_ain_circuit, nv->token, (int)nv->value); + xio_writeline(cs.out_buf); + } + + void ain_print_p(nvObj_t *nv) + { + sprintf(cs.out_buf, fmt_ain_parameter, nv->token, (float)nv->value); + xio_writeline(cs.out_buf); + } + #endif diff --git a/g2core/gpio.h b/g2core/gpio.h index cc5390b07..b782863f5 100644 --- a/g2core/gpio.h +++ b/g2core/gpio.h @@ -42,6 +42,7 @@ #include "MotatePins.h" using Motate::kPullUp; using Motate::kDebounce; +using Motate::kStartHigh; using Motate::kStartLow; using Motate::kPWMPinInverted; @@ -54,13 +55,17 @@ using Motate::kPWMPinInverted; //--- do not change from here down ---// typedef enum { - IO_ACTIVE_LOW = 0, // input/output is active low (aka normally open) - IO_ACTIVE_HIGH = 1, // input/output is active high (aka normally closed) - IO_MODE_DISABLED = 2 // input/output is disabled -} ioMode; + IO_UNAVAILABLE = -1, // input/output is missing/used/unavailable + IO_DISABLED = 0, // input/output is disabled + IO_ENABLED = 1 // input/output enabled +} ioEnabled; + +typedef enum { + IO_ACTIVE_HIGH = 0, // input/output is active high (aka normally closed) + IO_ACTIVE_LOW = 1, // input/output is active low (aka normally open) +} ioPolarity; #define NORMALLY_OPEN IO_ACTIVE_LOW // equivalent #define NORMALLY_CLOSED IO_ACTIVE_HIGH // equivalent -#define IO_MODE_MAX IO_MODE_DISABLED // for range checking typedef enum { // actions are initiated from within the input's ISR INPUT_ACTION_NONE = 0, @@ -97,10 +102,11 @@ typedef enum { } inputEdgeFlag; /* - * GPIO structures + * gpioDigitalInput - digital input base class */ struct gpioDigitalInput { - // this is the implementation for a non-existant pin - see gpioDigitalInputPin for a real pin + // this is the generic implementation for a "any"" digital input pin + // see gpioDigitalInputPin for a real pin // functions for use by other parts of the code @@ -112,8 +118,11 @@ struct gpioDigitalInput { virtual inputAction getAction(); virtual bool setAction(const inputAction); - virtual ioMode getMode(); - virtual bool setMode(const ioMode); + virtual ioEnabled getEnabled(); + virtual bool setEnabled(const ioEnabled); + + virtual ioPolarity getPolarity(); + virtual bool setPolarity(const ioPolarity); virtual void setExternalNumber(const uint8_t); virtual void setIsHoming(const bool); @@ -124,8 +133,7 @@ struct gpioDigitalInput { stat_t getState(nvObj_t *nv) { - if (getMode() == IO_MODE_DISABLED) { - nv->value = IO_MODE_DISABLED; // historical consistency + if (getEnabled() <= IO_DISABLED) { nv->valuetype = TYPE_NULL; return (STAT_OK); } @@ -135,18 +143,35 @@ struct gpioDigitalInput { }; // no setState - stat_t getMode(nvObj_t *nv) + stat_t getEnabled(nvObj_t *nv) + { + nv->value = getEnabled(); + nv->valuetype = TYPE_INT; + return (STAT_OK); + }; + stat_t setEnabled(nvObj_t *nv) + { + if ((nv->value < IO_DISABLED) || (nv->value > IO_ENABLED)) { + return (STAT_INPUT_VALUE_RANGE_ERROR); + } + if (!setEnabled((ioEnabled)nv->value)) { + return STAT_PARAMETER_IS_READ_ONLY; + } + return (STAT_OK); + }; + + stat_t getPolarity(nvObj_t *nv) { - nv->value = getMode(); + nv->value = getPolarity(); nv->valuetype = TYPE_INT; return (STAT_OK); }; - stat_t setMode(nvObj_t *nv) + stat_t setPolarity(nvObj_t *nv) { - if ((nv->value < IO_ACTIVE_LOW) || (nv->value >= IO_MODE_MAX)) { + if ((nv->value < IO_ACTIVE_HIGH) || (nv->value > IO_ACTIVE_LOW)) { return (STAT_INPUT_VALUE_RANGE_ERROR); } - if (!setMode((ioMode)nv->value)) { + if (!setPolarity((ioPolarity)nv->value)) { return STAT_PARAMETER_IS_READ_ONLY; } return (STAT_OK); @@ -160,7 +185,7 @@ struct gpioDigitalInput { }; stat_t setAction(nvObj_t *nv) { - if ((nv->value < INPUT_ACTION_NONE) || (nv->value >= INPUT_ACTION_MAX)) { + if ((nv->value < INPUT_ACTION_NONE) || (nv->value > INPUT_ACTION_MAX)) { return (STAT_INPUT_VALUE_RANGE_ERROR); } if (!setAction((inputAction)nv->value)) { @@ -177,7 +202,7 @@ struct gpioDigitalInput { }; stat_t setFunction(nvObj_t *nv) { - if ((nv->value < INPUT_FUNCTION_NONE) || (nv->value >= INPUT_FUNCTION_MAX)) { + if ((nv->value < INPUT_FUNCTION_NONE) || (nv->value > INPUT_FUNCTION_MAX)) { return (STAT_INPUT_VALUE_RANGE_ERROR); } if (!setFunction((inputFunc)nv->value)) { @@ -187,12 +212,15 @@ struct gpioDigitalInput { }; }; -template +/* + * gpioDigitalInputPin - concrete child of gpioDigitalInput + */ +template struct gpioDigitalInputPin : gpioDigitalInput { -protected: // so we know if anyone tries to reach in - ioMode mode; // 0=active low (NO), 1= active high (NC), 2=disabled + ioEnabled enabled; // -1=unavailable, 0=disabled, 1=enabled + ioPolarity polarity; // 0=normal/active high, 1=inverted/active low inputAction action; // 0=none, 1=stop, 2=halt, 3=stop_steps, 4=reset - inputFunc function; // function to perform when activated / deactivated + inputFunc input_function; // function to perform when activated / deactivated inputEdgeFlag edge; // keeps a transient record of edges for immediate inquiry @@ -204,44 +232,41 @@ struct gpioDigitalInputPin : gpioDigitalInput { uint16_t lockout_ms; // number of milliseconds for debounce lockout Motate::Timeout lockout_timer; // time to expire current debounce lockout, or 0 if no lockout - pinType pin; // the actual pin object itself + Pin_t pin; // the actual pin object itself -public: - // In constructor, simply forward all values to the pinType + // In constructor, simply forward all values to the Pin_t // To get a different behavior, override this object. template - gpioDigitalInputPin(const ioMode _mode, const uint8_t _ext_pin_number, T&&... V) : + gpioDigitalInputPin(const ioEnabled _enabled, const ioPolarity _polarity, const uint8_t _ext_pin_number, T&&... V) : gpioDigitalInput{}, - mode{_mode}, + enabled{_enabled}, + polarity{_polarity}, ext_pin_number{_ext_pin_number}, - pin{((mode == IO_ACTIVE_LOW) ? kPullUp|kDebounce : kDebounce), [&]{this->pin_changed();}, std::forward(V)...} - {}; - - // gpioDigitalInputPin(const ioMode _mode, const uint8_t _ext_pin_number) : - // gpioDigitalInput{}, - // mode{_mode}, - // ext_pin_number{_ext_pin_number}, - // pin{((mode == IO_ACTIVE_LOW) ? kPullUp|kDebounce : kDebounce), [&]{this->pin_changed();}} - // {}; + pin{((polarity == IO_ACTIVE_LOW) ? kPullUp|kDebounce : kDebounce), [&]{this->pin_changed();}, std::forward(V)...} + { + if (pin.isNull()) { + enabled = IO_UNAVAILABLE; + } + }; // functions for use by other parts of the code, and are overridden bool getState() override { - if (mode == IO_MODE_DISABLED) { + if (enabled <= IO_DISABLED) { return false; } const bool v = (const bool)pin; - return (mode == IO_ACTIVE_HIGH) ? v : !v; + return (polarity == IO_ACTIVE_HIGH) ? v : !v; }; inputFunc getFunction() override { - return function; + return input_function; } bool setFunction(const inputFunc f) override { - function = f; + input_function = f; return true; }; @@ -255,14 +280,27 @@ struct gpioDigitalInputPin : gpioDigitalInput { return true; }; - ioMode getMode() override + ioEnabled getEnabled() override + { + return enabled; + }; + bool setEnabled(const ioEnabled m) override + { + if (enabled == IO_UNAVAILABLE) { + return false; + } + enabled = m; + return true; + }; + + ioPolarity getPolarity() override { - return mode; + return polarity; }; - bool setMode(const ioMode m) override + bool setPolarity(const ioPolarity new_polarity) override { - mode = m; - pin.setOptions((mode == IO_ACTIVE_LOW) ? kPullUp|kDebounce : kDebounce); + polarity = new_polarity; + pin.setOptions((polarity == IO_ACTIVE_LOW) ? kPullUp|kDebounce : kDebounce); return true; }; @@ -287,7 +325,7 @@ struct gpioDigitalInputPin : gpioDigitalInput { void pin_changed() { // return if input is disabled - if (mode == IO_MODE_DISABLED) { + if (enabled == IO_DISABLED) { return; } @@ -297,7 +335,7 @@ struct gpioDigitalInputPin : gpioDigitalInput { } ioState pin_value = (ioState)(bool)pin; - ioState pin_value_corrected = (ioState)(pin_value ^ ((bool)mode ^ 1)); // correct for NO or NC mode + ioState pin_value_corrected = (ioState)(pin_value ^ ((bool)polarity)); // correct for NO or NC mode // This shouldn't be necessary - the processor shouldn't call without an edge // if (state == (ioState)pin_value_corrected) { @@ -370,74 +408,89 @@ struct gpioDigitalInputPin : gpioDigitalInput { // these functions also trigger on the leading edge - if (function == INPUT_FUNCTION_LIMIT) { + if (input_function == INPUT_FUNCTION_LIMIT) { cm.limit_requested = ext_pin_number; - } else if (function == INPUT_FUNCTION_SHUTDOWN) { + } else if (input_function == INPUT_FUNCTION_SHUTDOWN) { cm.shutdown_requested = ext_pin_number; - } else if (function == INPUT_FUNCTION_INTERLOCK) { + } else if (input_function == INPUT_FUNCTION_INTERLOCK) { cm.safety_interlock_disengaged = ext_pin_number; } } // if (edge == INPUT_EDGE_LEADING) // trigger interlock release on trailing edge if (edge == INPUT_EDGE_TRAILING) { - if (function == INPUT_FUNCTION_INTERLOCK) { + if (input_function == INPUT_FUNCTION_INTERLOCK) { cm.safety_interlock_reengaged = ext_pin_number; } } sr_request_status_report(SR_REQUEST_TIMED); //+++++ Put this one back in. }; - }; +/* + * gpioDigitalOutput - digital/PWM output base class + */ struct gpioDigitalOutput { + // this is the generic implementation for a "any"" output pin (PWM or Digital) + // see gpioDigitalOutputPin for a real pin // functions for use by other parts of the code, and are what to override - virtual ioMode getMode() - { - return IO_MODE_DISABLED; - }; - virtual bool setMode(const ioMode) - { - return false; - }; + virtual ioEnabled getEnabled(); + virtual bool setEnabled(const ioEnabled); - virtual float getValue() - { - return -1; - }; - virtual bool setValue(const float) - { - return false; - }; + virtual ioPolarity getPolarity(); + virtual bool setPolarity(const ioPolarity); + + virtual float getValue(); + virtual bool setValue(const float); + + virtual float getFrequency(); + virtual bool setFrequency(const float); // functions that take nvObj_t* and return stat_t, NOT overridden - virtual stat_t getMode(nvObj_t *nv) + stat_t getEnabled(nvObj_t *nv) + { + nv->value = getEnabled(); + nv->valuetype = TYPE_INT; + return (STAT_OK); + }; + stat_t setEnabled(nvObj_t *nv) + { + if ((nv->value < IO_DISABLED) || (nv->value > IO_ENABLED)) { + return (STAT_INPUT_VALUE_RANGE_ERROR); + } + if (!setEnabled((ioEnabled)nv->value)) { + return STAT_PARAMETER_IS_READ_ONLY; + } + return (STAT_OK); + }; + + stat_t getPolarity(nvObj_t *nv) { - nv->value = getMode(); + nv->value = getPolarity(); nv->valuetype = TYPE_INT; return (STAT_OK); }; - virtual stat_t setMode(nvObj_t *nv) + stat_t setPolarity(nvObj_t *nv) { - if ((nv->value < IO_ACTIVE_LOW) || (nv->value >= IO_MODE_MAX)) { + if ((nv->value < IO_ACTIVE_HIGH) || (nv->value > IO_ACTIVE_LOW)) { return (STAT_INPUT_VALUE_RANGE_ERROR); } - if (!setMode((ioMode)nv->value)) { - return STAT_INPUT_VALUE_RANGE_ERROR; + if (!setPolarity((ioPolarity)nv->value)) { + return STAT_PARAMETER_IS_READ_ONLY; } return (STAT_OK); }; virtual stat_t getValue(nvObj_t *nv) { - auto mode = getMode(); - if (mode == IO_MODE_DISABLED) { + auto enabled = getEnabled(); + if (enabled <= IO_DISABLED) { nv->value = 0; nv->valuetype = TYPE_NULL; // reports back as NULL } else { @@ -445,7 +498,7 @@ struct gpioDigitalOutput { nv->precision = 2; nv->value = getValue(); // read it as a float - bool invert = (mode == 0); + bool invert = (getPolarity() == IO_ACTIVE_LOW); if (invert) { nv->value = 1.0 - nv->value; } @@ -454,13 +507,13 @@ struct gpioDigitalOutput { }; virtual stat_t setValue(nvObj_t *nv) { - auto mode = getMode(); - if (mode == IO_MODE_DISABLED) { + auto enabled = getEnabled(); + if (enabled <= IO_DISABLED) { nv->valuetype = TYPE_NULL; // reports back as NULL } else { float value = nv->value; // read it as a float - bool invert = (mode == 0); + bool invert = (getPolarity() == IO_ACTIVE_LOW); if (invert) { value = 1.0 - value; } @@ -474,33 +527,53 @@ struct gpioDigitalOutput { }; -template +/* + * gpioDigitalOutputPin - concrete child of gpioDigitalOutput + */ +template struct gpioDigitalOutputPin : gpioDigitalOutput { - ioMode mode; // 0=active low (NO), 1= active high (NC), 2=disabled - pinType pin; + ioEnabled enabled; // -1=unavailable, 0=disabled, 1=enabled + ioPolarity polarity; // 0=normal/active high, 1=inverted/active low + Pin_t pin; - // In constructor, simply forward all values to the pinType + // In constructor, simply forward all values to the Pin_t template - gpioDigitalOutputPin(const ioMode _mode, T&&... V) : + gpioDigitalOutputPin(const ioEnabled _enabled, const ioPolarity _polarity, T&&... V) : gpioDigitalOutput{}, - mode{ _mode }, - pin{((mode == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow), std::forward(V)...} - {}; + enabled{ _enabled }, + polarity{ _polarity }, + pin{((polarity == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow), std::forward(V)...} + { + if (pin.isNull()) { + enabled = IO_UNAVAILABLE; + } + }; // functions for use by other parts of the code, and are overridden - ioMode getMode() override + ioEnabled getEnabled() override { - return mode; + return enabled; }; - bool setMode(const ioMode m) override + bool setEnabled(const ioEnabled m) override { - mode = m; - pin.setOptions((mode == IO_ACTIVE_LOW) ? kPullUp|kDebounce : kDebounce); // prepare the pin - pin = ((mode == IO_ACTIVE_LOW) ? true : false); // set the output to inactive + if (enabled == IO_UNAVAILABLE) { + return false; + } + enabled = m; return true; }; + ioPolarity getPolarity() override + { + return polarity; + }; + bool setPolarity(const ioPolarity new_polarity) override + { + polarity = new_polarity; + pin.setOptions((polarity == IO_ACTIVE_LOW) ? kPullUp|kDebounce : kDebounce); + return true; + }; float getValue() override { @@ -515,14 +588,368 @@ struct gpioDigitalOutputPin : gpioDigitalOutput { return true; }; + float _last_set_frequency = 0; + // it must be set through this interface at least once before it can be read back + float getFrequency() override + { + return _last_set_frequency; + }; + bool setFrequency(const float freq) override + { + pin.setFrequency(freq); + _last_set_frequency = freq; + return true; + }; + +}; + +/* + * gpioAnalogInput - analog (ADC) input base class + */ +struct gpioAnalogInput { + // type of analog input source - read only - defined by the board + enum AnalogInputType_t { + AIN_TYPE_DISABLED = 0, // the whole input is disabled + AIN_TYPE_INTERNAL = 1, // single-ended or differential + AIN_TYPE_EXTERNAL = 2, // for externally (SPI) connected inputs + }; + + // type of circuit connected - for use in determining the resistance + enum AnalogCircuit_t { + AIN_CIRCUIT_DISABLED = 0, // there is no circuit, resistance will read -1 + // no additional configuration + AIN_CIRCUIT_PULLUP = 1, // resistance being measured is pulling up to VCC + // the pull-up resistance is measured (rt) + // p1 is the set pull-down resistance (r1) + AIN_CIRCUIT_EXTERNAL = 2, // for externally (SPI) connected inputs + // no additional configuration + AIN_CIRCUIT_INV_OPAMP = 3, // inverted op-amp connected + // the pull-up resistance is measured (rt) + // p1 is the set pull-down resistance of the bias(+) (r1) + // p2 is the set pull-up resistance of the gain(-) (r2) + // p3 is the set pull-down to output of the gain(-) (r3) + AIN_CIRCUIT_CC_INV_OPAMP = 4, // for externally (SPI) connected inputs + // the pull-up resistance to the current source is measured (rt) + // p4 is the set pull-up resistance of the bias(+) (r4) + // p1 is the set pull-down resistance of the bias(+) (r1) + // p2 is the set pull-up resistance of the gain(-) (r2) + // p3 is the set pull-down to output of the gain(-) (r3) + // p5 is the set constant current in millivolts (c1) + }; + static const auto AIN_CIRCUIT_MAX = AIN_CIRCUIT_CC_INV_OPAMP; + + // this is the generic implementation for a "any"" analog input pin + // see gpioAnalogInputPin for a real pin + + // functions for use by other parts of the code + + virtual float getValue(); + virtual float getResistance(); + + virtual AnalogInputType_t getType(); + virtual bool setType(const AnalogInputType_t); + + virtual AnalogCircuit_t getCircuit(); + virtual bool setCircuit(const AnalogCircuit_t); + + virtual float getParameter(const uint8_t p); + virtual bool setParameter(const uint8_t p, const float v); + + virtual void startSampling(); + + // functions that take nvObj_t* and return stat_t, NOT overridden + + stat_t getValue(nvObj_t *nv) + { + if (getType() == AIN_TYPE_DISABLED) { + nv->valuetype = TYPE_NULL; + return (STAT_OK); + } + nv->value = getValue(); + nv->valuetype = TYPE_FLOAT; + return (STAT_OK); + }; + // no setValue + + stat_t getResistance(nvObj_t *nv) + { + if (getType() == AIN_TYPE_DISABLED || getCircuit() == AIN_CIRCUIT_DISABLED) { + nv->valuetype = TYPE_NULL; + return (STAT_OK); + } + nv->value = getResistance(); + nv->valuetype = TYPE_FLOAT; + return (STAT_OK); + }; + // no setResistance + + stat_t getType(nvObj_t *nv) + { + nv->value = getType(); + nv->valuetype = TYPE_INT; + return (STAT_OK); + }; + stat_t setType(nvObj_t *nv) + { + if ((nv->value < AIN_TYPE_DISABLED) || (nv->value > AIN_TYPE_EXTERNAL)) { + return (STAT_INPUT_VALUE_RANGE_ERROR); + } + if (!setType((AnalogInputType_t)nv->value)) { + return STAT_PARAMETER_IS_READ_ONLY; + } + return (STAT_OK); + }; + + stat_t getCircuit(nvObj_t *nv) + { + nv->value = getCircuit(); + nv->valuetype = TYPE_INT; + return (STAT_OK); + }; + stat_t setCircuit(nvObj_t *nv) + { + if ((nv->value < AIN_CIRCUIT_DISABLED) || (nv->value > AIN_CIRCUIT_MAX)) { + return (STAT_INPUT_VALUE_RANGE_ERROR); + } + if (!setCircuit((AnalogCircuit_t)nv->value)) { + return STAT_PARAMETER_IS_READ_ONLY; + } + return (STAT_OK); + }; + + stat_t getParameter(nvObj_t *nv, const uint8_t p) + { + nv->value = getParameter(p); + nv->valuetype = TYPE_FLOAT; + return (STAT_OK); + }; + stat_t setParameter(nvObj_t *nv, const uint8_t p) + { + if (!setParameter(p, nv->value)) { + return STAT_PARAMETER_IS_READ_ONLY; + } + return (STAT_OK); + }; }; -struct gpioAnalogInput { // one struct per analog input - ioMode mode; +// statistical sampling utility class +template +struct ValueHistory { + + float variance_max = 2.0; + ValueHistory() {}; + ValueHistory(float v_max) : variance_max{v_max} {}; + + struct sample_t { + float value; + float value_sq; + void set(float v) { value = v; value_sq = v*v; } + }; + sample_t samples[sample_count]; + uint16_t next_sample = 0; + void _bump_index(uint16_t &v) { + ++v; + if (v == sample_count) { + v = 0; + } + }; + uint16_t sampled = 0; + + float rolling_sum = 0; + float rolling_sum_sq = 0; + float rolling_mean = 0; + void add_sample(float t) { + rolling_sum -= samples[next_sample].value; + rolling_sum_sq -= samples[next_sample].value_sq; + + samples[next_sample].set(t); + + rolling_sum += samples[next_sample].value; + rolling_sum_sq += samples[next_sample].value_sq; + + _bump_index(next_sample); + if (sampled < sample_count) { ++sampled; } + + rolling_mean = rolling_sum/(float)sampled; + }; + + float get_std_dev() { + // Important note: this is a POPULATION standard deviation, not a population standard deviation + float variance = (rolling_sum_sq/(float)sampled) - (rolling_mean*rolling_mean); + return sqrt(std::abs(variance)); + }; + + float value() { + // we'll shoot through the samples and ignore the outliers + uint16_t samples_kept = 0; + float temp = 0; + float std_dev = get_std_dev(); + + for (uint16_t i=0; i +struct gpioAnalogInputPin : gpioAnalogInput { +protected: // so we know if anyone tries to reach in + AnalogInputType_t type; + AnalogCircuit_t circuit; + float parameters[6]; + + uint8_t ext_pin_number; // the number used externally for this pin ("in" + ext_pin_number) + + const float variance_max = 1.1; + ValueHistory<20> history {variance_max}; + + float last_raw_value; + + ADCPin_t pin; // the actual pin object itself + +public: + // In constructor, simply forward all values to the pin + // To get a different behavior, override this object. + template + gpioAnalogInputPin(const AnalogInputType_t _type, const uint8_t _ext_pin_number, T&&... additional_values) : + gpioAnalogInput{}, + type{_type}, + ext_pin_number{_ext_pin_number}, + pin{Motate::kNormal, [&]{this->adc_has_new_value();}, std::forward(additional_values)...} + { + pin.setInterrupts(Motate::kPinInterruptOnChange|Motate::kInterruptPriorityLow); + pin.setVoltageRange(3.29, 0.0, 3.29, 1000000.0); + }; + + // functions for use by other parts of the code, and are overridden + + float getValue() override + { + if (type == AIN_TYPE_DISABLED) { + return 0; + } + return history.value(); + }; + float getResistance() override + { + // NOTE: AIN_CIRCUIT_EXTERNAL is NOT handled here! + // That needs to be handled in a separate override! + if (type == AIN_TYPE_DISABLED || circuit == AIN_CIRCUIT_DISABLED) { + return -1; + } + const float v = history.value(); + const float s = pin.getTopVoltage(); + switch (circuit) { + + case AIN_CIRCUIT_PULLUP: + { + float r1 = parameters[0]; // pull-up + + if (ADCPin_t::is_differential) { + return (v * 2.0 * r1)/(s - v); + } else { + return (v * r1)/(s - v); + } + break; + } + + case AIN_CIRCUIT_INV_OPAMP: + { + float r1 = parameters[0]; // pull-down from bias(+) side of op-amp + float r2 = parameters[1]; // pull-up from gain(-) side of op-amp + float r3 = parameters[2]; // pull-to-output from gain(-) side of op-amp + + return (r1 * r2 * (s - v))/(r2 * v + r3 * s); + break; + } + + case AIN_CIRCUIT_CC_INV_OPAMP: + { + // the pull-up resistance to the current source is measured (rt) + float r4 = parameters[3]; // pull-up resistance of the bias(+) side of op-amp + float r1 = parameters[0]; // pull-down from bias(+) side of op-amp + float r2 = parameters[1]; // pull-up from gain(-) side of op-amp + float r3 = parameters[2]; // pull-to-output from gain(-) side of op-amp + float c = parameters[4]; // constant current in volts (c1) + + // r_0 = (r_1 (r_2 (s - v) + r_3 s) - v r_2 r_4)/(c r_3 (r_1 + r_4)) + return (r1 * (r2 * (s - v) + r3 * s) - v * r2 * r4)/(c * r3 * (r1 + r4)); + break; + } + + // AIN_CIRCUIT_EXTERNAL is specifically missing! + + default: + return -1; + } + + }; + + AnalogInputType_t getType() override + { + return type; + }; + bool setType(const AnalogInputType_t t) override + { + // NOTE: AIN_TYPE_EXTERNAL is NOT handled here! + // That needs to be handled in a separate override! + if (t == AIN_TYPE_EXTERNAL) { + return false; + } + type = t; + return true; + }; + + AnalogCircuit_t getCircuit() override + { + return circuit; + }; + bool setCircuit(const AnalogCircuit_t c) override + { + // prevent setting circuit to AIN_CIRCUIT_EXTERNAL + if (c == AIN_CIRCUIT_EXTERNAL) { + return false; + } + circuit = c; + return true; + }; + + float getParameter(const uint8_t p) override + { + if (p < 0 || p >= 6) { + return 0; + } + return parameters[p]; + }; + bool setParameter(const uint8_t p, const float v) override + { + if (p < 0 || p >= 6) { + return false; + } + parameters[p] = v; + return true; + }; + + void startSampling() override { + pin.startSampling(); + }; + + // support function for pin value update interrupt handling + + void adc_has_new_value() { + last_raw_value = pin.getRaw(); + history.add_sample(pin.getVoltage()); + }; }; /* @@ -539,36 +966,167 @@ void gpio_set_homing_mode(const uint8_t input_num, const bool is_homing); void gpio_set_probing_mode(const uint8_t input_num, const bool is_probing); int8_t gpio_get_probing_input(void); -stat_t din_get_mo(nvObj_t *nv); -stat_t din_set_mo(nvObj_t *nv); -stat_t din_get_ac(nvObj_t *nv); +stat_t din_get_en(nvObj_t *nv); // enabled +stat_t din_set_en(nvObj_t *nv); +stat_t din_get_po(nvObj_t *nv); // input sense +stat_t din_set_po(nvObj_t *nv); +stat_t din_get_ac(nvObj_t *nv); // input action stat_t din_set_ac(nvObj_t *nv); -stat_t din_get_fn(nvObj_t *nv); +stat_t din_get_fn(nvObj_t *nv); // input function stat_t din_set_fn(nvObj_t *nv); - stat_t din_get_input(nvObj_t *nv); -stat_t dout_get_mo(nvObj_t *nv); // output sense -stat_t dout_set_mo(nvObj_t *nv); // output sense -stat_t dout_get_output(nvObj_t *nv); +stat_t dout_get_en(nvObj_t *nv); // enabled +stat_t dout_set_en(nvObj_t *nv); +stat_t dout_get_po(nvObj_t *nv); // output sense +stat_t dout_set_po(nvObj_t *nv); +stat_t dout_get_output(nvObj_t *nv); // actual output value (float) stat_t dout_set_output(nvObj_t *nv); +stat_t ain_get_value(nvObj_t *nv); // get the voltage level +// no ain_set_value +stat_t ain_get_resistance(nvObj_t *nv); // get the resistance in ohms +// no ain_set_resistance +stat_t ain_get_type(nvObj_t *nv); // get the ADC type (or disabled) +stat_t ain_set_type(nvObj_t *nv); // set the type (used to disable/enable) +stat_t ain_get_circuit(nvObj_t *nv); // get the circuit type +stat_t ain_set_circuit(nvObj_t *nv); // set the circuit type +stat_t ain_get_parameter(nvObj_t *nv, const uint8_t p); // get the value of parameter p +stat_t ain_set_parameter(nvObj_t *nv, const uint8_t p); // set the value of parameter p +stat_t ain_get_p1(nvObj_t *nv); +stat_t ain_set_p1(nvObj_t *nv); +stat_t ain_get_p2(nvObj_t *nv); +stat_t ain_set_p2(nvObj_t *nv); +stat_t ain_get_p3(nvObj_t *nv); +stat_t ain_set_p3(nvObj_t *nv); +stat_t ain_get_p4(nvObj_t *nv); +stat_t ain_set_p4(nvObj_t *nv); +stat_t ain_get_p5(nvObj_t *nv); +stat_t ain_set_p5(nvObj_t *nv); + #ifdef __TEXT_MODE - void din_print_mo(nvObj_t *nv); + void din_print_en(nvObj_t *nv); + void din_print_po(nvObj_t *nv); void din_print_ac(nvObj_t *nv); void din_print_fn(nvObj_t *nv); void din_print_in(nvObj_t *nv); - void dout_print_mo(nvObj_t *nv); + + void dout_print_en(nvObj_t *nv); + void dout_print_po(nvObj_t *nv); void dout_print_out(nvObj_t *nv); + + void ain_print_value(nvObj_t *nv); + void ain_print_resistance(nvObj_t *nv); + void ain_print_type(nvObj_t *nv); + void ain_print_circuit(nvObj_t *nv); + void ain_print_p(nvObj_t *nv); #else - #define din_print_mo tx_print_stub + #define din_print_en tx_print_stub + #define din_print_po tx_print_stub #define din_print_ac tx_print_stub #define din_print_fn tx_print_stub #define din_print_in tx_print_stub - #define dout_print_mo tx_print_stub + + #define dout_print_en tx_print_stub + #define dout_print_po tx_print_stub #define dout_print_out tx_print_stub + + #define ain_print_value tx_print_stub + #define ain_print_resistance tx_print_stub + #define ain_print_type tx_print_stub + #define ain_print_circuit tx_print_stub + #define ain_print_p tx_print_stub #endif // __TEXT_MODE #include "board_gpio.h" +#ifndef AI1_TYPE +#define AI1_TYPE AIN_TYPE_DISABLED +#endif +#ifndef AI1_CIRCUIT +#define AI1_CIRCUIT AIN_CIRCUIT_DISABLED +#endif +#ifndef AI1_P1 +#define AI1_P1 0.0 +#endif +#ifndef AI1_P2 +#define AI1_P2 0.0 +#endif +#ifndef AI1_P3 +#define AI1_P3 0.0 +#endif +#ifndef AI1_P4 +#define AI1_P4 0.0 +#endif +#ifndef AI1_P5 +#define AI1_P5 0.0 +#endif + + +#ifndef AI2_TYPE +#define AI2_TYPE AIN_TYPE_DISABLED +#endif +#ifndef AI2_CIRCUIT +#define AI2_CIRCUIT AIN_CIRCUIT_DISABLED +#endif +#ifndef AI2_P1 +#define AI2_P1 0.0 +#endif +#ifndef AI2_P2 +#define AI2_P2 0.0 +#endif +#ifndef AI2_P3 +#define AI2_P3 0.0 +#endif +#ifndef AI2_P4 +#define AI2_P4 0.0 +#endif +#ifndef AI2_P5 +#define AI2_P5 0.0 +#endif + +#ifndef AI3_TYPE +#define AI3_TYPE AIN_TYPE_DISABLED +#endif +#ifndef AI3_CIRCUIT +#define AI3_CIRCUIT AIN_CIRCUIT_DISABLED +#endif +#ifndef AI3_P1 +#define AI3_P1 0.0 +#endif +#ifndef AI3_P2 +#define AI3_P2 0.0 +#endif +#ifndef AI3_P3 +#define AI3_P3 0.0 +#endif +#ifndef AI3_P4 +#define AI3_P4 0.0 +#endif +#ifndef AI3_P5 +#define AI3_P5 0.0 +#endif + +#ifndef AI4_TYPE +#define AI4_TYPE AIN_TYPE_DISABLED +#endif +#ifndef AI4_CIRCUIT +#define AI4_CIRCUIT AIN_CIRCUIT_DISABLED +#endif +#ifndef AI4_P1 +#define AI4_P1 0.0 +#endif +#ifndef AI4_P2 +#define AI4_P2 0.0 +#endif +#ifndef AI4_P3 +#define AI4_P3 0.0 +#endif +#ifndef AI4_P4 +#define AI4_P4 0.0 +#endif +#ifndef AI4_P5 +#define AI4_P5 0.0 +#endif + #endif // End of include guard: GPIO_H_ONCE diff --git a/g2core/pwm.cpp b/g2core/pwm.cpp index ecc5212b4..fe91d3f20 100755 --- a/g2core/pwm.cpp +++ b/g2core/pwm.cpp @@ -28,6 +28,7 @@ #include "g2core.h" // #1 #include "config.h" // #2 #include "hardware.h" +#include "gpio.h" #include "spindle.h" #include "text_parser.h" #include "pwm.h" @@ -40,8 +41,19 @@ pwmSingleton_t pwm; // Setup motate PWM pins -Motate::PWMOutputPin spindle_pwm_pin {Motate::kNormal, P1_PWM_FREQUENCY}; -Motate::PWMOutputPin secondary_pwm_pin {Motate::kNormal, P1_PWM_FREQUENCY}; // assume the same frequency, to start with at least +//Motate::PWMOutputPin spindle_pwm_pin {Motate::kNormal, P1_PWM_FREQUENCY}; +//Motate::PWMOutputPin secondary_pwm_pin {Motate::kNormal, P1_PWM_FREQUENCY}; // assume the same frequency, to start with at least + +gpioDigitalOutput *spindle_pwm_output = nullptr; +gpioDigitalOutput *secondary_pwm_output = nullptr; + +#ifndef SPINDLE_OUTPUT_NUMBER +#define SPINDLE_OUTPUT_NUMBER 6 +#endif + +#ifndef SECONDARY_PWM_OUTPUT_NUMBER +#define SECONDARY_PWM_OUTPUT_NUMBER 0 +#endif /***** PWM code *****/ /* @@ -53,7 +65,17 @@ Motate::PWMOutputPin secondary_pwm_pin {Motate:: * - See system.h for timer and port assignments * - Don't do this: memset(&TIMER_PWM1, 0, sizeof(PWM_TIMER_t)); // zero out the timer registers */ -void pwm_init() {} +void pwm_init() { + if (SPINDLE_OUTPUT_NUMBER > 0) { + spindle_pwm_output = d_out[SPINDLE_OUTPUT_NUMBER-1]; + spindle_pwm_output->setFrequency(P1_PWM_FREQUENCY); + + } + if (SECONDARY_PWM_OUTPUT_NUMBER > 0) { + secondary_pwm_output = d_out[SECONDARY_PWM_OUTPUT_NUMBER-1]; + secondary_pwm_output->setFrequency(P1_PWM_FREQUENCY); + } +} /* * pwm_set_freq() - set PWM channel frequency @@ -72,9 +94,13 @@ stat_t pwm_set_freq(uint8_t chan, float freq) //if (freq > PWM_MAX_FREQ) { return (STAT_INPUT_EXCEEDS_MAX_VALUE);} if (chan == PWM_1) { - spindle_pwm_pin.setFrequency(freq); + if (spindle_pwm_output != nullptr) { + spindle_pwm_output->setFrequency(freq); + } } else if (chan == PWM_2) { - secondary_pwm_pin.setFrequency(freq); + if (secondary_pwm_output != nullptr) { + secondary_pwm_output->setFrequency(freq); + } } return (STAT_OK); @@ -99,15 +125,13 @@ stat_t pwm_set_duty(uint8_t chan, float duty) if (duty > 1.0) { return (STAT_INPUT_EXCEEDS_MAX_VALUE);} if (chan == PWM_1) { -// if (spindle_pwm_pin.isNull()) { -// cm_alarm(STAT_ALARM, "attempt to turn on a non-existant spindle"); -// } - spindle_pwm_pin = duty; + if (spindle_pwm_output != nullptr) { + spindle_pwm_output->setValue(duty); + } } else if (chan == PWM_2) { -// if (secondary_pwm_pin.isNull()) { -// cm_alarm(STAT_ALARM, "attempt to turn on a non-existant spindle"); -// } - secondary_pwm_pin = duty; + if (secondary_pwm_output != nullptr) { + secondary_pwm_output->setValue(duty); + } } return (STAT_OK); diff --git a/g2core/settings/settings_default.h b/g2core/settings/settings_default.h index 24aa3b208..000539cd1 100644 --- a/g2core/settings/settings_default.h +++ b/g2core/settings/settings_default.h @@ -817,6 +817,12 @@ #ifndef A_ZERO_BACKOFF #define A_ZERO_BACKOFF 2.0 #endif +#ifndef A_SPRING_OFFSET_FACTOR +#define A_SPRING_OFFSET_FACTOR 0 +#endif +#ifndef A_SPRING_OFFSET_MAX +#define A_SPRING_OFFSET_MAX 0 +#endif // B AXIS #ifndef B_AXIS_MODE @@ -934,8 +940,11 @@ */ // Xmin on v9 board -#ifndef DI1_MODE -#define DI1_MODE IO_ACTIVE_LOW // Normally open +#ifndef DI1_ENABLED +#define DI1_ENABLED IO_ENABLED +#endif +#ifndef DI1_POLARITY +#define DI1_POLARITY IO_ACTIVE_LOW // Normally open #endif #ifndef DI1_ACTION #define DI1_ACTION INPUT_ACTION_NONE @@ -945,8 +954,11 @@ #endif // Xmax -#ifndef DI2_MODE -#define DI2_MODE IO_ACTIVE_LOW // Normally open +#ifndef DI2_ENABLED +#define DI2_ENABLED IO_ENABLED +#endif +#ifndef DI2_POLARITY +#define DI2_POLARITY IO_ACTIVE_LOW // Normally open #endif #ifndef DI2_ACTION #define DI2_ACTION INPUT_ACTION_NONE @@ -956,8 +968,11 @@ #endif // Ymin -#ifndef DI3_MODE -#define DI3_MODE IO_ACTIVE_LOW // Normally open +#ifndef DI3_ENABLED +#define DI3_ENABLED IO_ENABLED +#endif +#ifndef DI3_POLARITY +#define DI3_POLARITY IO_ACTIVE_LOW // Normally open #endif #ifndef DI3_ACTION #define DI3_ACTION INPUT_ACTION_NONE @@ -967,8 +982,11 @@ #endif // Ymax -#ifndef DI4_MODE -#define DI4_MODE IO_ACTIVE_LOW // Normally open +#ifndef DI4_ENABLED +#define DI4_ENABLED IO_ENABLED +#endif +#ifndef DI4_POLARITY +#define DI4_POLARITY IO_ACTIVE_LOW // Normally open #endif #ifndef DI4_ACTION #define DI4_ACTION INPUT_ACTION_NONE @@ -978,8 +996,11 @@ #endif // Zmin -#ifndef DI5_MODE -#define DI5_MODE IO_ACTIVE_LOW // Normally open +#ifndef DI5_ENABLED +#define DI5_ENABLED IO_ENABLED +#endif +#ifndef DI5_POLARITY +#define DI5_POLARITY IO_ACTIVE_LOW // Normally open #endif #ifndef DI5_ACTION #define DI5_ACTION INPUT_ACTION_NONE @@ -989,8 +1010,11 @@ #endif // Zmax -#ifndef DI6_MODE -#define DI6_MODE IO_ACTIVE_LOW // Normally open +#ifndef DI6_ENABLED +#define DI6_ENABLED IO_ENABLED +#endif +#ifndef DI6_POLARITY +#define DI6_POLARITY IO_ACTIVE_LOW // Normally open #endif #ifndef DI6_ACTION #define DI6_ACTION INPUT_ACTION_NONE @@ -1000,8 +1024,11 @@ #endif // Amin -#ifndef DI7_MODE -#define DI7_MODE IO_ACTIVE_LOW // Normally open +#ifndef DI7_ENABLED +#define DI7_ENABLED IO_ENABLED +#endif +#ifndef DI7_POLARITY +#define DI7_POLARITY IO_ACTIVE_LOW // Normally open #endif #ifndef DI7_ACTION #define DI7_ACTION INPUT_ACTION_NONE @@ -1011,8 +1038,11 @@ #endif // Amax -#ifndef DI8_MODE -#define DI8_MODE IO_ACTIVE_LOW // Normally open +#ifndef DI8_ENABLED +#define DI8_ENABLED IO_ENABLED +#endif +#ifndef DI8_POLARITY +#define DI8_POLARITY IO_ACTIVE_LOW // Normally open #endif #ifndef DI8_ACTION #define DI8_ACTION INPUT_ACTION_NONE @@ -1022,8 +1052,11 @@ #endif // Safety line -#ifndef DI9_MODE -#define DI9_MODE IO_ACTIVE_HIGH // Normally closed +#ifndef DI9_ENABLED +#define DI9_ENABLED IO_ENABLED +#endif +#ifndef DI9_POLARITY +#define DI9_POLARITY IO_ACTIVE_HIGH // Normally closed #endif #ifndef DI9_ACTION #define DI9_ACTION INPUT_ACTION_NONE @@ -1032,8 +1065,11 @@ #define DI9_FUNCTION INPUT_FUNCTION_NONE #endif -#ifndef DI10_MODE -#define DI10_MODE IO_ACTIVE_LOW // Normally open +#ifndef DI10_ENABLED +#define DI10_ENABLED IO_ENABLED +#endif +#ifndef DI10_POLARITY +#define DI10_POLARITY IO_ACTIVE_LOW // Normally open #endif #ifndef DI10_ACTION #define DI10_ACTION INPUT_ACTION_NONE @@ -1042,8 +1078,11 @@ #define DI10_FUNCTION INPUT_FUNCTION_NONE #endif -#ifndef DI11_MODE -#define DI11_MODE IO_ACTIVE_LOW // Normally open +#ifndef DI11_ENABLED +#define DI11_ENABLED IO_ENABLED +#endif +#ifndef DI11_POLARITY +#define DI11_POLARITY IO_ACTIVE_LOW // Normally open #endif #ifndef DI11_ACTION #define DI11_ACTION INPUT_ACTION_NONE @@ -1052,8 +1091,11 @@ #define DI11_FUNCTION INPUT_FUNCTION_NONE #endif -#ifndef DI12_MODE -#define DI12_MODE IO_ACTIVE_LOW // Normally open +#ifndef DI12_ENABLED +#define DI12_ENABLED IO_ENABLED +#endif +#ifndef DI12_POLARITY +#define DI12_POLARITY IO_ACTIVE_LOW // Normally open #endif #ifndef DI12_ACTION #define DI12_ACTION INPUT_ACTION_NONE @@ -1065,60 +1107,189 @@ // DIGITAL OUTPUTS - Currently these are hard-wired to extruders //Extruder1_PWM -#ifndef DO1_MODE -#define DO1_MODE IO_ACTIVE_HIGH +#ifndef DO1_ENABLED +#define DO1_ENABLED IO_ENABLED +#endif +#ifndef DO1_POLARITY +#define DO1_POLARITY IO_ACTIVE_HIGH #endif //Extruder2_PWM -#ifndef DO2_MODE -#define DO2_MODE IO_ACTIVE_HIGH +#ifndef DO2_ENABLED +#define DO2_ENABLED IO_ENABLED +#endif +#ifndef DO2_POLARITY +#define DO2_POLARITY IO_ACTIVE_HIGH #endif //Fan1A_PWM -#ifndef DO3_MODE -#define DO3_MODE IO_ACTIVE_HIGH +#ifndef DO3_ENABLED +#define DO3_ENABLED IO_ENABLED +#endif +#ifndef DO3_POLARITY +#define DO3_POLARITY IO_ACTIVE_HIGH #endif //Fan1B_PWM -#ifndef DO4_MODE -#define DO4_MODE IO_ACTIVE_HIGH +#ifndef DO4_ENABLED +#define DO4_ENABLED IO_ENABLED +#endif +#ifndef DO4_POLARITY +#define DO4_POLARITY IO_ACTIVE_HIGH #endif -#ifndef DO5_MODE -#define DO5_MODE IO_ACTIVE_HIGH +#ifndef DO5_ENABLED +#define DO5_ENABLED IO_ENABLED +#endif +#ifndef DO5_POLARITY +#define DO5_POLARITY IO_ACTIVE_HIGH +#endif +#ifndef DO6_ENABLED +#define DO6_ENABLED IO_ENABLED +#endif +#ifndef DO6_POLARITY +#define DO6_POLARITY IO_ACTIVE_HIGH #endif -#ifndef DO6_MODE -#define DO6_MODE IO_ACTIVE_HIGH +#ifndef DO7_ENABLED +#define DO7_ENABLED IO_ENABLED #endif -#ifndef DO7_MODE -#define DO7_MODE IO_ACTIVE_HIGH +#ifndef DO7_POLARITY +#define DO7_POLARITY IO_ACTIVE_HIGH #endif -#ifndef DO8_MODE -#define DO8_MODE IO_ACTIVE_HIGH +#ifndef DO8_ENABLED +#define DO8_ENABLED IO_ENABLED +#endif +#ifndef DO8_POLARITY +#define DO8_POLARITY IO_ACTIVE_HIGH #endif //SAFEin (Output) signal -#ifndef DO9_MODE -#define DO9_MODE IO_ACTIVE_HIGH +#ifndef DO9_ENABLED +#define DO9_ENABLED IO_ENABLED +#endif +#ifndef DO9_POLARITY +#define DO9_POLARITY IO_ACTIVE_HIGH #endif -#ifndef DO10_MODE -#define DO10_MODE IO_ACTIVE_HIGH +#ifndef DO10_ENABLED +#define DO10_ENABLED IO_ENABLED +#endif +#ifndef DO10_POLARITY +#define DO10_POLARITY IO_ACTIVE_HIGH #endif //Header Bed FET -#ifndef DO11_MODE -#define DO11_MODE IO_ACTIVE_HIGH +#ifndef DO11_ENABLED +#define DO11_ENABLED IO_ENABLED #endif - -//Indicator_LED -#ifndef DO12_MODE -#define DO12_MODE IO_ACTIVE_HIGH +#ifndef DO11_POLARITY +#define DO11_POLARITY IO_ACTIVE_HIGH #endif -#ifndef DO13_MODE -#define DO13_MODE IO_ACTIVE_HIGH -#endif +//Indicator_LED +#ifndef DO12_ENABLED +#define DO12_ENABLED IO_ENABLED +#endif +#ifndef DO12_POLARITY +#define DO12_POLARITY IO_ACTIVE_HIGH +#endif + +#ifndef DO13_ENABLED +#define DO13_ENABLED IO_ENABLED +#endif +#ifndef DO13_POLARITY +#define DO13_POLARITY IO_ACTIVE_HIGH +#endif + +// foind in gpio.h: +// #ifndef AI1_TYPE +// #define AI1_TYPE AIN_TYPE_DISABLED +// #endif +// #ifndef AI1_CIRCUIT +// #define AI1_CIRCUIT AIN_CIRCUIT_DISABLED +// #endif +// #ifndef AI1_P1 +// #define AI1_P1 0.0 +// #endif +// #ifndef AI1_P2 +// #define AI1_P2 0.0 +// #endif +// #ifndef AI1_P3 +// #define AI1_P3 0.0 +// #endif +// #ifndef AI1_P4 +// #define AI1_P4 0.0 +// #endif +// #ifndef AI1_P5 +// #define AI1_P5 0.0 +// #endif +// +// +// #ifndef AI2_TYPE +// #define AI2_TYPE AIN_TYPE_DISABLED +// #endif +// #ifndef AI2_CIRCUIT +// #define AI2_CIRCUIT AIN_CIRCUIT_DISABLED +// #endif +// #ifndef AI2_P1 +// #define AI2_P1 0.0 +// #endif +// #ifndef AI2_P2 +// #define AI2_P2 0.0 +// #endif +// #ifndef AI2_P3 +// #define AI2_P3 0.0 +// #endif +// #ifndef AI2_P4 +// #define AI2_P4 0.0 +// #endif +// #ifndef AI2_P5 +// #define AI2_P5 0.0 +// #endif +// +// #ifndef AI3_TYPE +// #define AI3_TYPE AIN_TYPE_DISABLED +// #endif +// #ifndef AI3_CIRCUIT +// #define AI3_CIRCUIT AIN_CIRCUIT_DISABLED +// #endif +// #ifndef AI3_P1 +// #define AI3_P1 0.0 +// #endif +// #ifndef AI3_P2 +// #define AI3_P2 0.0 +// #endif +// #ifndef AI3_P3 +// #define AI3_P3 0.0 +// #endif +// #ifndef AI3_P4 +// #define AI3_P4 0.0 +// #endif +// #ifndef AI3_P5 +// #define AI3_P5 0.0 +// #endif +// +// #ifndef AI4_TYPE +// #define AI4_TYPE AIN_TYPE_DISABLED +// #endif +// #ifndef AI4_CIRCUIT +// #define AI4_CIRCUIT AIN_CIRCUIT_DISABLED +// #endif +// #ifndef AI4_P1 +// #define AI4_P1 0.0 +// #endif +// #ifndef AI4_P2 +// #define AI4_P2 0.0 +// #endif +// #ifndef AI4_P3 +// #define AI4_P3 0.0 +// #endif +// #ifndef AI4_P4 +// #define AI4_P4 0.0 +// #endif +// #ifndef AI4_P5 +// #define AI4_P5 0.0 +// #endif // *** PWM Settings *** // diff --git a/g2core/spindle.cpp b/g2core/spindle.cpp index e61e1ee4d..a24891a9c 100644 --- a/g2core/spindle.cpp +++ b/g2core/spindle.cpp @@ -30,6 +30,7 @@ #include "canonical_machine.h" // #3 #include "text_parser.h" // #4 +#include "gpio.h" #include "spindle.h" #include "planner.h" #include "hardware.h" @@ -40,6 +41,18 @@ cmSpindleton_t spindle; + +gpioDigitalOutput *spindle_enable_output = nullptr; +gpioDigitalOutput *spindle_direction_output = nullptr; + +#ifndef SPINDLE_ENABLE_OUTPUT_NUMBER +#define SPINDLE_ENABLE_OUTPUT_NUMBER 4 +#endif + +#ifndef SPINDLE_DIRECTION_OUTPUT_NUMBER +#define SPINDLE_DIRECTION_OUTPUT_NUMBER 5 +#endif + /**** Static functions ****/ static void _exec_spindle_speed(float *value, bool *flag); @@ -52,6 +65,17 @@ static float _get_spindle_pwm (cmSpindleEnable enable, cmSpindleDir direction); */ void spindle_init() { + if (SPINDLE_ENABLE_OUTPUT_NUMBER > 0) { + spindle_enable_output = d_out[SPINDLE_ENABLE_OUTPUT_NUMBER-1]; + spindle_enable_output->setEnabled(IO_ENABLED); + spindle_enable_output->setPolarity((ioPolarity)SPINDLE_ENABLE_POLARITY); + } + if (SPINDLE_DIRECTION_OUTPUT_NUMBER > 0) { + spindle_direction_output = d_out[SPINDLE_DIRECTION_OUTPUT_NUMBER-1]; + spindle_direction_output->setEnabled(IO_ENABLED); + spindle_direction_output->setPolarity((ioPolarity)SPINDLE_DIR_POLARITY); + } + if( pwm.c[PWM_1].frequency < 0 ) { pwm.c[PWM_1].frequency = 0; } @@ -153,10 +177,10 @@ stat_t cm_spindle_control(uint8_t control) // requires SPINDLE_CONTROL_xxx styl return(STAT_OK); } - #define _set_spindle_enable_bit_hi() spindle_enable_pin.set() - #define _set_spindle_enable_bit_lo() spindle_enable_pin.clear() - #define _set_spindle_direction_bit_hi() spindle_dir_pin.set() - #define _set_spindle_direction_bit_lo() spindle_dir_pin.clear() +// #define _set_spindle_enable_bit_hi() spindle_enable_pin.set() +// #define _set_spindle_enable_bit_lo() spindle_enable_pin.clear() +// #define _set_spindle_direction_bit_hi() spindle_dir_pin.set() +// #define _set_spindle_direction_bit_lo() spindle_dir_pin.clear() static void _exec_spindle_control(float *value, bool *flag) { @@ -164,10 +188,13 @@ static void _exec_spindle_control(float *value, bool *flag) if (flag[1]) { spindle.direction = (cmSpindleDir)value[1]; // record spindle direction in the struct - if (spindle.direction ^ spindle.dir_polarity) { - _set_spindle_direction_bit_hi(); - } else { - _set_spindle_direction_bit_lo(); +// if (spindle.direction ^ spindle.dir_polarity) { +// _set_spindle_direction_bit_hi(); +// } else { +// _set_spindle_direction_bit_lo(); +// } + if (spindle_direction_output != nullptr) { + spindle_direction_output->setValue(spindle.direction); } } @@ -175,10 +202,13 @@ static void _exec_spindle_control(float *value, bool *flag) { // set on/off. Mask out PAUSE and consider it OFF spindle.enable = (cmSpindleEnable)value[0]; // record spindle enable in the struct - if ((spindle.enable & 0x01) ^ spindle.enable_polarity) { - _set_spindle_enable_bit_lo(); - } else { - _set_spindle_enable_bit_hi(); +// if ((spindle.enable & 0x01) ^ spindle.enable_polarity) { +// _set_spindle_enable_bit_lo(); +// } else { +// _set_spindle_enable_bit_hi(); +// } + if (spindle_enable_output != nullptr) { + spindle_enable_output->setValue(spindle.enable); } } diff --git a/g2core/temperature.cpp b/g2core/temperature.cpp index 2c323b994..d668baf24 100755 --- a/g2core/temperature.cpp +++ b/g2core/temperature.cpp @@ -313,7 +313,7 @@ struct Thermistor { template Thermistor(const float temp_low, const float temp_med, const float temp_high, const float res_low, const float res_med, const float res_high, const ADCCircuit *_circuit, Ts&&... additional_values) : circuit{_circuit}, - adc_pin{kNormal, [&]{this->adc_has_new_value();}, additional_values...} + adc_pin{kNormal, [&]{this->adc_has_new_value();}, std::forward(additional_values)...} { setup(temp_low, temp_med, temp_high, res_low, res_med, res_high); adc_pin.setInterrupts(kPinInterruptOnChange|kInterruptPriorityLow); From 193493b1dcbfd980da6d71c5e4eb0364c076c4e5 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Mon, 19 Feb 2018 10:18:39 -0600 Subject: [PATCH 168/193] Finish support for gQuintic rev D --- g2core/board/gquintic/board_stepper.cpp | 8 +++++--- g2core/board/gquintic/board_stepper.h | 8 +++++--- g2core/board/gquintic/gquintic-c-pinout.h | 2 ++ g2core/board/gquintic/gquintic-d-pinout.h | 18 ++++++++++-------- 4 files changed, 22 insertions(+), 14 deletions(-) diff --git a/g2core/board/gquintic/board_stepper.cpp b/g2core/board/gquintic/board_stepper.cpp index 2cd1acde4..8d956b05c 100755 --- a/g2core/board/gquintic/board_stepper.cpp +++ b/g2core/board/gquintic/board_stepper.cpp @@ -29,7 +29,7 @@ #include "board_stepper.h" // These are identical to board_stepper.h, except for the word "extern" and the initialization -#if defined(USING_A_MAX31865) && USING_A_MAX31865 == 1 +#if QUINTIC_REVISION == 'C' HOT_DATA Trinamic2130 motor_5; Stepper* const Motors[MOTORS] = {&motor_1, &motor_2, &motor_3, &motor_4, &motor_5}; -#else +#endif // 'C' + +#if QUINTIC_REVISION == 'D' HOT_DATA Trinamic2130 motor_6; Stepper* const Motors[MOTORS] = {&motor_1, &motor_2, &motor_3, &motor_4, &motor_5, &motor_6}; -#endif +#endif // 'D' void board_stepper_init() { for (uint8_t motor = 0; motor < MOTORS; motor++) { Motors[motor]->init(); } diff --git a/g2core/board/gquintic/board_stepper.h b/g2core/board/gquintic/board_stepper.h index 52db83468..0204801db 100755 --- a/g2core/board/gquintic/board_stepper.h +++ b/g2core/board/gquintic/board_stepper.h @@ -33,7 +33,7 @@ #include "step_dir_hobbyservo.h" // These are identical to board_stepper.h, except for the word "extern" and the initialization -#if defined(USING_A_MAX31865) && USING_A_MAX31865 == 1 +#if QUINTIC_REVISION == 'C' extern Trinamic2130 motor_4; extern StepDirHobbyServo motor_5; -#else +#endif // 'C' + +#if QUINTIC_REVISION == 'D' extern Trinamic2130 motor_5; extern StepDirHobbyServo motor_6; -#endif +#endif // 'D' extern Stepper* const Motors[MOTORS]; diff --git a/g2core/board/gquintic/gquintic-c-pinout.h b/g2core/board/gquintic/gquintic-c-pinout.h index 08ccf5509..ae7b7da3d 100755 --- a/g2core/board/gquintic/gquintic-c-pinout.h +++ b/g2core/board/gquintic/gquintic-c-pinout.h @@ -111,6 +111,8 @@ #define OUTPUT12_PWM 0 // Unused #define OUTPUT13_PWM 0 // Unused +#define QUINTIC_REVISION 'C' + namespace Motate { // Unused: diff --git a/g2core/board/gquintic/gquintic-d-pinout.h b/g2core/board/gquintic/gquintic-d-pinout.h index faf2acead..f24d81b20 100755 --- a/g2core/board/gquintic/gquintic-d-pinout.h +++ b/g2core/board/gquintic/gquintic-d-pinout.h @@ -111,6 +111,8 @@ #define OUTPUT12_PWM 0 // Unused #define OUTPUT13_PWM 0 // Unused +#define QUINTIC_REVISION 'D' + namespace Motate { // Unused: @@ -155,7 +157,7 @@ _MAKE_MOTATE_PIN(kInput1_PinNumber, 'A', 30); // _MAKE_MOTATE_PIN(kInput4_PinNumber, 'A', 31); // _MAKE_MOTATE_PIN(kSerial_CTSPinNumber, 'B', 0); // -_MAKE_MOTATE_PIN(kUnassigned9, 'B', 1); // AFEC1,0 +_MAKE_MOTATE_PIN(kUnassigned4, 'B', 1); // AFEC1,0 _MAKE_MOTATE_PIN(kSocket1_SPISlaveSelectPinNumber, 'B', 2); // _MAKE_MOTATE_PIN(kOutputSAFE_PinNumber, 'B', 3); // //_MAKE_MOTATE_PIN( , 'B', 4); // TDI @@ -168,7 +170,7 @@ _MAKE_MOTATE_PIN(kOutputSAFE_PinNumber, 'B', 3); // //_MAKE_MOTATE_PIN( , 'B', 11); // USB_D+ //_MAKE_MOTATE_PIN( , 'B', 12); // ERASE _MAKE_MOTATE_PIN(kLED_USBRXPinNumber, 'B', 13); // LED_1 (Heartbeat) - PWM2 -_MAKE_MOTATE_PIN(kUnassigned6, 'B', 14); // NOT CONNECTED +_MAKE_MOTATE_PIN(kUnassigned5, 'B', 14); // NOT CONNECTED _MAKE_MOTATE_PIN(kUSBVBUS_PinNumber, 'D', 0); // USB_VBUS @@ -181,12 +183,12 @@ _MAKE_MOTATE_PIN(kInput5_PinNumber, 'D', 6); // _MAKE_MOTATE_PIN(kInput3_PinNumber, 'D', 7); // _MAKE_MOTATE_PIN(kInput2_PinNumber, 'D', 8); // ] _MAKE_MOTATE_PIN(kTMC2130_DIAG0_pinNumber, 'D', 9); // DIAG0 -_MAKE_MOTATE_PIN(kUnassigned4, 'D', 10); // +_MAKE_MOTATE_PIN(kUnassigned6, 'D', 10); // _MAKE_MOTATE_PIN(kSocket5_StepPinNumber, 'D', 11); // _MAKE_MOTATE_PIN(kSocket3_SPISlaveSelectPinNumber, 'D', 12); // _MAKE_MOTATE_PIN(kSocket5_DirPinNumber, 'D', 13); // _MAKE_MOTATE_PIN(kSocket5_EnablePinNumber, 'D', 14); // -_MAKE_MOTATE_PIN(kUnassigned5, 'D', 15); // +_MAKE_MOTATE_PIN(kUnassigned7, 'D', 15); // _MAKE_MOTATE_PIN(kSocket4_StepPinNumber, 'D', 16); // _MAKE_MOTATE_PIN(kSocket4_DirPinNumber, 'D', 17); // _MAKE_MOTATE_PIN(kSocket3_StepPinNumber, 'D', 18); // @@ -194,15 +196,15 @@ _MAKE_MOTATE_PIN(kSocket1_DirPinNumber, 'D', 19); // _MAKE_MOTATE_PIN(kSPI0_MISOPinNumber, 'D', 20); // _MAKE_MOTATE_PIN(kSPI0_MOSIPinNumber, 'D', 21); // _MAKE_MOTATE_PIN(kSPI0_SCKPinNumber, 'D', 22); // -_MAKE_MOTATE_PIN(kUnassigned7, 'D', 23); // NO PHYSICAL PIN +_MAKE_MOTATE_PIN(kUnassigned8, 'D', 23); // NO PHYSICAL PIN _MAKE_MOTATE_PIN(kSocket2_StepPinNumber, 'D', 24); // _MAKE_MOTATE_PIN(kSocket2_SPISlaveSelectPinNumber, 'D', 25); // _MAKE_MOTATE_PIN(kOutput9_PinNumber, 'D', 26); // PWM 2 _MAKE_MOTATE_PIN(kSocket4_SPISlaveSelectPinNumber, 'D', 27); // _MAKE_MOTATE_PIN(kSocket4_EnablePinNumber, 'D', 28); // -_MAKE_MOTATE_PIN(kUnassigned8, 'D', 29); // NO PHYSICAL PIN -_MAKE_MOTATE_PIN(kADC3_Neg_PinNumber, 'D', 30); // AFEC0,0 - was INTERRUPT_OUT -_MAKE_MOTATE_PIN(kUnassigned10, 'D', 31); // +_MAKE_MOTATE_PIN(kUnassigned9, 'D', 29); // NO PHYSICAL PIN +_MAKE_MOTATE_PIN(kUnassigned10, 'D', 30); // AFEC0,0 - was INTERRUPT_OUT +_MAKE_MOTATE_PIN(kUnassigned11, 'D', 31); // } // namespace Motate From c827075eac6f90d21977981d5034d51bfb7b419a Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Mon, 19 Feb 2018 10:29:26 -0600 Subject: [PATCH 169/193] Adding support for SMW3D R7 and Pendulum v2 --- g2core/boards.mk | 20 ++ g2core/g2core.xcodeproj/project.pbxproj | 40 +++ .../xcschemes/G2 gQuadratic SMW3d r7.xcscheme | 82 +++++ g2core/settings/settings_smw3d_r7.h | 274 +++++++++++++++++ .../settings/settings_synthetos_pendulum_v2.h | 282 ++++++++++++++++++ 5 files changed, 698 insertions(+) create mode 100644 g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 gQuadratic SMW3d r7.xcscheme create mode 100644 g2core/settings/settings_smw3d_r7.h create mode 100644 g2core/settings/settings_synthetos_pendulum_v2.h diff --git a/g2core/boards.mk b/g2core/boards.mk index bc75ad948..cb48f6845 100644 --- a/g2core/boards.mk +++ b/g2core/boards.mk @@ -192,4 +192,24 @@ ifeq ("$(CONFIG)","Quintic-Ender") SETTINGS_FILE="settings_ender.h" endif +########## +# SMW3D r7 config: +# https://www.smw3d.com/r7-cnc-diy-kit/ + +ifeq ("$(CONFIG)","r7") + ifeq ("$(BOARD)","NONE") + BOARD=gquintic-d + endif + SETTINGS_FILE="settings_smw3d_r7.h" +endif + +########## +# Synthetos Pendulum v2 config: + +ifeq ("$(CONFIG)","pendulum") + ifeq ("$(BOARD)","NONE") + BOARD=gquintic-d + endif + SETTINGS_FILE="settings_synthetos_pendulum_v2.h" +endif include $(wildcard ./board/$(STAR).mk) diff --git a/g2core/g2core.xcodeproj/project.pbxproj b/g2core/g2core.xcodeproj/project.pbxproj index 289068333..acf15e30c 100644 --- a/g2core/g2core.xcodeproj/project.pbxproj +++ b/g2core/g2core.xcodeproj/project.pbxproj @@ -344,6 +344,20 @@ passBuildSettingsInEnvironment = 1; productName = g3_due; }; + D4C9C2FD20164DE200487D7F /* G2 gQuadratic SMW3D r7 */ = { + isa = PBXLegacyTarget; + buildArgumentsString = "$(ACTION) VERBOSE=1 COLOR=0 CONFIG=r7 DEBUG=0"; + buildConfigurationList = D4C9C2FE20164DE200487D7F /* Build configuration list for PBXLegacyTarget "G2 gQuadratic SMW3D r7" */; + buildPhases = ( + ); + buildToolPath = /usr/bin/make; + buildWorkingDirectory = .; + dependencies = ( + ); + name = "G2 gQuadratic SMW3D r7"; + passBuildSettingsInEnvironment = 1; + productName = g3_due; + }; D4CBBAD01A0D51FE00150DE2 /* G2 G2V9k Ultimaker */ = { isa = PBXLegacyTarget; buildArgumentsString = "$(ACTION) VERBOSE=1 COLOR=0 CONFIG=UltimakerTests BOARD=g2v9k"; @@ -441,6 +455,7 @@ D4782AB61D9E39EC00B32136 /* G2 EggBot */, D492E5AE1E54C2B4005ED97D /* G2 gQuadratic AxiDraw v3 */, D43DFE011E8C84B400A2030D /* G2 gQuadratic Ultimaker2+ */, + D4C9C2FD20164DE200487D7F /* G2 gQuadratic SMW3D r7 */, ); }; /* End PBXProject section */ @@ -791,6 +806,22 @@ }; name = Release; }; + D4C9C2FF20164DE200487D7F /* Debug */ = { + isa = XCBuildConfiguration; + buildSettings = { + PATH = "$PATH:/usr/local/gcc-arm-none-eabi/bin"; + PRODUCT_NAME = "$(TARGET_NAME)"; + }; + name = Debug; + }; + D4C9C30020164DE200487D7F /* Release */ = { + isa = XCBuildConfiguration; + buildSettings = { + PATH = "$PATH:/usr/local/gcc-arm-none-eabi/bin"; + PRODUCT_NAME = "$(TARGET_NAME)"; + }; + name = Release; + }; D4CBBAD21A0D51FE00150DE2 /* Debug */ = { isa = XCBuildConfiguration; buildSettings = { @@ -950,6 +981,15 @@ defaultConfigurationIsVisible = 0; defaultConfigurationName = Release; }; + D4C9C2FE20164DE200487D7F /* Build configuration list for PBXLegacyTarget "G2 gQuadratic SMW3D r7" */ = { + isa = XCConfigurationList; + buildConfigurations = ( + D4C9C2FF20164DE200487D7F /* Debug */, + D4C9C30020164DE200487D7F /* Release */, + ); + defaultConfigurationIsVisible = 0; + defaultConfigurationName = Release; + }; D4CBBAD11A0D51FE00150DE2 /* Build configuration list for PBXLegacyTarget "G2 G2V9k Ultimaker" */ = { isa = XCConfigurationList; buildConfigurations = ( diff --git a/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 gQuadratic SMW3d r7.xcscheme b/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 gQuadratic SMW3d r7.xcscheme new file mode 100644 index 000000000..10dea5ad5 --- /dev/null +++ b/g2core/g2core.xcodeproj/xcshareddata/xcschemes/G2 gQuadratic SMW3d r7.xcscheme @@ -0,0 +1,82 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/g2core/settings/settings_smw3d_r7.h b/g2core/settings/settings_smw3d_r7.h new file mode 100644 index 000000000..6840275fa --- /dev/null +++ b/g2core/settings/settings_smw3d_r7.h @@ -0,0 +1,274 @@ +/* + * settings_smw3d_r7.h - SMW3d r7 machine with VFD + * This file is part of the g2core project + * + * Copyright (c) 2010 - 2016 Alden S. Hart, Jr. + * + * This file ("the software") is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License, version 2 as published by the + * Free Software Foundation. You should have received a copy of the GNU General Public + * License, version 2 along with the software. If not, see . + * + * As a special exception, you may use this file as part of a software library without + * restriction. Specifically, if other files instantiate templates or use macros or + * inline functions from this file, or you compile this file and link it with other + * files to produce an executable, this file does not by itself cause the resulting + * executable to be covered by the GNU General Public License. This exception does not + * however invalidate any other reasons why the executable file might be covered by the + * GNU General Public License. + * + * THE SOFTWARE IS DISTRIBUTED IN THE HOPE THAT IT WILL BE USEFUL, BUT WITHOUT ANY + * WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES + * OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT + * SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF + * OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + */ + +/***********************************************************************/ +/**** Shapeoko2 500mm profile ******************************************/ +/***********************************************************************/ + +// ***> NOTE: The init message must be a single line with no CRs or LFs +#define INIT_MESSAGE "Initializing configs to SMW3d r7" + +//**** GLOBAL / GENERAL SETTINGS ****************************************************** + +// Machine configuration settings + +#define JUNCTION_INTEGRATION_TIME 0.75 // cornering - between 0.10 and 2.00 (higher is faster) +#define CHORDAL_TOLERANCE 0.01 // chordal tolerance for arcs (in mm) + +#define SOFT_LIMIT_ENABLE 0 // 0=off, 1=on +#define HARD_LIMIT_ENABLE 0 // 0=off, 1=on +#define SAFETY_INTERLOCK_ENABLE 1 // 0=off, 1=on + +#define SPINDLE_ENABLE_POLARITY 1 // 0=active low, 1=active high +#define SPINDLE_DIR_POLARITY 0 // 0=clockwise is low, 1=clockwise is high +#define SPINDLE_PAUSE_ON_HOLD true +#define SPINDLE_DWELL_TIME 1.0 + +#define COOLANT_MIST_POLARITY 1 // 0=active low, 1=active high +#define COOLANT_FLOOD_POLARITY 1 // 0=active low, 1=active high +#define COOLANT_PAUSE_ON_HOLD false + +// Communications and reporting settings + +#define USB_SERIAL_PORTS_EXPOSED 1 // 1=single endpoint usb, 2=dual endpoint usb +#define COMM_MODE JSON_MODE // one of: TEXT_MODE, JSON_MODE +#define XIO_ENABLE_FLOW_CONTROL FLOW_CONTROL_RTS // FLOW_CONTROL_OFF, FLOW_CONTROL_RTS + +#define TEXT_VERBOSITY TV_VERBOSE // one of: TV_SILENT, TV_VERBOSE +#define JSON_VERBOSITY JV_MESSAGES // one of: JV_SILENT, JV_FOOTER, JV_CONFIGS, JV_MESSAGES, JV_LINENUM, JV_VERBOSE +#define QUEUE_REPORT_VERBOSITY QR_OFF // one of: QR_OFF, QR_SINGLE, QR_TRIPLE + +#define STATUS_REPORT_VERBOSITY SR_FILTERED // one of: SR_OFF, SR_FILTERED, SR_VERBOSE + +#define STATUS_REPORT_MIN_MS 100 // milliseconds - enforces a viable minimum +#define STATUS_REPORT_INTERVAL_MS 250 // milliseconds - set $SV=0 to disable + +//#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","feed","vel","unit","coor","dist","admo","frmo","momo","stat" +#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","feed","vel","momo","stat" + +// Alternate SRs that report in drawable units +//#define STATUS_REPORT_DEFAULTS "line","vel","mpox","mpoy","mpoz","mpoa","coor","ofsa","ofsx","ofsy","ofsz","dist","unit","stat","homz","homy","homx","momo" +//#define STATUS_REPORT_DEFAULTS "_ts1","_cs1","_es1","_xs1","_fe1","line","posx","posy","posz","vel","stat" + +// Gcode startup defaults +#define GCODE_DEFAULT_UNITS MILLIMETERS // MILLIMETERS or INCHES +#define GCODE_DEFAULT_PLANE CANON_PLANE_XY // CANON_PLANE_XY, CANON_PLANE_XZ, or CANON_PLANE_YZ +#define GCODE_DEFAULT_COORD_SYSTEM G54 // G54, G55, G56, G57, G58 or G59 +#define GCODE_DEFAULT_PATH_CONTROL PATH_CONTINUOUS +#define GCODE_DEFAULT_DISTANCE_MODE ABSOLUTE_DISTANCE_MODE + +// *** motor settings ************************************************************************************ + +#define MOTOR_POWER_MODE MOTOR_POWERED_IN_CYCLE // default motor power mode (see cmMotorPowerMode in stepper.h) +#define MOTOR_POWER_TIMEOUT 2.00 // motor power timeout in seconds + +#define M1_MOTOR_MAP AXIS_X // 1ma +#define M1_STEP_ANGLE 1.8 // 1sa +#define M1_TRAVEL_PER_REV 8.0934060625 // 1tr +#define M1_MICROSTEPS 64 // 1mi 1,2,4,8,16,32 +#define M1_POLARITY 1 // 1po 0=normal, 1=reversed +#define M1_POWER_MODE MOTOR_ALWAYS_POWERED // 1pm TRUE=low power idle enabled +#define M1_POWER_LEVEL 0.500 + +#define M2_MOTOR_MAP AXIS_Y +#define M2_STEP_ANGLE 1.8 +#define M2_TRAVEL_PER_REV 8.0934060625 +#define M2_MICROSTEPS 64 +#define M2_POLARITY 0 +#define M2_POWER_MODE MOTOR_ALWAYS_POWERED +#define M2_POWER_LEVEL 0.500 + +#define M3_MOTOR_MAP AXIS_Y +#define M3_STEP_ANGLE 1.8 +#define M3_TRAVEL_PER_REV 8.0934060625 +#define M3_MICROSTEPS 64 +#define M3_POLARITY 0 +#define M3_POWER_MODE MOTOR_ALWAYS_POWERED +#define M3_POWER_LEVEL 0.500 + +#define M4_MOTOR_MAP AXIS_Z +#define M4_STEP_ANGLE 1.8 +#define M4_TRAVEL_PER_REV 8.0934060625 +#define M4_MICROSTEPS 64 +#define M4_POLARITY 1 +#define M4_POWER_MODE MOTOR_ALWAYS_POWERED +#define M4_POWER_LEVEL 0.750 + +// *** axis settings ********************************************************************************** + +#define JERK_MAX 5000 + +#define X_AXIS_MODE AXIS_STANDARD // xam see canonical_machine.h cmAxisMode for valid values +#define X_VELOCITY_MAX 5000 // xvm G0 max velocity in mm/min +#define X_FEEDRATE_MAX X_VELOCITY_MAX // xfr G1 max feed rate in mm/min +#define X_TRAVEL_MIN 0 // xtn minimum travel for soft limits +#define X_TRAVEL_MAX 824 // xtm travel between switches or crashes +#define X_JERK_MAX 3500 // xjm jerk * 1,000,000 +#define X_JERK_HIGH_SPEED 20000 // xjh +#define X_HOMING_INPUT 1 // xhi input used for homing or 0 to disable +#define X_HOMING_DIRECTION 1 // xhd 0=search moves negative, 1= search moves positive +#define X_SEARCH_VELOCITY 2000 // xsv minus means move to minimum switch +#define X_LATCH_VELOCITY 100 // xlv mm/min +#define X_LATCH_BACKOFF 4 // xlb mm +#define X_ZERO_BACKOFF 2 // xzb mm + +#define Y_AXIS_MODE AXIS_STANDARD +#define Y_VELOCITY_MAX 5000 +#define Y_FEEDRATE_MAX Y_VELOCITY_MAX +#define Y_TRAVEL_MIN 0 +#define Y_TRAVEL_MAX 781 +#define Y_JERK_MAX 3500 +#define Y_JERK_HIGH_SPEED 20000 +#define Y_HOMING_INPUT 2 +#define Y_HOMING_DIRECTION 1 +#define Y_SEARCH_VELOCITY 2000 +#define Y_LATCH_VELOCITY 100 +#define Y_LATCH_BACKOFF 4 +#define Y_ZERO_BACKOFF 2 + +#define Z_AXIS_MODE AXIS_STANDARD +#define Z_VELOCITY_MAX 1200 +#define Z_FEEDRATE_MAX Z_VELOCITY_MAX +#define Z_TRAVEL_MAX 75 +#define Z_TRAVEL_MIN -15 +#define Z_JERK_MAX 500 +#define Z_JERK_HIGH_SPEED 1000 +#define Z_HOMING_INPUT 3 +#define Z_HOMING_DIRECTION 1 +#define Z_SEARCH_VELOCITY (Z_VELOCITY_MAX * 0.66666) +#define Z_LATCH_VELOCITY 25 +#define Z_LATCH_BACKOFF 4 +#define Z_ZERO_BACKOFF 2 + +//*** Input / output settings *** +/* + IO_MODE_DISABLED + IO_ACTIVE_LOW aka NORMALLY_OPEN + IO_ACTIVE_HIGH aka NORMALLY_CLOSED + + INPUT_ACTION_NONE + INPUT_ACTION_STOP + INPUT_ACTION_FAST_STOP + INPUT_ACTION_HALT + INPUT_ACTION_RESET + + INPUT_FUNCTION_NONE + INPUT_FUNCTION_LIMIT + INPUT_FUNCTION_INTERLOCK + INPUT_FUNCTION_SHUTDOWN + INPUT_FUNCTION_PANIC +*/ +// Xmin on v9 board +#define DI1_POLARITY NORMALLY_CLOSED +//#define DI1_ACTION INPUT_ACTION_STOP +#define DI1_ACTION INPUT_ACTION_NONE +#define DI1_FUNCTION INPUT_FUNCTION_LIMIT + +// Xmax +#define DI2_POLARITY NORMALLY_CLOSED +//#define DI2_ACTION INPUT_ACTION_STOP +#define DI2_ACTION INPUT_ACTION_NONE +#define DI2_FUNCTION INPUT_FUNCTION_LIMIT + +// Ymin +#define DI3_POLARITY NORMALLY_CLOSED +//#define DI3_ACTION INPUT_ACTION_STOP +#define DI3_ACTION INPUT_ACTION_NONE +#define DI3_FUNCTION INPUT_FUNCTION_LIMIT + +// Ymax +#define DI4_POLARITY NORMALLY_CLOSED +//#define DI4_ACTION INPUT_ACTION_STOP +#define DI4_ACTION INPUT_ACTION_NONE +#define DI4_FUNCTION INPUT_FUNCTION_PROBE + +// Zmin +#define DI5_POLARITY IO_ACTIVE_HIGH // Z probe +#define DI5_ACTION INPUT_ACTION_NONE +#define DI5_FUNCTION INPUT_FUNCTION_NONE + +// Zmax +#define DI6_POLARITY NORMALLY_CLOSED +//#define DI6_ACTION INPUT_ACTION_STOP +#define DI6_ACTION INPUT_ACTION_NONE +#define DI6_FUNCTION INPUT_FUNCTION_LIMIT + +// Amin +#define DI7_ENABLED IO_DISABLED +#define DI7_ACTION INPUT_ACTION_NONE +#define DI7_FUNCTION INPUT_FUNCTION_NONE + +// Amax +#define DI8_ENABLED IO_DISABLED +#define DI8_ACTION INPUT_ACTION_NONE +#define DI8_FUNCTION INPUT_FUNCTION_NONE + +// Hardware interlock input +#define DI9_ENABLED IO_DISABLED +#define DI9_ACTION INPUT_ACTION_NONE +#define DI9_FUNCTION INPUT_FUNCTION_NONE + + +// *** PWM SPINDLE CONTROL *** + +/* VFD settings: + P0 settings need to be changed: + P0-000 = 1 (Select command source = Analog terminal control) + P0-001 = 3 (Select frequency source = max(Main frequency source x,Assistant frequency source y)) + P0-002 = 2 (Main frequency source x selection = AIN1) + + P0-007 = 400 + P0-024 = 400 (set maximum frequency at 100%) + + For run/stop and direction control: + P0-016 = 1 (factory) (X1 terminal function = forward run) + P0-017 = 2 (factory was 24) (X2 terminal function = reverse run) + P0-020 = 1 (2-wire mode = 2) + P0-021 = 0 (set minimum input) + P0-022 = 0 (set minimum speed) + + Disconnect X1, X2, set P0-24 to 10, and P0-023 to 10, and read the monitor, + then set the g2 to 100% output (via M3 or direct json), then use the shown value for P0-23 + + P0-023 = 9.22 for me (set maximum input voltage) + + + X1 = running + X2 = reverse direction (low = forward) + +*/ + +#define P1_PWM_FREQUENCY 100000 // in Hz +#define P1_CW_SPEED_LO 1 // in RPM (arbitrary units) +#define P1_CW_SPEED_HI 24000 +#define P1_CW_PHASE_LO 0.05 // phase [0..1] +#define P1_CW_PHASE_HI 1.0 +#define P1_CCW_SPEED_LO 1 +#define P1_CCW_SPEED_HI 24000.0 +#define P1_CCW_PHASE_LO 0.05 +#define P1_CCW_PHASE_HI 1.0 +#define P1_PWM_PHASE_OFF 0.0 diff --git a/g2core/settings/settings_synthetos_pendulum_v2.h b/g2core/settings/settings_synthetos_pendulum_v2.h new file mode 100644 index 000000000..d5a77e6a8 --- /dev/null +++ b/g2core/settings/settings_synthetos_pendulum_v2.h @@ -0,0 +1,282 @@ +/* + * settings_smw3d_r7.h - Synthetos Pendulum v2 + * This file is part of the g2core project + * + * Copyright (c) 2010 - 2016 Alden S. Hart, Jr. + * + * This file ("the software") is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License, version 2 as published by the + * Free Software Foundation. You should have received a copy of the GNU General Public + * License, version 2 along with the software. If not, see . + * + * As a special exception, you may use this file as part of a software library without + * restriction. Specifically, if other files instantiate templates or use macros or + * inline functions from this file, or you compile this file and link it with other + * files to produce an executable, this file does not by itself cause the resulting + * executable to be covered by the GNU General Public License. This exception does not + * however invalidate any other reasons why the executable file might be covered by the + * GNU General Public License. + * + * THE SOFTWARE IS DISTRIBUTED IN THE HOPE THAT IT WILL BE USEFUL, BUT WITHOUT ANY + * WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES + * OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT + * SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF + * OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + */ + +/***********************************************************************/ +/**** Shapeoko2 500mm profile ******************************************/ +/***********************************************************************/ + +// ***> NOTE: The init message must be a single line with no CRs or LFs +#define INIT_MESSAGE "Initializing configs to Pendulum v2" + +//**** GLOBAL / GENERAL SETTINGS ****************************************************** + +// Machine configuration settings + +#define JUNCTION_INTEGRATION_TIME 0.75 // cornering - between 0.10 and 2.00 (higher is faster) +#define CHORDAL_TOLERANCE 0.01 // chordal tolerance for arcs (in mm) + +#define SOFT_LIMIT_ENABLE 0 // 0=off, 1=on +#define HARD_LIMIT_ENABLE 0 // 0=off, 1=on +#define SAFETY_INTERLOCK_ENABLE 1 // 0=off, 1=on + +#define SPINDLE_ENABLE_POLARITY 1 // 0=active low, 1=active high +#define SPINDLE_DIR_POLARITY 0 // 0=clockwise is low, 1=clockwise is high +#define SPINDLE_PAUSE_ON_HOLD true +#define SPINDLE_DWELL_TIME 1.0 + +#define COOLANT_MIST_POLARITY 1 // 0=active low, 1=active high +#define COOLANT_FLOOD_POLARITY 1 // 0=active low, 1=active high +#define COOLANT_PAUSE_ON_HOLD false + +// Communications and reporting settings + +#define USB_SERIAL_PORTS_EXPOSED 1 // 1=single endpoint usb, 2=dual endpoint usb +#define COMM_MODE JSON_MODE // one of: TEXT_MODE, JSON_MODE +#define XIO_ENABLE_FLOW_CONTROL FLOW_CONTROL_RTS // FLOW_CONTROL_OFF, FLOW_CONTROL_RTS + +#define TEXT_VERBOSITY TV_VERBOSE // one of: TV_SILENT, TV_VERBOSE +#define JSON_VERBOSITY JV_MESSAGES // one of: JV_SILENT, JV_FOOTER, JV_CONFIGS, JV_MESSAGES, JV_LINENUM, JV_VERBOSE +#define QUEUE_REPORT_VERBOSITY QR_OFF // one of: QR_OFF, QR_SINGLE, QR_TRIPLE + +#define STATUS_REPORT_VERBOSITY SR_FILTERED // one of: SR_OFF, SR_FILTERED, SR_VERBOSE + +#define STATUS_REPORT_MIN_MS 100 // milliseconds - enforces a viable minimum +#define STATUS_REPORT_INTERVAL_MS 250 // milliseconds - set $SV=0 to disable + +//#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","feed","vel","unit","coor","dist","admo","frmo","momo","stat" +#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","feed","vel","momo","stat" + +// Alternate SRs that report in drawable units +//#define STATUS_REPORT_DEFAULTS "line","vel","mpox","mpoy","mpoz","mpoa","coor","ofsa","ofsx","ofsy","ofsz","dist","unit","stat","homz","homy","homx","momo" +//#define STATUS_REPORT_DEFAULTS "_ts1","_cs1","_es1","_xs1","_fe1","line","posx","posy","posz","vel","stat" + +// Gcode startup defaults +#define GCODE_DEFAULT_UNITS MILLIMETERS // MILLIMETERS or INCHES +#define GCODE_DEFAULT_PLANE CANON_PLANE_XY // CANON_PLANE_XY, CANON_PLANE_XZ, or CANON_PLANE_YZ +#define GCODE_DEFAULT_COORD_SYSTEM G54 // G54, G55, G56, G57, G58 or G59 +#define GCODE_DEFAULT_PATH_CONTROL PATH_CONTINUOUS +#define GCODE_DEFAULT_DISTANCE_MODE ABSOLUTE_DISTANCE_MODE + +// *** motor settings ************************************************************************************ + +#define MOTOR_POWER_MODE MOTOR_POWERED_IN_CYCLE // default motor power mode (see cmMotorPowerMode in stepper.h) +#define MOTOR_POWER_TIMEOUT 2.00 // motor power timeout in seconds + +#define M1_MOTOR_MAP AXIS_X // 1ma +#define M1_STEP_ANGLE 1.8 // 1sa +#define M1_TRAVEL_PER_REV 60 // 1tr +#define M1_MICROSTEPS 64 // 1mi 1,2,4,8,16,32 +#define M1_POLARITY 1 // 1po 0=normal, 1=reversed +#define M1_POWER_MODE MOTOR_POWERED_IN_CYCLE // 1pm TRUE=low power idle enabled +#define M1_POWER_LEVEL 0.500 + +#define M5_MOTOR_MAP AXIS_X // 1ma +#define M5_STEP_ANGLE 1.8 // 1sa +#define M5_TRAVEL_PER_REV 60 // 1tr +#define M5_MICROSTEPS 64 // 1mi 1,2,4,8,16,32 +#define M5_POLARITY 1 // 1po 0=normal, 1=reversed +#define M5_POWER_MODE MOTOR_POWERED_IN_CYCLE // 1pm TRUE=low power idle enabled +#define M5_POWER_LEVEL 0.500 + +#define M2_MOTOR_MAP AXIS_X +#define M2_STEP_ANGLE 1.8 +#define M2_TRAVEL_PER_REV 60 +#define M2_MICROSTEPS 64 +#define M2_POLARITY 0 +#define M2_POWER_MODE MOTOR_POWERED_IN_CYCLE +#define M2_POWER_LEVEL 0.500 + +#define M3_MOTOR_MAP AXIS_X +#define M3_STEP_ANGLE 1.8 +#define M3_TRAVEL_PER_REV 60 +#define M3_MICROSTEPS 64 +#define M3_POLARITY 0 +#define M3_POWER_MODE MOTOR_POWERED_IN_CYCLE +#define M3_POWER_LEVEL 0.500 + +#define M4_MOTOR_MAP AXIS_X +#define M4_STEP_ANGLE 1.8 +#define M4_TRAVEL_PER_REV 60 +#define M4_MICROSTEPS 64 +#define M4_POLARITY 1 +#define M4_POWER_MODE MOTOR_POWERED_IN_CYCLE +#define M4_POWER_LEVEL 0.750 + +// *** axis settings ********************************************************************************** + +#define JERK_MAX 5000 + +#define X_AXIS_MODE AXIS_STANDARD // xam see canonical_machine.h cmAxisMode for valid values +#define X_VELOCITY_MAX 5000 // xvm G0 max velocity in mm/min +#define X_FEEDRATE_MAX X_VELOCITY_MAX // xfr G1 max feed rate in mm/min +#define X_TRAVEL_MIN 0 // xtn minimum travel for soft limits +#define X_TRAVEL_MAX 1370 // xtm travel between switches or crashes +#define X_JERK_MAX 3500 // xjm jerk * 1,000,000 +#define X_JERK_HIGH_SPEED 20000 // xjh +#define X_HOMING_INPUT 1 // xhi input used for homing or 0 to disable +#define X_HOMING_DIRECTION 1 // xhd 0=search moves negative, 1= search moves positive +#define X_SEARCH_VELOCITY 2000 // xsv minus means move to minimum switch +#define X_LATCH_VELOCITY 100 // xlv mm/min +#define X_LATCH_BACKOFF 4 // xlb mm +#define X_ZERO_BACKOFF 2 // xzb mm + +#define Y_AXIS_MODE AXIS_STANDARD +#define Y_VELOCITY_MAX 5000 +#define Y_FEEDRATE_MAX Y_VELOCITY_MAX +#define Y_TRAVEL_MIN 0 +#define Y_TRAVEL_MAX 781 +#define Y_JERK_MAX 3500 +#define Y_JERK_HIGH_SPEED 20000 +#define Y_HOMING_INPUT 2 +#define Y_HOMING_DIRECTION 1 +#define Y_SEARCH_VELOCITY 2000 +#define Y_LATCH_VELOCITY 100 +#define Y_LATCH_BACKOFF 4 +#define Y_ZERO_BACKOFF 2 + +#define Z_AXIS_MODE AXIS_STANDARD +#define Z_VELOCITY_MAX 1200 +#define Z_FEEDRATE_MAX Z_VELOCITY_MAX +#define Z_TRAVEL_MAX 75 +#define Z_TRAVEL_MIN -15 +#define Z_JERK_MAX 500 +#define Z_JERK_HIGH_SPEED 1000 +#define Z_HOMING_INPUT 3 +#define Z_HOMING_DIRECTION 1 +#define Z_SEARCH_VELOCITY (Z_VELOCITY_MAX * 0.66666) +#define Z_LATCH_VELOCITY 25 +#define Z_LATCH_BACKOFF 4 +#define Z_ZERO_BACKOFF 2 + +//*** Input / output settings *** +/* + IO_MODE_DISABLED + IO_ACTIVE_LOW aka NORMALLY_OPEN + IO_ACTIVE_HIGH aka NORMALLY_CLOSED + + INPUT_ACTION_NONE + INPUT_ACTION_STOP + INPUT_ACTION_FAST_STOP + INPUT_ACTION_HALT + INPUT_ACTION_RESET + + INPUT_FUNCTION_NONE + INPUT_FUNCTION_LIMIT + INPUT_FUNCTION_INTERLOCK + INPUT_FUNCTION_SHUTDOWN + INPUT_FUNCTION_PANIC +*/ +// Xmin on v9 board +#define DI1_POLARITY NORMALLY_CLOSED +//#define DI1_ACTION INPUT_ACTION_STOP +#define DI1_ACTION INPUT_ACTION_NONE +#define DI1_FUNCTION INPUT_FUNCTION_LIMIT + +// Xmax +#define DI2_POLARITY NORMALLY_CLOSED +//#define DI2_ACTION INPUT_ACTION_STOP +#define DI2_ACTION INPUT_ACTION_NONE +#define DI2_FUNCTION INPUT_FUNCTION_LIMIT + +// Ymin +#define DI3_POLARITY NORMALLY_CLOSED +//#define DI3_ACTION INPUT_ACTION_STOP +#define DI3_ACTION INPUT_ACTION_NONE +#define DI3_FUNCTION INPUT_FUNCTION_LIMIT + +// Ymax +#define DI4_POLARITY NORMALLY_CLOSED +//#define DI4_ACTION INPUT_ACTION_STOP +#define DI4_ACTION INPUT_ACTION_NONE +#define DI4_FUNCTION INPUT_FUNCTION_PROBE + +// Zmin +#define DI5_POLARITY IO_ACTIVE_HIGH // Z probe +#define DI5_ACTION INPUT_ACTION_NONE +#define DI5_FUNCTION INPUT_FUNCTION_NONE + +// Zmax +#define DI6_POLARITY NORMALLY_CLOSED +//#define DI6_ACTION INPUT_ACTION_STOP +#define DI6_ACTION INPUT_ACTION_NONE +#define DI6_FUNCTION INPUT_FUNCTION_LIMIT + +// Amin +#define DI7_ENABLED IO_DISABLED +#define DI7_ACTION INPUT_ACTION_NONE +#define DI7_FUNCTION INPUT_FUNCTION_NONE + +// Amax +#define DI8_ENABLED IO_DISABLED +#define DI8_ACTION INPUT_ACTION_NONE +#define DI8_FUNCTION INPUT_FUNCTION_NONE + +// Hardware interlock input +#define DI9_ENABLED IO_DISABLED +#define DI9_ACTION INPUT_ACTION_NONE +#define DI9_FUNCTION INPUT_FUNCTION_NONE + + +// *** PWM SPINDLE CONTROL *** + +/* VFD settings: + P0 settings need to be changed: + P0-000 = 1 (Select command source = Analog terminal control) + P0-001 = 3 (Select frequency source = max(Main frequency source x,Assistant frequency source y)) + P0-002 = 2 (Main frequency source x selection = AIN1) + + P0-007 = 400 + P0-024 = 400 (set maximum frequency at 100%) + + For run/stop and direction control: + P0-016 = 1 (factory) (X1 terminal function = forward run) + P0-017 = 2 (factory was 24) (X2 terminal function = reverse run) + P0-020 = 1 (2-wire mode = 2) + P0-021 = 0 (set minimum input) + P0-022 = 0 (set minimum speed) + + Disconnect X1, X2, set P0-24 to 10, and P0-023 to 10, and read the monitor, + then set the g2 to 100% output (via M3 or direct json), then use the shown value for P0-23 + + P0-023 = 9.22 for me (set maximum input voltage) + + + X1 = running + X2 = reverse direction (low = forward) + +*/ + +#define P1_PWM_FREQUENCY 100000 // in Hz +#define P1_CW_SPEED_LO 1 // in RPM (arbitrary units) +#define P1_CW_SPEED_HI 24000 +#define P1_CW_PHASE_LO 0.05 // phase [0..1] +#define P1_CW_PHASE_HI 1.0 +#define P1_CCW_SPEED_LO 1 +#define P1_CCW_SPEED_HI 24000.0 +#define P1_CCW_PHASE_LO 0.05 +#define P1_CCW_PHASE_HI 1.0 +#define P1_PWM_PHASE_OFF 0.0 From 3e8f4434a07bd993473c8e55666fb55e76f8c3d2 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Mon, 19 Feb 2018 10:29:55 -0600 Subject: [PATCH 170/193] Adjustments to Ultimaker_2_Plus --- g2core/settings/settings_Ultimaker_2_Plus.h | 16 ++++++---------- 1 file changed, 6 insertions(+), 10 deletions(-) diff --git a/g2core/settings/settings_Ultimaker_2_Plus.h b/g2core/settings/settings_Ultimaker_2_Plus.h index 532347fcf..0fb64f28f 100644 --- a/g2core/settings/settings_Ultimaker_2_Plus.h +++ b/g2core/settings/settings_Ultimaker_2_Plus.h @@ -126,7 +126,7 @@ #define M1_MICROSTEPS 128 // 1mi 1,2,4,8,16,32 #define M1_POLARITY 0 // 1po 0=normal, 1=reversed #define M1_POWER_MODE MOTOR_POWERED_IN_CYCLE // 1pm standard -#define M1_POWER_LEVEL 0.8 // 1pl +#define M1_POWER_LEVEL 0.65 // 1pl #define M1_TMC2130_TPWMTHRS 1200 // 1pth #define M1_TMC2130_TCOOLTHRS 1000 // 1cth #define M1_TMC2130_THIGH 10 // 1hth @@ -149,7 +149,7 @@ #define M2_MICROSTEPS 128 #define M2_POLARITY 1 #define M2_POWER_MODE MOTOR_POWERED_IN_CYCLE -#define M2_POWER_LEVEL 0.8 +#define M2_POWER_LEVEL 0.65 #define M2_TMC2130_TPWMTHRS 1200 #define M2_TMC2130_TCOOLTHRS 1000 #define M2_TMC2130_THIGH 10 @@ -192,7 +192,7 @@ #define M4_MICROSTEPS 16 #define M4_POLARITY 0 #define M4_POWER_MODE MOTOR_POWER_MODE -#define M4_POWER_LEVEL 0.8 +#define M4_POWER_LEVEL 0.7 #define M4_TMC2130_TPWMTHRS 180000 #define M4_TMC2130_TCOOLTHRS 100000 #define M4_TMC2130_THIGH 10 @@ -360,7 +360,7 @@ M100.1 ({{avm:90000.0}}) M100.1 ({{afr:1000}}) M100.1 ({{ajm:25000.0}}) M100.1 ({{ajh:144000.0}}) - + {ajh:50000.0} {ajh:60000.0} @@ -375,11 +375,7 @@ M100.1 ({{ajh:144000.0}}) //** Temperature Sensors ** -#include "device/max31865/max31865.h" - -#define USING_A_MAX31865 1 - -#define HAS_TEMPERATURE_SENSOR_1 true +#define HAS_TEMPERATURE_SENSOR_1 false #if HAS_TEMPERATURE_SENSOR_1 // #define TEMPERATURE_SENSOR_1_CIRCUIT_TYPE ADCCircuitDifferentialPullup // #define TEMPERATURE_SENSOR_1_CIRCUIT_INIT { /*pullup_resistance:*/ 200 } @@ -410,7 +406,7 @@ M100.1 ({{ajh:144000.0}}) #define EXTRUDER_2_OUTPUT_PIN kHeaterOutput2_PinNumber -#define HAS_TEMPERATURE_SENSOR_3 true +#define HAS_TEMPERATURE_SENSOR_3 false #if HAS_TEMPERATURE_SENSOR_3 // #define TEMPERATURE_SENSOR_3_CIRCUIT_TYPE ADCCircuitDifferentialPullup // #define TEMPERATURE_SENSOR_3_CIRCUIT_INIT { /*pullup_resistance:*/ 200 } From 5ed86f8566b7182d3659ba85c82f0cb6a9594249 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Mon, 26 Feb 2018 18:40:23 -0600 Subject: [PATCH 171/193] First pass at making outN and inN configured by doutNout and dinNin respectively. --- g2core/config_app.cpp | 190 ++++++++++++++-------- g2core/gpio.cpp | 89 +++++++++-- g2core/gpio.h | 247 +++++++++++++++++++++++++++-- g2core/settings/settings_default.h | 78 +++++++++ 4 files changed, 514 insertions(+), 90 deletions(-) diff --git a/g2core/config_app.cpp b/g2core/config_app.cpp index 412217e10..549fd6fb1 100644 --- a/g2core/config_app.cpp +++ b/g2core/config_app.cpp @@ -487,130 +487,188 @@ const cfgItem_t cfgArray[] = { { "di1","di1po",_fip, 0, din_print_po, din_get_po, din_set_po, (float *)&din1, DI1_POLARITY }, { "di1","di1ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din1, DI1_ACTION }, { "di1","di1fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din1, DI1_FUNCTION }, + { "di1","di1in",_fip, 0, din_print_in, din_get_in, din_set_in, (float *)&din1, DI1_EXTERNAL_NUMBER }, { "di2","di2en",_fip, 0, din_print_en, din_get_en, din_set_en, (float *)&din2, DI2_ENABLED }, { "di2","di2po",_fip, 0, din_print_po, din_get_po, din_set_po, (float *)&din2, DI2_POLARITY }, { "di2","di2ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din2, DI2_ACTION }, { "di2","di2fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din2, DI2_FUNCTION }, + { "di2","di2in",_fip, 0, din_print_in, din_get_in, din_set_in, (float *)&din2, DI2_EXTERNAL_NUMBER }, +#if (D_IN_CHANNELS >= 3) { "di3","di3en",_fip, 0, din_print_en, din_get_en, din_set_en, (float *)&din3, DI3_ENABLED }, { "di3","di3po",_fip, 0, din_print_po, din_get_po, din_set_po, (float *)&din3, DI3_POLARITY }, { "di3","di3ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din3, DI3_ACTION }, { "di3","di3fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din3, DI3_FUNCTION }, - + { "di3","di3in",_fip, 0, din_print_in, din_get_in, din_set_in, (float *)&din3, DI3_EXTERNAL_NUMBER }, +#endif +#if (D_IN_CHANNELS >= 4) { "di4","di4en",_fip, 0, din_print_en, din_get_en, din_set_en, (float *)&din4, DI4_ENABLED }, { "di4","di4po",_fip, 0, din_print_po, din_get_po, din_set_po, (float *)&din4, DI4_POLARITY }, { "di4","di4ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din4, DI4_ACTION }, { "di4","di4fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din4, DI4_FUNCTION }, - + { "di4","di4in",_fip, 0, din_print_in, din_get_in, din_set_in, (float *)&din4, DI4_EXTERNAL_NUMBER }, +#endif +#if (D_IN_CHANNELS >= 5) { "di5","di5en",_fip, 0, din_print_en, din_get_en, din_set_en, (float *)&din5, DI5_ENABLED }, { "di5","di5po",_fip, 0, din_print_po, din_get_po, din_set_po, (float *)&din5, DI5_POLARITY }, { "di5","di5ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din5, DI5_ACTION }, { "di5","di5fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din5, DI5_FUNCTION }, - + { "di5","di5in",_fip, 0, din_print_in, din_get_in, din_set_in, (float *)&din5, DI5_EXTERNAL_NUMBER }, +#endif +#if (D_IN_CHANNELS >= 6) { "di6","di6en",_fip, 0, din_print_en, din_get_en, din_set_en, (float *)&din6, DI6_ENABLED }, { "di6","di6po",_fip, 0, din_print_po, din_get_po, din_set_po, (float *)&din6, DI6_POLARITY }, { "di6","di6ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din6, DI6_ACTION }, { "di6","di6fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din6, DI6_FUNCTION }, - + { "di6","di6in",_fip, 0, din_print_in, din_get_in, din_set_in, (float *)&din6, DI6_EXTERNAL_NUMBER }, +#endif +#if (D_IN_CHANNELS >= 7) { "di7","di7en",_fip, 0, din_print_en, din_get_en, din_set_en, (float *)&din7, DI7_ENABLED }, { "di7","di7po",_fip, 0, din_print_po, din_get_po, din_set_po, (float *)&din7, DI7_POLARITY }, { "di7","di7ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din7, DI7_ACTION }, { "di7","di7fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din7, DI7_FUNCTION }, - + { "di7","di7in",_fip, 0, din_print_in, din_get_in, din_set_in, (float *)&din7, DI7_EXTERNAL_NUMBER }, +#endif +#if (D_IN_CHANNELS >= 8) { "di8","di8en",_fip, 0, din_print_en, din_get_en, din_set_en, (float *)&din8, DI8_ENABLED }, { "di3","di8po",_fip, 0, din_print_po, din_get_po, din_set_po, (float *)&din8, DI8_POLARITY }, { "di8","di8ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din8, DI8_ACTION }, { "di8","di8fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din8, DI8_FUNCTION }, + { "di8","di8in",_fip, 0, din_print_in, din_get_in, din_set_in, (float *)&din8, DI8_EXTERNAL_NUMBER }, +#endif #if (D_IN_CHANNELS >= 9) { "di9","di9en",_fip, 0, din_print_en, din_get_en, din_set_en, (float *)&din9, DI9_ENABLED }, { "di9","di9po",_fip, 0, din_print_po, din_get_po, din_set_po, (float *)&din9, DI9_POLARITY }, { "di9","di9ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din9, DI9_ACTION }, { "di9","di9fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din9, DI9_FUNCTION }, + { "di9","di9in",_fip, 0, din_print_in, din_get_in, din_set_in, (float *)&din9, DI9_EXTERNAL_NUMBER }, #endif #if (D_IN_CHANNELS >= 10) { "di10","di10en",_fip, 0, din_print_en, din_get_en, din_set_en, (float *)&din10, DI10_ENABLED }, { "di10","di10po",_fip, 0, din_print_po, din_get_po, din_set_po, (float *)&din10, DI10_POLARITY }, { "di10","di10ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din10, DI10_ACTION }, { "di10","di10fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din10, DI10_FUNCTION }, + { "di10","di10in",_fip, 0, din_print_in, din_get_in, din_set_in, (float *)&din10, DI10_EXTERNAL_NUMBER }, #endif #if (D_IN_CHANNELS >= 11) { "di11","di11en",_fip, 0, din_print_en, din_get_en, din_set_en, (float *)&din11, DI11_ENABLED }, { "di11","di11po",_fip, 0, din_print_po, din_get_po, din_set_po, (float *)&din11, DI11_POLARITY }, { "di11","di11ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din11, DI11_ACTION }, { "di11","di11fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din11, DI11_FUNCTION }, + { "di11","di11in",_fip, 0, din_print_in, din_get_in, din_set_in, (float *)&din11, DI11_EXTERNAL_NUMBER }, #endif #if (D_IN_CHANNELS >= 12) { "di12","di12en",_fip, 0, din_print_en, din_get_en, din_set_en, (float *)&din12, DI12_ENABLED }, { "di12","di12po",_fip, 0, din_print_po, din_get_po, din_set_po, (float *)&din12, DI12_POLARITY }, { "di12","di12ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din12, DI12_ACTION }, { "di12","di12fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din12, DI12_FUNCTION }, + { "di12","di12in",_fip, 0, din_print_in, din_get_in, din_set_in, (float *)&din12, DI12_EXTERNAL_NUMBER }, #endif // Digital input state readers - { "in","in1", _f0, 0, din_print_in, din_get_input, set_ro, (float *)&din1, 0 }, - { "in","in2", _f0, 0, din_print_in, din_get_input, set_ro, (float *)&din2, 0 }, - { "in","in3", _f0, 0, din_print_in, din_get_input, set_ro, (float *)&din3, 0 }, - { "in","in4", _f0, 0, din_print_in, din_get_input, set_ro, (float *)&din4, 0 }, - { "in","in5", _f0, 0, din_print_in, din_get_input, set_ro, (float *)&din5, 0 }, - { "in","in6", _f0, 0, din_print_in, din_get_input, set_ro, (float *)&din6, 0 }, - { "in","in7", _f0, 0, din_print_in, din_get_input, set_ro, (float *)&din7, 0 }, - { "in","in8", _f0, 0, din_print_in, din_get_input, set_ro, (float *)&din8, 0 }, -#if (D_IN_CHANNELS >= 9) - { "in","in9", _f0, 0, din_print_in, din_get_input, set_ro, (float *)&din9, 0 }, + { "in","in1", _f0, 0, din_print_state, din_get_input, set_ro, (float *)&in1, 0 }, + { "in","in2", _f0, 0, din_print_state, din_get_input, set_ro, (float *)&in2, 0 }, + { "in","in3", _f0, 0, din_print_state, din_get_input, set_ro, (float *)&in3, 0 }, + { "in","in4", _f0, 0, din_print_state, din_get_input, set_ro, (float *)&in4, 0 }, + { "in","in5", _f0, 0, din_print_state, din_get_input, set_ro, (float *)&in5, 0 }, + { "in","in6", _f0, 0, din_print_state, din_get_input, set_ro, (float *)&in6, 0 }, + { "in","in7", _f0, 0, din_print_state, din_get_input, set_ro, (float *)&in7, 0 }, + { "in","in8", _f0, 0, din_print_state, din_get_input, set_ro, (float *)&in8, 0 }, + { "in","in9", _f0, 0, din_print_state, din_get_input, set_ro, (float *)&in9, 0 }, + { "in","in10", _f0, 0, din_print_state, din_get_input, set_ro, (float *)&in10, 0 }, + { "in","in11", _f0, 0, din_print_state, din_get_input, set_ro, (float *)&in11, 0 }, + { "in","in12", _f0, 0, din_print_state, din_get_input, set_ro, (float *)&in12, 0 }, + { "in","in13", _f0, 0, din_print_state, din_get_input, set_ro, (float *)&in13, 0 }, + { "in","in14", _f0, 0, din_print_state, din_get_input, set_ro, (float *)&in14, 0 }, + + // digital output configs + { "do1", "do1en", _fip, 0, dout_print_en, dout_get_en, dout_set_en, (float *)&dout1, DO1_ENABLED }, + { "do1", "do1po", _fip, 0, dout_print_po, dout_get_po, dout_set_po, (float *)&dout1, DO1_POLARITY }, + { "do1", "do1out",_fip, 0, dout_print_out, dout_get_out, dout_set_out, (float *)&dout1, DO1_EXTERNAL_NUMBER }, +#if (D_OUT_CHANNELS >= 2) + { "do2", "do2en", _fip, 0, dout_print_en, dout_get_en, dout_set_en, (float *)&dout2, DO2_ENABLED }, + { "do2", "do2po", _fip, 0, dout_print_po, dout_get_po, dout_set_po, (float *)&dout2, DO2_POLARITY }, + { "do2", "do2out",_fip, 0, dout_print_out, dout_get_out, dout_set_out, (float *)&dout2, DO2_EXTERNAL_NUMBER }, #endif -#if (D_IN_CHANNELS >= 10) - { "in","in10", _f0, 0, din_print_in, din_get_input, set_ro, (float *)&din10,0 }, +#if (D_OUT_CHANNELS >= 3) + { "do3", "do3en", _fip, 0, dout_print_en, dout_get_en, dout_set_en, (float *)&dout3, DO3_ENABLED }, + { "do3", "do3po", _fip, 0, dout_print_po, dout_get_po, dout_set_po, (float *)&dout3, DO3_POLARITY }, + { "do3", "do3out",_fip, 0, dout_print_out, dout_get_out, dout_set_out, (float *)&dout3, DO3_EXTERNAL_NUMBER }, #endif -#if (D_IN_CHANNELS >= 11) - { "in","in11", _f0, 0, din_print_in, din_get_input, set_ro, (float *)&din11,0 }, +#if (D_OUT_CHANNELS >= 4) + { "do4", "do4en", _fip, 0, dout_print_en, dout_get_en, dout_set_en, (float *)&dout4, DO4_ENABLED }, + { "do4", "do4po", _fip, 0, dout_print_po, dout_get_po, dout_set_po, (float *)&dout4, DO4_POLARITY }, + { "do4", "do4out",_fip, 0, dout_print_out, dout_get_out, dout_set_out, (float *)&dout4, DO4_EXTERNAL_NUMBER }, #endif -#if (D_IN_CHANNELS >= 12) - { "in","in12", _f0, 0, din_print_in, din_get_input, set_ro, (float *)&din12,0 }, +#if (D_OUT_CHANNELS >= 5) + { "do5", "do5en", _fip, 0, dout_print_en, dout_get_en, dout_set_en, (float *)&dout5, DO5_ENABLED }, + { "do5", "do5po", _fip, 0, dout_print_po, dout_get_po, dout_set_po, (float *)&dout5, DO5_POLARITY }, + { "do5", "do5out",_fip, 0, dout_print_out, dout_get_out, dout_set_out, (float *)&dout5, DO5_EXTERNAL_NUMBER }, +#endif +#if (D_OUT_CHANNELS >= 6) + { "do6", "do6en", _fip, 0, dout_print_en, dout_get_en, dout_set_en, (float *)&dout6, DO6_ENABLED }, + { "do6", "do6po", _fip, 0, dout_print_po, dout_get_po, dout_set_po, (float *)&dout6, DO6_POLARITY }, + { "do6", "do6out",_fip, 0, dout_print_out, dout_get_out, dout_set_out, (float *)&dout6, DO6_EXTERNAL_NUMBER }, +#endif +#if (D_OUT_CHANNELS >= 7) + { "do7", "do7en", _fip, 0, dout_print_en, dout_get_en, dout_set_en, (float *)&dout7, DO7_ENABLED }, + { "do7", "do7po", _fip, 0, dout_print_po, dout_get_po, dout_set_po, (float *)&dout7, DO7_POLARITY }, + { "do7", "do7out",_fip, 0, dout_print_out, dout_get_out, dout_set_out, (float *)&dout7, DO7_EXTERNAL_NUMBER }, +#endif +#if (D_OUT_CHANNELS >= 8) + { "do8", "do8en", _fip, 0, dout_print_en, dout_get_en, dout_set_en, (float *)&dout8, DO8_ENABLED }, + { "do8", "do8po", _fip, 0, dout_print_po, dout_get_po, dout_set_po, (float *)&dout8, DO8_POLARITY }, + { "do8", "do8out",_fip, 0, dout_print_out, dout_get_out, dout_set_out, (float *)&dout8, DO8_EXTERNAL_NUMBER }, +#endif +#if (D_OUT_CHANNELS >= 9) + { "do9", "do9en", _fip, 0, dout_print_en, dout_get_en, dout_set_en, (float *)&dout9, DO9_ENABLED }, + { "do9", "do9po", _fip, 0, dout_print_po, dout_get_po, dout_set_po, (float *)&dout9, DO9_POLARITY }, + { "do9", "do9out",_fip, 0, dout_print_out, dout_get_out, dout_set_out, (float *)&dout9, DO9_EXTERNAL_NUMBER }, +#endif +#if (D_OUT_CHANNELS >= 10) + { "do10", "do10en", _fip, 0, dout_print_en, dout_get_en, dout_set_en, (float *)&dout10, DO10_ENABLED }, + { "do10", "do10po", _fip, 0, dout_print_po, dout_get_po, dout_set_po, (float *)&dout10, DO10_POLARITY }, + { "do10", "do10out",_fip, 0, dout_print_out, dout_get_out, dout_set_out, (float *)&dout10, DO10_EXTERNAL_NUMBER }, +#endif +#if (D_OUT_CHANNELS >= 11) + { "do11", "do11en", _fip, 0, dout_print_en, dout_get_en, dout_set_en, (float *)&dout11, DO11_ENABLED }, + { "do11", "do11po", _fip, 0, dout_print_po, dout_get_po, dout_set_po, (float *)&dout11, DO11_POLARITY }, + { "do11", "do11out",_fip, 0, dout_print_out, dout_get_out, dout_set_out, (float *)&dout11, DO11_EXTERNAL_NUMBER }, +#endif +#if (D_OUT_CHANNELS >= 12) + { "do12", "do12en", _fip, 0, dout_print_en, dout_get_en, dout_set_en, (float *)&dout12, DO12_ENABLED }, + { "do12", "do12po", _fip, 0, dout_print_po, dout_get_po, dout_set_po, (float *)&dout12, DO12_POLARITY }, + { "do12", "do12out",_fip, 0, dout_print_out, dout_get_out, dout_set_out, (float *)&dout12, DO12_EXTERNAL_NUMBER }, +#endif +#if (D_OUT_CHANNELS >= 13) + { "do13", "do13en", _fip, 0, dout_print_en, dout_get_en, dout_set_en, (float *)&dout13, DO13_ENABLED }, + { "do13", "do13po", _fip, 0, dout_print_po, dout_get_po, dout_set_po, (float *)&dout13, DO13_POLARITY }, + { "do13", "do13out",_fip, 0, dout_print_out, dout_get_out, dout_set_out, (float *)&dout13, DO13_EXTERNAL_NUMBER }, +#endif +#if (D_OUT_CHANNELS >= 14) + { "do14", "do14en", _fip, 0, dout_print_en, dout_get_en, dout_set_en, (float *)&dout14, DO14_ENABLED }, + { "do14", "do14po", _fip, 0, dout_print_po, dout_get_po, dout_set_po, (float *)&dout14, DO14_POLARITY }, + { "do14", "do14out",_fip, 0, dout_print_out, dout_get_out, dout_set_out, (float *)&dout14, DO14_EXTERNAL_NUMBER }, #endif - - // digital output configs - { "do1", "do1en", _fip, 0, dout_print_en, dout_get_en, dout_set_en, (float *)&dout1, DO1_ENABLED }, - { "do1", "do1po", _fip, 0, dout_print_po, dout_get_po, dout_set_po, (float *)&dout1, DO1_POLARITY }, - { "do2", "do2en", _fip, 0, dout_print_en, dout_get_en, dout_set_en, (float *)&dout2, DO2_ENABLED }, - { "do2", "do2po", _fip, 0, dout_print_po, dout_get_po, dout_set_po, (float *)&dout2, DO2_POLARITY }, - { "do3", "do3en", _fip, 0, dout_print_en, dout_get_en, dout_set_en, (float *)&dout3, DO3_ENABLED }, - { "do3", "do3po", _fip, 0, dout_print_po, dout_get_po, dout_set_po, (float *)&dout3, DO3_POLARITY }, - { "do4", "do4en", _fip, 0, dout_print_en, dout_get_en, dout_set_en, (float *)&dout4, DO4_ENABLED }, - { "do5", "do5po", _fip, 0, dout_print_po, dout_get_po, dout_set_po, (float *)&dout5, DO5_POLARITY }, - { "do5", "do5en", _fip, 0, dout_print_en, dout_get_en, dout_set_en, (float *)&dout5, DO5_ENABLED }, - { "do6", "do6po", _fip, 0, dout_print_po, dout_get_po, dout_set_po, (float *)&dout6, DO6_POLARITY }, - { "do7", "do7en", _fip, 0, dout_print_en, dout_get_en, dout_set_en, (float *)&dout7, DO7_ENABLED }, - { "do7", "do7po", _fip, 0, dout_print_po, dout_get_po, dout_set_po, (float *)&dout7, DO7_POLARITY }, - { "do8", "do8en", _fip, 0, dout_print_en, dout_get_en, dout_set_en, (float *)&dout8, DO8_ENABLED }, - { "do8", "do8po", _fip, 0, dout_print_po, dout_get_po, dout_set_po, (float *)&dout8, DO8_POLARITY }, - { "do9", "do9en", _fip, 0, dout_print_en, dout_get_en, dout_set_en, (float *)&dout9, DO9_ENABLED }, - { "do9", "do9po", _fip, 0, dout_print_po, dout_get_po, dout_set_po, (float *)&dout9, DO9_POLARITY }, - { "do10","do10en",_fip, 0, dout_print_en, dout_get_en, dout_set_en, (float *)&dout10, DO10_ENABLED }, - { "do10","do10po",_fip, 0, dout_print_po, dout_get_po, dout_set_po, (float *)&dout10, DO10_POLARITY }, - { "do11","do11en",_fip, 0, dout_print_en, dout_get_en, dout_set_en, (float *)&dout11, DO11_ENABLED }, - { "do11","do11po",_fip, 0, dout_print_po, dout_get_po, dout_set_po, (float *)&dout11, DO11_POLARITY }, - { "do12","do12en",_fip, 0, dout_print_en, dout_get_en, dout_set_en, (float *)&dout12, DO12_ENABLED }, - { "do12","do12po",_fip, 0, dout_print_po, dout_get_po, dout_set_po, (float *)&dout12, DO12_POLARITY }, - { "do13","do13en",_fip, 0, dout_print_en, dout_get_en, dout_set_en, (float *)&dout13, DO13_ENABLED }, - { "do13","do13po",_fip, 0, dout_print_po, dout_get_po, dout_set_po, (float *)&dout13, DO13_POLARITY }, - // Digital output state readers (default to non-active) - { "out","out1", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&dout1, 0 }, - { "out","out2", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&dout2, 0 }, - { "out","out3", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&dout3, 0 }, - { "out","out4", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&dout4, 0 }, - { "out","out5", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&dout5, 0 }, - { "out","out6", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&dout6, 0 }, - { "out","out7", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&dout7, 0 }, - { "out","out8", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&dout8, 0 }, - { "out","out9", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&dout9, 0 }, - { "out","out10", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&dout10, 0 }, - { "out","out11", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&dout11, 0 }, - { "out","out12", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&dout12, 0 }, - { "out","out13", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&dout13, 0 }, + { "out","out1", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&out1, 0 }, + { "out","out2", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&out2, 0 }, + { "out","out3", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&out3, 0 }, + { "out","out4", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&out4, 0 }, + { "out","out5", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&out5, 0 }, + { "out","out6", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&out6, 0 }, + { "out","out7", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&out7, 0 }, + { "out","out8", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&out8, 0 }, + { "out","out9", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&out9, 0 }, + { "out","out10", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&out10, 0 }, + { "out","out11", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&out11, 0 }, + { "out","out12", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&out12, 0 }, + { "out","out13", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&out13, 0 }, + { "out","out14", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&out14, 0 }, // Analog input configs +#if (A_IN_CHANNELS >= 1) { "ain1","ain1ty",_fip, 0, ain_print_type, ain_get_type, ain_set_type, (float *)&ain1, AI1_TYPE }, { "ain1","ain1ct",_fip, 0, ain_print_circuit, ain_get_circuit, ain_set_circuit, (float *)&ain1, AI1_CIRCUIT }, { "ain1","ain1p1",_fip, 4, ain_print_p, ain_get_p1, ain_set_p1, (float *)&ain1, AI1_P1 }, @@ -620,7 +678,8 @@ const cfgItem_t cfgArray[] = { { "ain1","ain1p5",_fip, 4, ain_print_p, ain_get_p5, ain_set_p5, (float *)&ain1, AI1_P5 }, { "ain1","ain1vv",_f0, 4, ain_print_value, ain_get_value, set_ro, (float *)&ain1, 0 }, { "ain1","ain1rv",_f0, 2, ain_print_resistance, ain_get_resistance, set_ro, (float *)&ain1, 0 }, - +#endif +#if (A_IN_CHANNELS >= 2) { "ain2","ain2ty",_fip, 0, ain_print_type, ain_get_type, ain_set_type, (float *)&ain2, AI2_TYPE }, { "ain2","ain2ct",_fip, 0, ain_print_circuit, ain_get_circuit, ain_set_circuit, (float *)&ain2, AI2_CIRCUIT }, { "ain2","ain2p1",_fip, 4, ain_print_p, ain_get_p1, ain_set_p1, (float *)&ain2, AI2_P1 }, @@ -630,7 +689,8 @@ const cfgItem_t cfgArray[] = { { "ain2","ain2p5",_fip, 4, ain_print_p, ain_get_p5, ain_set_p5, (float *)&ain2, AI2_P5 }, { "ain2","ain2vv",_f0, 4, ain_print_value, ain_get_value, set_ro, (float *)&ain2, 0 }, { "ain2","ain2rv",_f0, 2, ain_print_resistance, ain_get_resistance, set_ro, (float *)&ain2, 0 }, - +#endif +#if (A_IN_CHANNELS >= 3) { "ain3","ain3ty",_fip, 0, ain_print_type, ain_get_type, ain_set_type, (float *)&ain3, AI3_TYPE }, { "ain3","ain3ct",_fip, 0, ain_print_circuit, ain_get_circuit, ain_set_circuit, (float *)&ain3, AI3_CIRCUIT }, { "ain3","ain3p1",_fip, 4, ain_print_p, ain_get_p1, ain_set_p1, (float *)&ain3, AI3_P1 }, @@ -640,7 +700,8 @@ const cfgItem_t cfgArray[] = { { "ain3","ain3p5",_fip, 4, ain_print_p, ain_get_p5, ain_set_p5, (float *)&ain3, AI3_P5 }, { "ain3","ain3vv",_f0, 4, ain_print_value, ain_get_value, set_ro, (float *)&ain3, 0 }, { "ain3","ain3rv",_f0, 2, ain_print_resistance, ain_get_resistance, set_ro, (float *)&ain3, 0 }, - +#endif +#if (A_IN_CHANNELS >= 4) { "ain4","ain4ty",_fip, 0, ain_print_type, ain_get_type, ain_set_type, (float *)&ain4, AI4_TYPE }, { "ain4","ain4ct",_fip, 0, ain_print_circuit, ain_get_circuit, ain_set_circuit, (float *)&ain4, AI4_CIRCUIT }, { "ain4","ain4p1",_fip, 4, ain_print_p, ain_get_p1, ain_set_p1, (float *)&ain4, AI4_P1 }, @@ -650,6 +711,7 @@ const cfgItem_t cfgArray[] = { { "ain4","ain4p5",_fip, 4, ain_print_p, ain_get_p5, ain_set_p5, (float *)&ain4, AI4_P5 }, { "ain4","ain4vv",_f0, 4, ain_print_value, ain_get_value, set_ro, (float *)&ain4, 0 }, { "ain4","ain4rv",_f0, 2, ain_print_resistance, ain_get_resistance, set_ro, (float *)&ain4, 0 }, +#endif // PWM settings { "p1","p1frq",_fip, 0, pwm_print_p1frq, get_flt, pwm_set_pwm,(float *)&pwm.c[PWM_1].frequency, P1_PWM_FREQUENCY }, diff --git a/g2core/gpio.cpp b/g2core/gpio.cpp index 0cb6e9aef..49f0528f4 100644 --- a/g2core/gpio.cpp +++ b/g2core/gpio.cpp @@ -150,9 +150,44 @@ type* _io(const nvObj_t *nv) { }; gpioDigitalInput* _i(const nvObj_t *nv) { return _io(nv); } +gpioDigitalInputReader* _ir(const nvObj_t *nv) { return _io(nv); } gpioDigitalOutput* _o(const nvObj_t *nv) { return _io(nv); } +gpioDigitalOutputReader* _or(const nvObj_t *nv) { return _io(nv); } gpioAnalogInput* _ai(const nvObj_t *nv) { return _io(nv); } +gpioDigitalInputReader in1; +gpioDigitalInputReader in2; +gpioDigitalInputReader in3; +gpioDigitalInputReader in4; +gpioDigitalInputReader in5; +gpioDigitalInputReader in6; +gpioDigitalInputReader in7; +gpioDigitalInputReader in8; +gpioDigitalInputReader in9; +gpioDigitalInputReader in10; +gpioDigitalInputReader in11; +gpioDigitalInputReader in12; +gpioDigitalInputReader in13; +gpioDigitalInputReader in14; + +gpioDigitalInputReader* const in_r[14] = {&in1, &in2, &in3, &in4, &in5, &in6, &in7, &in8, &in9, &in10, &in11, &in12, &in13, &in14}; + +gpioDigitalOutputReader out1; +gpioDigitalOutputReader out2; +gpioDigitalOutputReader out3; +gpioDigitalOutputReader out4; +gpioDigitalOutputReader out5; +gpioDigitalOutputReader out6; +gpioDigitalOutputReader out7; +gpioDigitalOutputReader out8; +gpioDigitalOutputReader out9; +gpioDigitalOutputReader out10; +gpioDigitalOutputReader out11; +gpioDigitalOutputReader out12; +gpioDigitalOutputReader out13; +gpioDigitalOutputReader out14; + +gpioDigitalOutputReader* const out_r[14] = {&out1 ,&out2 ,&out3 ,&out4 ,&out5 ,&out6 ,&out7 ,&out8 ,&out9 ,&out10 ,&out11 ,&out12 ,&out13 ,&out14}; /* * Get/set enabled @@ -203,12 +238,25 @@ stat_t din_set_fn(nvObj_t *nv) } /* - * io_get_input() - return input state given an nv object - * Note: if the input is disabled, it returns NULL. + * Get/set input function + */ +stat_t din_get_in(nvObj_t *nv) +{ + return _i(nv)->getExternalNumber(nv); +} +stat_t din_set_in(nvObj_t *nv) +{ + return _i(nv)->setExternalNumber(nv); +} + +/* + * Get input state given an nv object + * Note: if this is not forwarded to an input or the input is disabled, + * it returns NULL. */ stat_t din_get_input(nvObj_t *nv) { - return _i(nv)->getState(nv); + return _ir(nv)->getState(nv); } @@ -237,15 +285,28 @@ stat_t dout_set_po(nvObj_t *nv) } /* - * io_get_output()/io_set_output() - get/set output state given an nv object + * Get/set input polarity + */ +stat_t dout_get_out(nvObj_t *nv) +{ + return _o(nv)->getExternalNumber(nv); +} +stat_t dout_set_out(nvObj_t *nv) +{ + return _o(nv)->setExternalNumber(nv); +} + + +/* + * Gget/set output state given an nv object */ stat_t dout_get_output(nvObj_t *nv) { - return _o(nv)->getValue(nv); + return _or(nv)->getValue(nv); } stat_t dout_set_output(nvObj_t *nv) { - return _o(nv)->setValue(nv); + return _or(nv)->setValue(nv); } @@ -312,11 +373,13 @@ stat_t ain_set_p5(nvObj_t *nv) { return ain_set_parameter(nv, 4); }; static const char fmt_gpio_in_po[] = "[%smo] input polarity%13d [0=normal/active-high,1=inverted/active-low]\n"; static const char fmt_gpio_ac[] = "[%sac] input action%15d [0=none,1=stop,2=fast_stop,3=halt,4=alarm,5=shutdown,6=panic,7=reset]\n"; static const char fmt_gpio_fn[] = "[%sfn] input function%13d [0=none,1=limit,2=interlock,3=shutdown,4=probe]\n"; - static const char fmt_gpio_in[] = "Input %s state: %5d\n"; + static const char fmt_gpio_in[] = "[%sin] input external number%6d [0=none,1-12=inX shows the value of this din]\n"; + static const char fmt_gpio_state[] = "Input %s state: %5d\n"; static const char fmt_gpio_out_en[] = "[%smo] output enabled%12d [-1=unavailable,0=disabled,1=enabled]\n"; static const char fmt_gpio_out_po[] = "[%smo] output polarity%12d [0=normal/active-high,1=inverted/active-low]\n"; - static const char fmt_gpio_out[] = "Output %s state: %5d\n"; + static const char fmt_gpio_out_out[] = "[%sout] output external number%5d [0=none,1-14=outX shows the value of this dout]\n"; + static const char fmt_gpio_out_state[] = "Output %s state: %5d\n"; static const char fmt_ain_value[] = "Analog input %s voltage: %5.2fV\n"; static const char fmt_ain_resistance[] = "Analog input %s resistance: %5.2fohm\n"; @@ -333,15 +396,17 @@ stat_t ain_set_p5(nvObj_t *nv) { return ain_set_parameter(nv, 4); }; void din_print_po(nvObj_t *nv) {_print_di(nv, fmt_gpio_in_po);} void din_print_ac(nvObj_t *nv) {_print_di(nv, fmt_gpio_ac);} void din_print_fn(nvObj_t *nv) {_print_di(nv, fmt_gpio_fn);} - void din_print_in(nvObj_t *nv) { - sprintf(cs.out_buf, fmt_gpio_in, nv->token, (int)nv->value); + void din_print_in(nvObj_t *nv) {_print_di(nv, fmt_gpio_in);} + void din_print_state(nvObj_t *nv) { + sprintf(cs.out_buf, fmt_gpio_state, nv->token, (int)nv->value); xio_writeline(cs.out_buf); } void dout_print_en(nvObj_t *nv) {_print_di(nv, fmt_gpio_out_en);} void dout_print_po(nvObj_t *nv) {_print_di(nv, fmt_gpio_out_po);} - void dout_print_out(nvObj_t *nv) { - sprintf(cs.out_buf, fmt_gpio_out, nv->token, (int)nv->value); + void dout_print_out(nvObj_t *nv) {_print_di(nv, fmt_gpio_out_out);} + void dout_print_out_state(nvObj_t *nv) { + sprintf(cs.out_buf, fmt_gpio_out_state, nv->token, (int)nv->value); xio_writeline(cs.out_buf); } diff --git a/g2core/gpio.h b/g2core/gpio.h index b782863f5..708957593 100644 --- a/g2core/gpio.h +++ b/g2core/gpio.h @@ -101,6 +101,10 @@ typedef enum { INPUT_EDGE_TRAILING // flag is set when trailing edge is detected } inputEdgeFlag; +// forward declare +struct gpioDigitalInputReader; +extern gpioDigitalInputReader* const in_r[14]; + /* * gpioDigitalInput - digital input base class */ @@ -124,7 +128,9 @@ struct gpioDigitalInput { virtual ioPolarity getPolarity(); virtual bool setPolarity(const ioPolarity); - virtual void setExternalNumber(const uint8_t); + virtual bool setExternalNumber(const uint8_t); + virtual const uint8_t getExternalNumber(); + virtual void setIsHoming(const bool); virtual void setIsProbing(const bool); @@ -210,8 +216,79 @@ struct gpioDigitalInput { } return (STAT_OK); }; + + stat_t getExternalNumber(nvObj_t *nv) + { + nv->value = getExternalNumber(); + nv->valuetype = TYPE_INT; + return (STAT_OK); + }; + stat_t setExternalNumber(nvObj_t *nv) + { + if ((nv->value < 0) || (nv->value > 14)) { + return (STAT_INPUT_VALUE_RANGE_ERROR); + } + if (!setExternalNumber(nv->value)) { + return STAT_PARAMETER_IS_READ_ONLY; + } + return (STAT_OK); + }; +}; + + +/* + * gpioDigitalInputReader - digital input reader class - the "in1" - "inX" objects + */ + +struct gpioDigitalInputReader { + gpioDigitalInput* pin; + + // functions for use by other parts of the code + + bool setPin(gpioDigitalInput* new_pin) { + new_pin = pin; // might be null + return true; + }; + + gpioDigitalInput* getPin() { + return pin; // might be null + }; + + bool getState() { + if (!pin) { return false; } + return pin->getState(); + }; + + + // functions that take nvObj_t* and return stat_t, NOT overridden + + stat_t getState(nvObj_t *nv) + { + if (!pin) { + nv->valuetype = TYPE_NULL; + return (STAT_OK); + } + return pin->getState(nv); + }; }; +// setup the gpioDigitalInputReader objects as extern +extern gpioDigitalInputReader in1; +extern gpioDigitalInputReader in2; +extern gpioDigitalInputReader in3; +extern gpioDigitalInputReader in4; +extern gpioDigitalInputReader in5; +extern gpioDigitalInputReader in6; +extern gpioDigitalInputReader in7; +extern gpioDigitalInputReader in8; +extern gpioDigitalInputReader in9; +extern gpioDigitalInputReader in10; +extern gpioDigitalInputReader in11; +extern gpioDigitalInputReader in12; +extern gpioDigitalInputReader in13; +extern gpioDigitalInputReader in14; + + /* * gpioDigitalInputPin - concrete child of gpioDigitalInput */ @@ -227,7 +304,8 @@ struct gpioDigitalInputPin : gpioDigitalInput { bool homing_mode; // set true when input is in homing mode. bool probing_mode; // set true when input is in probing mode. - uint8_t ext_pin_number; // the number used externally for this pin ("in" + ext_pin_number) + const uint8_t ext_pin_number; // the number used externally for this pin ("din" + ext_pin_number) + uint8_t proxy_pin_number; // the number used externally for this pin ("in" + proxy_pin_number) uint16_t lockout_ms; // number of milliseconds for debounce lockout Motate::Timeout lockout_timer; // time to expire current debounce lockout, or 0 if no lockout @@ -237,15 +315,19 @@ struct gpioDigitalInputPin : gpioDigitalInput { // In constructor, simply forward all values to the Pin_t // To get a different behavior, override this object. template - gpioDigitalInputPin(const ioEnabled _enabled, const ioPolarity _polarity, const uint8_t _ext_pin_number, T&&... V) : + gpioDigitalInputPin(const ioEnabled _enabled, const ioPolarity _polarity, const uint8_t _ext_pin_number, const uint8_t _proxy_pin_number, T&&... V) : gpioDigitalInput{}, enabled{_enabled}, polarity{_polarity}, ext_pin_number{_ext_pin_number}, + proxy_pin_number{_proxy_pin_number}, pin{((polarity == IO_ACTIVE_LOW) ? kPullUp|kDebounce : kDebounce), [&]{this->pin_changed();}, std::forward(V)...} { if (pin.isNull()) { enabled = IO_UNAVAILABLE; + proxy_pin_number = 0; + } else { + setExternalNumber(proxy_pin_number); } }; @@ -304,20 +386,36 @@ struct gpioDigitalInputPin : gpioDigitalInput { return true; }; - void setExternalNumber(const uint8_t e) override + bool setExternalNumber(const uint8_t e) override { - ext_pin_number = e; - } + if (e == proxy_pin_number) { return true; } + if (proxy_pin_number > 0) { + // clear the old pin + in_r[proxy_pin_number-1]->setPin(nullptr); + } + proxy_pin_number = e; + if (proxy_pin_number > 0) { + // set the new pin + in_r[proxy_pin_number-1]->setPin(this); + } + return true; + }; + + const uint8_t getExternalNumber() override + { + return proxy_pin_number; + }; - virtual void setIsHoming(const bool m) + void setIsHoming(const bool m) override { homing_mode = m; - } + }; - virtual void setIsProbing(const bool m) + void setIsProbing(const bool m) override { probing_mode = m; - } + }; + // support function for pin change interrupt handling @@ -430,6 +528,11 @@ struct gpioDigitalInputPin : gpioDigitalInput { }; }; + +// forward declare +struct gpioDigitalOutputReader; +extern gpioDigitalOutputReader* const out_r[14]; + /* * gpioDigitalOutput - digital/PWM output base class */ @@ -450,6 +553,8 @@ struct gpioDigitalOutput { virtual float getFrequency(); virtual bool setFrequency(const float); + virtual bool setExternalNumber(const uint8_t); + virtual const uint8_t getExternalNumber(); // functions that take nvObj_t* and return stat_t, NOT overridden @@ -469,7 +574,7 @@ struct gpioDigitalOutput { } return (STAT_OK); }; - + stat_t getPolarity(nvObj_t *nv) { nv->value = getPolarity(); @@ -487,7 +592,7 @@ struct gpioDigitalOutput { return (STAT_OK); }; - virtual stat_t getValue(nvObj_t *nv) + stat_t getValue(nvObj_t *nv) { auto enabled = getEnabled(); if (enabled <= IO_DISABLED) { @@ -505,7 +610,7 @@ struct gpioDigitalOutput { } return (STAT_OK); }; - virtual stat_t setValue(nvObj_t *nv) + stat_t setValue(nvObj_t *nv) { auto enabled = getEnabled(); if (enabled <= IO_DISABLED) { @@ -525,8 +630,92 @@ struct gpioDigitalOutput { return (STAT_OK); }; + stat_t getExternalNumber(nvObj_t *nv) + { + nv->value = getExternalNumber(); + nv->valuetype = TYPE_INT; + return (STAT_OK); + }; + stat_t setExternalNumber(nvObj_t *nv) + { + if ((nv->value < 0) || (nv->value > 14)) { + return (STAT_INPUT_VALUE_RANGE_ERROR); + } + if (!setExternalNumber(nv->value)) { + return STAT_PARAMETER_IS_READ_ONLY; + } + return (STAT_OK); + }; + +}; + + +/* + * gpioDigitalOutputReader - digital output reader class - the "out1" - "outX" objects + */ + +struct gpioDigitalOutputReader { + gpioDigitalOutput* pin; + + // functions for use by other parts of the code + + bool setPin(gpioDigitalOutput* new_pin) { + new_pin = pin; // might be null + return true; + }; + + gpioDigitalOutput* getPin() { + return pin; // might be null + }; + + float getValue() { + if (!pin) { return false; } + return pin->getValue(); + }; + bool setValue(const float v) { + if (!pin) { return false; } + return pin->setValue(v); + }; + + + // functions that take nvObj_t* and return stat_t, NOT overridden + + stat_t getValue(nvObj_t *nv) + { + if (!pin) { + nv->value = 0; + nv->valuetype = TYPE_NULL; // reports back as NULL + return (STAT_OK); + } + return pin->getValue(nv); + }; + stat_t setValue(nvObj_t *nv) + { + if (!pin) { + nv->valuetype = TYPE_NULL; // reports back as NULL + return (STAT_OK); + } + return pin->setValue(nv); + }; }; +// setup the gpioDigitalInputReader objects as extern +extern gpioDigitalOutputReader out1; +extern gpioDigitalOutputReader out2; +extern gpioDigitalOutputReader out3; +extern gpioDigitalOutputReader out4; +extern gpioDigitalOutputReader out5; +extern gpioDigitalOutputReader out6; +extern gpioDigitalOutputReader out7; +extern gpioDigitalOutputReader out8; +extern gpioDigitalOutputReader out9; +extern gpioDigitalOutputReader out10; +extern gpioDigitalOutputReader out11; +extern gpioDigitalOutputReader out12; +extern gpioDigitalOutputReader out13; +extern gpioDigitalOutputReader out14; + + /* * gpioDigitalOutputPin - concrete child of gpioDigitalOutput */ @@ -534,18 +723,23 @@ template struct gpioDigitalOutputPin : gpioDigitalOutput { ioEnabled enabled; // -1=unavailable, 0=disabled, 1=enabled ioPolarity polarity; // 0=normal/active high, 1=inverted/active low + uint8_t proxy_pin_number; // the number used externally for this pin ("in" + proxy_pin_number) Pin_t pin; // In constructor, simply forward all values to the Pin_t template - gpioDigitalOutputPin(const ioEnabled _enabled, const ioPolarity _polarity, T&&... V) : + gpioDigitalOutputPin(const ioEnabled _enabled, const ioPolarity _polarity, const uint8_t _proxy_pin_number, T&&... V) : gpioDigitalOutput{}, enabled{ _enabled }, polarity{ _polarity }, + proxy_pin_number{ _proxy_pin_number }, pin{((polarity == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow), std::forward(V)...} { if (pin.isNull()) { enabled = IO_UNAVAILABLE; + proxy_pin_number = 0; + } else { + setExternalNumber(proxy_pin_number); } }; @@ -601,6 +795,26 @@ struct gpioDigitalOutputPin : gpioDigitalOutput { return true; }; + bool setExternalNumber(const uint8_t e) override + { + if (e == proxy_pin_number) { return true; } + if (proxy_pin_number > 0) { + // clear the old pin + out_r[proxy_pin_number-1]->setPin(nullptr); + } + proxy_pin_number = e; + if (proxy_pin_number > 0) { + // set the new pin + out_r[proxy_pin_number-1]->setPin(this); + } + return true; + }; + + const uint8_t getExternalNumber() override + { + return proxy_pin_number; + }; + }; /* @@ -974,12 +1188,16 @@ stat_t din_get_ac(nvObj_t *nv); // input action stat_t din_set_ac(nvObj_t *nv); stat_t din_get_fn(nvObj_t *nv); // input function stat_t din_set_fn(nvObj_t *nv); +stat_t din_get_in(nvObj_t *nv); // input external number +stat_t din_set_in(nvObj_t *nv); stat_t din_get_input(nvObj_t *nv); stat_t dout_get_en(nvObj_t *nv); // enabled stat_t dout_set_en(nvObj_t *nv); stat_t dout_get_po(nvObj_t *nv); // output sense stat_t dout_set_po(nvObj_t *nv); +stat_t dout_get_out(nvObj_t *nv); // external number +stat_t dout_set_out(nvObj_t *nv); stat_t dout_get_output(nvObj_t *nv); // actual output value (float) stat_t dout_set_output(nvObj_t *nv); @@ -1010,6 +1228,7 @@ stat_t ain_set_p5(nvObj_t *nv); void din_print_ac(nvObj_t *nv); void din_print_fn(nvObj_t *nv); void din_print_in(nvObj_t *nv); + void din_print_state(nvObj_t *nv); void dout_print_en(nvObj_t *nv); void dout_print_po(nvObj_t *nv); diff --git a/g2core/settings/settings_default.h b/g2core/settings/settings_default.h index 000539cd1..298cfc409 100644 --- a/g2core/settings/settings_default.h +++ b/g2core/settings/settings_default.h @@ -952,6 +952,9 @@ #ifndef DI1_FUNCTION #define DI1_FUNCTION INPUT_FUNCTION_NONE #endif +#ifndef DI1_EXTERNAL_NUMBER +#define DI1_EXTERNAL_NUMBER 1 +#endif // Xmax #ifndef DI2_ENABLED @@ -966,6 +969,9 @@ #ifndef DI2_FUNCTION #define DI2_FUNCTION INPUT_FUNCTION_NONE #endif +#ifndef DI2_EXTERNAL_NUMBER +#define DI2_EXTERNAL_NUMBER 2 +#endif // Ymin #ifndef DI3_ENABLED @@ -980,6 +986,9 @@ #ifndef DI3_FUNCTION #define DI3_FUNCTION INPUT_FUNCTION_NONE #endif +#ifndef DI3_EXTERNAL_NUMBER +#define DI3_EXTERNAL_NUMBER 3 +#endif // Ymax #ifndef DI4_ENABLED @@ -994,6 +1003,9 @@ #ifndef DI4_FUNCTION #define DI4_FUNCTION INPUT_FUNCTION_NONE #endif +#ifndef DI4_EXTERNAL_NUMBER +#define DI4_EXTERNAL_NUMBER 4 +#endif // Zmin #ifndef DI5_ENABLED @@ -1008,6 +1020,9 @@ #ifndef DI5_FUNCTION #define DI5_FUNCTION INPUT_FUNCTION_PROBE #endif +#ifndef DI5_EXTERNAL_NUMBER +#define DI5_EXTERNAL_NUMBER 5 +#endif // Zmax #ifndef DI6_ENABLED @@ -1022,6 +1037,9 @@ #ifndef DI6_FUNCTION #define DI6_FUNCTION INPUT_FUNCTION_NONE #endif +#ifndef DI6_EXTERNAL_NUMBER +#define DI6_EXTERNAL_NUMBER 6 +#endif // Amin #ifndef DI7_ENABLED @@ -1036,6 +1054,9 @@ #ifndef DI7_FUNCTION #define DI7_FUNCTION INPUT_FUNCTION_NONE #endif +#ifndef DI7_EXTERNAL_NUMBER +#define DI7_EXTERNAL_NUMBER 7 +#endif // Amax #ifndef DI8_ENABLED @@ -1050,6 +1071,9 @@ #ifndef DI8_FUNCTION #define DI8_FUNCTION INPUT_FUNCTION_NONE #endif +#ifndef DI8_EXTERNAL_NUMBER +#define DI8_EXTERNAL_NUMBER 8 +#endif // Safety line #ifndef DI9_ENABLED @@ -1064,6 +1088,9 @@ #ifndef DI9_FUNCTION #define DI9_FUNCTION INPUT_FUNCTION_NONE #endif +#ifndef DI9_EXTERNAL_NUMBER +#define DI9_EXTERNAL_NUMBER 9 +#endif #ifndef DI10_ENABLED #define DI10_ENABLED IO_ENABLED @@ -1077,6 +1104,9 @@ #ifndef DI10_FUNCTION #define DI10_FUNCTION INPUT_FUNCTION_NONE #endif +#ifndef DI10_EXTERNAL_NUMBER +#define DI10_EXTERNAL_NUMBER 10 +#endif #ifndef DI11_ENABLED #define DI11_ENABLED IO_ENABLED @@ -1090,6 +1120,9 @@ #ifndef DI11_FUNCTION #define DI11_FUNCTION INPUT_FUNCTION_NONE #endif +#ifndef DI11_EXTERNAL_NUMBER +#define DI11_EXTERNAL_NUMBER 11 +#endif #ifndef DI12_ENABLED #define DI12_ENABLED IO_ENABLED @@ -1103,6 +1136,9 @@ #ifndef DI12_FUNCTION #define DI12_FUNCTION INPUT_FUNCTION_NONE #endif +#ifndef DI12_EXTERNAL_NUMBER +#define DI12_EXTERNAL_NUMBER 12 +#endif // DIGITAL OUTPUTS - Currently these are hard-wired to extruders @@ -1113,6 +1149,9 @@ #ifndef DO1_POLARITY #define DO1_POLARITY IO_ACTIVE_HIGH #endif +#ifndef DO1_EXTERNAL_NUMBER +#define DO1_EXTERNAL_NUMBER 1 +#endif //Extruder2_PWM #ifndef DO2_ENABLED @@ -1121,6 +1160,9 @@ #ifndef DO2_POLARITY #define DO2_POLARITY IO_ACTIVE_HIGH #endif +#ifndef DO2_EXTERNAL_NUMBER +#define DO2_EXTERNAL_NUMBER 2 +#endif //Fan1A_PWM #ifndef DO3_ENABLED @@ -1129,6 +1171,9 @@ #ifndef DO3_POLARITY #define DO3_POLARITY IO_ACTIVE_HIGH #endif +#ifndef DO3_EXTERNAL_NUMBER +#define DO3_EXTERNAL_NUMBER 3 +#endif //Fan1B_PWM #ifndef DO4_ENABLED @@ -1137,6 +1182,9 @@ #ifndef DO4_POLARITY #define DO4_POLARITY IO_ACTIVE_HIGH #endif +#ifndef DO4_EXTERNAL_NUMBER +#define DO4_EXTERNAL_NUMBER 4 +#endif #ifndef DO5_ENABLED #define DO5_ENABLED IO_ENABLED @@ -1144,24 +1192,39 @@ #ifndef DO5_POLARITY #define DO5_POLARITY IO_ACTIVE_HIGH #endif +#ifndef DO5_EXTERNAL_NUMBER +#define DO5_EXTERNAL_NUMBER 5 +#endif + #ifndef DO6_ENABLED #define DO6_ENABLED IO_ENABLED #endif #ifndef DO6_POLARITY #define DO6_POLARITY IO_ACTIVE_HIGH #endif +#ifndef DO6_EXTERNAL_NUMBER +#define DO6_EXTERNAL_NUMBER 6 +#endif + #ifndef DO7_ENABLED #define DO7_ENABLED IO_ENABLED #endif #ifndef DO7_POLARITY #define DO7_POLARITY IO_ACTIVE_HIGH #endif +#ifndef DO7_EXTERNAL_NUMBER +#define DO7_EXTERNAL_NUMBER 7 +#endif + #ifndef DO8_ENABLED #define DO8_ENABLED IO_ENABLED #endif #ifndef DO8_POLARITY #define DO8_POLARITY IO_ACTIVE_HIGH #endif +#ifndef DO8_EXTERNAL_NUMBER +#define DO8_EXTERNAL_NUMBER 8 +#endif //SAFEin (Output) signal #ifndef DO9_ENABLED @@ -1170,6 +1233,9 @@ #ifndef DO9_POLARITY #define DO9_POLARITY IO_ACTIVE_HIGH #endif +#ifndef DO9_EXTERNAL_NUMBER +#define DO9_EXTERNAL_NUMBER 9 +#endif #ifndef DO10_ENABLED #define DO10_ENABLED IO_ENABLED @@ -1177,6 +1243,9 @@ #ifndef DO10_POLARITY #define DO10_POLARITY IO_ACTIVE_HIGH #endif +#ifndef DO10_EXTERNAL_NUMBER +#define DO10_EXTERNAL_NUMBER 10 +#endif //Header Bed FET #ifndef DO11_ENABLED @@ -1185,6 +1254,9 @@ #ifndef DO11_POLARITY #define DO11_POLARITY IO_ACTIVE_HIGH #endif +#ifndef DO11_EXTERNAL_NUMBER +#define DO11_EXTERNAL_NUMBER 11 +#endif //Indicator_LED #ifndef DO12_ENABLED @@ -1193,6 +1265,9 @@ #ifndef DO12_POLARITY #define DO12_POLARITY IO_ACTIVE_HIGH #endif +#ifndef DO12_EXTERNAL_NUMBER +#define DO12_EXTERNAL_NUMBER 12 +#endif #ifndef DO13_ENABLED #define DO13_ENABLED IO_ENABLED @@ -1200,6 +1275,9 @@ #ifndef DO13_POLARITY #define DO13_POLARITY IO_ACTIVE_HIGH #endif +#ifndef DO13_EXTERNAL_NUMBER +#define DO13_EXTERNAL_NUMBER 13 +#endif // foind in gpio.h: // #ifndef AI1_TYPE From 4a86b9d66074b5cd9d799effa3e8953c2ca69de7 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Mon, 26 Feb 2018 18:40:58 -0600 Subject: [PATCH 172/193] Fixing gQuintic gpio configuration for new settings --- g2core/board/gquintic/board_gpio.cpp | 50 ++++++++++++++-------------- 1 file changed, 25 insertions(+), 25 deletions(-) diff --git a/g2core/board/gquintic/board_gpio.cpp b/g2core/board/gquintic/board_gpio.cpp index 1ee6d9a95..2d3183cef 100644 --- a/g2core/board/gquintic/board_gpio.cpp +++ b/g2core/board/gquintic/board_gpio.cpp @@ -56,35 +56,35 @@ /**** Setup Actual Objects ****/ -gpioDigitalInputPin> din1 {DI1_ENABLED, DI1_POLARITY, 1}; -gpioDigitalInputPin> din2 {DI2_ENABLED, DI2_POLARITY, 2}; -gpioDigitalInputPin> din3 {DI3_ENABLED, DI3_POLARITY, 3}; -gpioDigitalInputPin> din4 {DI4_ENABLED, DI4_POLARITY, 4}; -gpioDigitalInputPin> din5 {DI5_ENABLED, DI5_POLARITY, 5}; -gpioDigitalInputPin> din6 {DI6_ENABLED, DI6_POLARITY, 6}; -gpioDigitalInputPin> din7 {DI7_ENABLED, DI7_POLARITY, 7}; -gpioDigitalInputPin> din8 {DI8_ENABLED, DI8_POLARITY, 8}; -gpioDigitalInputPin> din9 {DI9_ENABLED, DI9_POLARITY, 9}; -// gpioDigitalInputPin> din10 {DI10ENABLEDE, DI10_POLARITY, 10}; -// gpioDigitalInputPin> din11 {DI11ENABLEDE, DI11_POLARITY, 11}; -// gpioDigitalInputPin> din12 {DI12ENABLEDE, DI12_POLARITY, 12}; +gpioDigitalInputPin> din1 {DI1_ENABLED, DI1_POLARITY, 1, DI1_EXTERNAL_NUMBER}; +gpioDigitalInputPin> din2 {DI2_ENABLED, DI2_POLARITY, 2, DI2_EXTERNAL_NUMBER}; +gpioDigitalInputPin> din3 {DI3_ENABLED, DI3_POLARITY, 3, DI3_EXTERNAL_NUMBER}; +gpioDigitalInputPin> din4 {DI4_ENABLED, DI4_POLARITY, 4, DI4_EXTERNAL_NUMBER}; +gpioDigitalInputPin> din5 {DI5_ENABLED, DI5_POLARITY, 5, DI5_EXTERNAL_NUMBER}; +gpioDigitalInputPin> din6 {DI6_ENABLED, DI6_POLARITY, 6, DI6_EXTERNAL_NUMBER}; +gpioDigitalInputPin> din7 {DI7_ENABLED, DI7_POLARITY, 7, DI7_EXTERNAL_NUMBER}; +gpioDigitalInputPin> din8 {DI8_ENABLED, DI8_POLARITY, 8, DI8_EXTERNAL_NUMBER}; +gpioDigitalInputPin> din9 {DI9_ENABLED, DI9_POLARITY, 9, DI9_EXTERNAL_NUMBER}; +// gpioDigitalInputPin> din10 {DI10ENABLEDE, DI10_POLARITY, 10, DI10_EXTERNAL_NUMBER}; +// gpioDigitalInputPin> din11 {DI11ENABLEDE, DI11_POLARITY, 11, DI11_EXTERNAL_NUMBER}; +// gpioDigitalInputPin> din12 {DI12ENABLEDE, DI12_POLARITY, 12, DI12_EXTERNAL_NUMBER}; gpioDigitalInput* const d_in[] = {&din1, &din2, &din3, &din4, &din5, &din6, &din7, &din8, &din9}; -gpioDigitalOutputPin> dout1 { DO1_ENABLED, DO1_POLARITY, (uint32_t)200000 }; -gpioDigitalOutputPin> dout2 { DO2_ENABLED, DO2_POLARITY, (uint32_t)200000 }; -gpioDigitalOutputPin> dout3 { DO3_ENABLED, DO3_POLARITY, (uint32_t)200000 }; -gpioDigitalOutputPin> dout4 { DO4_ENABLED, DO4_POLARITY, (uint32_t)200000 }; -gpioDigitalOutputPin> dout5 { DO5_ENABLED, DO5_POLARITY, (uint32_t)200000 }; -gpioDigitalOutputPin> dout6 { DO6_ENABLED, DO6_POLARITY, (uint32_t)200000 }; -gpioDigitalOutputPin> dout7 { DO7_ENABLED, DO7_POLARITY, (uint32_t)200000 }; -gpioDigitalOutputPin> dout8 { DO8_ENABLED, DO8_POLARITY, (uint32_t)200000 }; -gpioDigitalOutputPin> dout9 { DO9_ENABLED, DO9_POLARITY, (uint32_t)200000 }; -gpioDigitalOutputPin> dout10 { DO10_ENABLED, DO10_POLARITY, (uint32_t)200000 }; -gpioDigitalOutputPin> dout11 { DO11_ENABLED, DO11_POLARITY, (uint32_t)200000 }; -gpioDigitalOutputPin> dout12 { DO12_ENABLED, DO12_POLARITY, (uint32_t)200000 }; -gpioDigitalOutputPin> dout13 { DO13_ENABLED, DO13_POLARITY, (uint32_t)200000 }; +gpioDigitalOutputPin> dout1 { DO1_ENABLED, DO1_POLARITY, DO1_EXTERNAL_NUMBER, (uint32_t)200000 }; +gpioDigitalOutputPin> dout2 { DO2_ENABLED, DO2_POLARITY, DO2_EXTERNAL_NUMBER, (uint32_t)200000 }; +gpioDigitalOutputPin> dout3 { DO3_ENABLED, DO3_POLARITY, DO3_EXTERNAL_NUMBER, (uint32_t)200000 }; +gpioDigitalOutputPin> dout4 { DO4_ENABLED, DO4_POLARITY, DO4_EXTERNAL_NUMBER, (uint32_t)200000 }; +gpioDigitalOutputPin> dout5 { DO5_ENABLED, DO5_POLARITY, DO5_EXTERNAL_NUMBER, (uint32_t)200000 }; +gpioDigitalOutputPin> dout6 { DO6_ENABLED, DO6_POLARITY, DO6_EXTERNAL_NUMBER, (uint32_t)200000 }; +gpioDigitalOutputPin> dout7 { DO7_ENABLED, DO7_POLARITY, DO7_EXTERNAL_NUMBER, (uint32_t)200000 }; +gpioDigitalOutputPin> dout8 { DO8_ENABLED, DO8_POLARITY, DO8_EXTERNAL_NUMBER, (uint32_t)200000 }; +gpioDigitalOutputPin> dout9 { DO9_ENABLED, DO9_POLARITY, DO9_EXTERNAL_NUMBER, (uint32_t)200000 }; +gpioDigitalOutputPin> dout10 { DO10_ENABLED, DO10_POLARITY, DO10_EXTERNAL_NUMBER, (uint32_t)200000 }; +gpioDigitalOutputPin> dout11 { DO11_ENABLED, DO11_POLARITY, DO11_EXTERNAL_NUMBER, (uint32_t)200000 }; +gpioDigitalOutputPin> dout12 { DO12_ENABLED, DO12_POLARITY, DO12_EXTERNAL_NUMBER, (uint32_t)200000 }; +gpioDigitalOutputPin> dout13 { DO13_ENABLED, DO13_POLARITY, DO13_EXTERNAL_NUMBER, (uint32_t)200000 }; gpioDigitalOutput* const d_out[] = {&dout1, &dout2, &dout3, &dout4, &dout5, &dout6, &dout7, &dout8, &dout9, &dout10, &dout11, &dout12, &dout13}; From 865dd561efdfc3ea3a6bbf9de90596356aaa4d4c Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Mon, 26 Feb 2018 18:41:31 -0600 Subject: [PATCH 173/193] Add gQuadratic rev C (need to fix motors still) --- g2core/board/gquadratic.mk | 6 + g2core/board/gquadratic/board_gpio.cpp | 35 +-- g2core/board/gquadratic/board_gpio.h | 23 +- g2core/board/gquadratic/board_xio.cpp | 1 + g2core/board/gquadratic/board_xio.h | 2 +- g2core/board/gquadratic/gquadratic-b-pinout.h | 6 +- g2core/board/gquadratic/gquadratic-c-pinout.h | 205 ++++++++++++++++++ .../board/gquadratic/motate_pin_assignments.h | 15 +- 8 files changed, 235 insertions(+), 58 deletions(-) create mode 100644 g2core/board/gquadratic/gquadratic-c-pinout.h diff --git a/g2core/board/gquadratic.mk b/g2core/board/gquadratic.mk index 9527cdc11..c426b7cb4 100755 --- a/g2core/board/gquadratic.mk +++ b/g2core/board/gquadratic.mk @@ -18,6 +18,12 @@ ifeq ("$(BOARD)","gquadratic-b") DEVICE_DEFINES += SETTINGS_FILE=${SETTINGS_FILE} endif +ifeq ("$(BOARD)","gquadratic-c") + BASE_BOARD=gquadratic + DEVICE_DEFINES += MOTATE_BOARD="gquadratic-c" + DEVICE_DEFINES += SETTINGS_FILE=${SETTINGS_FILE} +endif + ########## # The general gquadratic BASE_BOARD. diff --git a/g2core/board/gquadratic/board_gpio.cpp b/g2core/board/gquadratic/board_gpio.cpp index 5033c3f10..614f4e0e6 100644 --- a/g2core/board/gquadratic/board_gpio.cpp +++ b/g2core/board/gquadratic/board_gpio.cpp @@ -56,37 +56,18 @@ /**** Setup Actual Objects ****/ -gpioDigitalInputPin> din1 {DI1_ENABLED, DI1_POLARITY, 1}; -gpioDigitalInputPin> din2 {DI2_ENABLED, DI2_POLARITY, 2}; -gpioDigitalInputPin> din3 {DI3_ENABLED, DI3_POLARITY, 3}; -gpioDigitalInputPin> din4 {DI4_ENABLED, DI4_POLARITY, 4}; -gpioDigitalInputPin> din5 {DI5_ENABLED, DI5_POLARITY, 5}; -gpioDigitalInputPin> din6 {DI6_ENABLED, DI6_POLARITY, 6}; -gpioDigitalInputPin> din7 {DI7_ENABLED, DI7_POLARITY, 7}; -gpioDigitalInputPin> din8 {DI8_ENABLED, DI8_POLARITY, 8}; -gpioDigitalInputPin> din9 {DI9_ENABLED, DI9_POLARITY, 9}; -// gpioDigitalInputPin> din10 {DI10ENABLEDE, DI10_POLARITY, 10}; -// gpioDigitalInputPin> din11 {DI11ENABLEDE, DI11_POLARITY, 11}; -// gpioDigitalInputPin> din12 {DI12ENABLEDE, DI12_POLARITY, 12}; +gpioDigitalInputPin> din1 {DI1_ENABLED, DI1_POLARITY, 1, DI1_EXTERNAL_NUMBER}; +gpioDigitalInputPin> din2 {DI2_ENABLED, DI2_POLARITY, 2, DI2_EXTERNAL_NUMBER}; +gpioDigitalInputPin> din3 {DI3_ENABLED, DI3_POLARITY, 3, DI3_EXTERNAL_NUMBER}; +gpioDigitalInputPin> din4 {DI4_ENABLED, DI4_POLARITY, 4, DI4_EXTERNAL_NUMBER}; -gpioDigitalOutputPin> dout1 { DO1_ENABLED, DO1_POLARITY, (uint32_t)200000 }; -gpioDigitalOutputPin> dout2 { DO2_ENABLED, DO2_POLARITY, (uint32_t)200000 }; -gpioDigitalOutputPin> dout3 { DO3_ENABLED, DO3_POLARITY, (uint32_t)200000 }; -gpioDigitalOutputPin> dout4 { DO4_ENABLED, DO4_POLARITY, (uint32_t)200000 }; -gpioDigitalOutputPin> dout5 { DO5_ENABLED, DO5_POLARITY, (uint32_t)200000 }; -gpioDigitalOutputPin> dout6 { DO6_ENABLED, DO6_POLARITY, (uint32_t)200000 }; -gpioDigitalOutputPin> dout7 { DO7_ENABLED, DO7_POLARITY, (uint32_t)200000 }; -gpioDigitalOutputPin> dout8 { DO8_ENABLED, DO8_POLARITY, (uint32_t)200000 }; -gpioDigitalOutputPin> dout9 { DO9_ENABLED, DO9_POLARITY, (uint32_t)200000 }; -gpioDigitalOutputPin> dout10 { DO10_ENABLED, DO10_POLARITY, (uint32_t)200000 }; -gpioDigitalOutputPin> dout11 { DO11_ENABLED, DO11_POLARITY, (uint32_t)200000 }; -gpioDigitalOutputPin> dout12 { DO12_ENABLED, DO12_POLARITY, (uint32_t)200000 }; -gpioDigitalOutputPin> dout13 { DO13_ENABLED, DO13_POLARITY, (uint32_t)200000 }; +gpioDigitalOutputPin> dout1 { DO1_ENABLED, DO1_POLARITY, DO1_EXTERNAL_NUMBER, (uint32_t)200000 }; +gpioDigitalOutputPin> dout2 { DO2_ENABLED, DO2_POLARITY, DO2_EXTERNAL_NUMBER, (uint32_t)200000 }; /**** Setup Arrays - these are extern and MUST match the board_gpio.h ****/ -gpioDigitalInput* const d_in[] = {&din1, &din2, &din3, &din4, &din5, &din6, &din7, &din8, &din9}; -gpioDigitalOutput* const d_out[] = {&dout1, &dout2, &dout3, &dout4, &dout5, &dout6, &dout7, &dout8, &dout9, &dout10, &dout11, &dout12, &dout13}; +gpioDigitalInput* const d_in[] = {&din1, &din2, &din3, &din4}; +gpioDigitalOutput* const d_out[] = {&dout1, &dout2}; // not yet used // gpioAnalogInput* a_in[A_IN_CHANNELS]; // gpioAnalogOutput* a_out[A_OUT_CHANNELS]; diff --git a/g2core/board/gquadratic/board_gpio.h b/g2core/board/gquadratic/board_gpio.h index 25a1cddcd..c596fc545 100644 --- a/g2core/board/gquadratic/board_gpio.h +++ b/g2core/board/gquadratic/board_gpio.h @@ -36,8 +36,8 @@ */ //--- change as required for board and switch hardware ---// -#define D_IN_CHANNELS 9 // v9 // number of digital inputs supported -#define D_OUT_CHANNELS 13 // number of digital outputs supported +#define D_IN_CHANNELS 4 // number of digital inputs supported +#define D_OUT_CHANNELS 2 // number of digital outputs supported #define A_IN_CHANNELS 0 // number of analog inputs supported #define A_OUT_CHANNELS 0 // number of analog outputs supported @@ -63,28 +63,9 @@ extern gpioDigitalInputPin> din1; extern gpioDigitalInputPin> din2; extern gpioDigitalInputPin> din3; extern gpioDigitalInputPin> din4; -extern gpioDigitalInputPin> din5; -extern gpioDigitalInputPin> din6; -extern gpioDigitalInputPin> din7; -extern gpioDigitalInputPin> din8; -extern gpioDigitalInputPin> din9; -// extern gpioDigitalInputPin> din10; -// extern gpioDigitalInputPin> din11; -// extern gpioDigitalInputPin> din12; extern gpioDigitalOutputPin> dout1; extern gpioDigitalOutputPin> dout2; -extern gpioDigitalOutputPin> dout3; -extern gpioDigitalOutputPin> dout4; -extern gpioDigitalOutputPin> dout5; -extern gpioDigitalOutputPin> dout6; -extern gpioDigitalOutputPin> dout7; -extern gpioDigitalOutputPin> dout8; -extern gpioDigitalOutputPin> dout9; -extern gpioDigitalOutputPin> dout10; -extern gpioDigitalOutputPin> dout11; -extern gpioDigitalOutputPin> dout12; -extern gpioDigitalOutputPin> dout13; #endif // End of include guard: BOARD_GPIO_H_ONCE diff --git a/g2core/board/gquadratic/board_xio.cpp b/g2core/board/gquadratic/board_xio.cpp index c48356be1..077df084d 100755 --- a/g2core/board/gquadratic/board_xio.cpp +++ b/g2core/board/gquadratic/board_xio.cpp @@ -71,6 +71,7 @@ void board_hardware_init(void) // called 1st #if XIO_HAS_USB // Init USB usb.attach(); + usb.handleVbusChange(true); #endif // XIO_HAS_USB } diff --git a/g2core/board/gquadratic/board_xio.h b/g2core/board/gquadratic/board_xio.h index 6055d4611..659f68a4a 100755 --- a/g2core/board/gquadratic/board_xio.h +++ b/g2core/board/gquadratic/board_xio.h @@ -36,7 +36,7 @@ #include "MotateUSB.h" #include "MotateUSBCDC.h" -typedef Motate::USBDeviceHardwareBus> USBDeviceHardware_t; +typedef Motate::USBDeviceHardwareVBus> USBDeviceHardware_t; #if USB_SERIAL_PORTS_EXPOSED == 1 typedef Motate::USBDevice< USBDeviceHardware_t, Motate::USBCDC > XIOUSBDevice_t; diff --git a/g2core/board/gquadratic/gquadratic-b-pinout.h b/g2core/board/gquadratic/gquadratic-b-pinout.h index 6eab01841..7eb8946bb 100755 --- a/g2core/board/gquadratic/gquadratic-b-pinout.h +++ b/g2core/board/gquadratic/gquadratic-b-pinout.h @@ -2,8 +2,8 @@ * gquadratic-b-pinout.h - board pinout specification * This file is part of the g2core project * - * Copyright (c) 2016 Robert Giseburt - * Copyright (c) 2016 Alden S. Hart Jr. + * Copyright (c) 2016-2018 Robert Giseburt + * Copyright (c) 2016-2018 Alden S. Hart Jr. * * This file is part of the Motate Library. * @@ -108,6 +108,8 @@ #define OUTPUT12_PWM 0 // Unused #define OUTPUT13_PWM 0 // Unused +#define QUADRATIC_REVISION 'B' + namespace Motate { // Arduino pin name & function diff --git a/g2core/board/gquadratic/gquadratic-c-pinout.h b/g2core/board/gquadratic/gquadratic-c-pinout.h new file mode 100644 index 000000000..dd8fd42f5 --- /dev/null +++ b/g2core/board/gquadratic/gquadratic-c-pinout.h @@ -0,0 +1,205 @@ +/* + * gquadratic-c-pinout.h - board pinout specification + * This file is part of the g2core project + * + * Copyright (c) 2018 Robert Giseburt + * Copyright (c) 2018 Alden S. Hart Jr. + * + * This file is part of the Motate Library. + * + * This file ("the software") is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License, version 2 as published by the + * Free Software Foundation. You should have received a copy of the GNU General Public + * License, version 2 along with the software. If not, see . + * + * As a special exception, you may use this file as part of a software library without + * restriction. Specifically, if other files instantiate templates or use macros or + * inline functions from this file, or you compile this file and link it with other + * files to produce an executable, this file does not by itself cause the resulting + * executable to be covered by the GNU General Public License. This exception does not + * however invalidate any other reasons why the executable file might be covered by the + * GNU General Public License. + * + * THE SOFTWARE IS DISTRIBUTED IN THE HOPE THAT IT WILL BE USEFUL, BUT WITHOUT ANY + * WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES + * OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT + * SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF + * OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + * + */ + +#ifndef GQUADRATIC_C_PINOUT_H +#define GQUADRATIC_C_PINOUT_H + +/* + * USAGE NOTES + * + * Read this first: + * https://github.com/synthetos/g2/wiki/Adding-a-new-G2-board-(or-revision)-to-G2#making-a-new-pin-assignment + * + * USAGE: + * + * This file is lays out all the pin capabilities of the SAM3X8C organized by pin number. + * Each pin has its associated functions listed at the bottom of the file, and is essentially + * immutable for each processor. + * + * To use, assign Motate pin numbers to the first value in the _MAKE_MOTATE_PIN() macro. + * ALL PINS MUST BE ASSIGNED A NUMBER, even if they are not used. There will NOT be a + * code-size or speed penalty for unused pins, but the WILL be a compiler-failure for + * unassigned pins. This new restriction allows for simplification of linkages deep in + * Motate. + */ +/* See motate_pin_assignments.h for pin names to be used int he rest of the G2 code. + * EXAMPLES: + * + * *** Vanilla pin example *** + * + * _MAKE_MOTATE_PIN(4, A, 'A', 27); // SPI0_SCKPinNumber + * + * This assigns Motate pin 4 to Port A, pin 27 (A27) + * Look in motate_pin_assignments.h to see that this is kSPI_SCKPinNumber + * + * ** Other pin functions *** + * + * Please look in /platform/atmel_sam/motate_chip_pin_functions.h + */ + + +#include + +// We don't have all of the inputs, so we have to indicate as much: +#define INPUT1_AVAILABLE 1 +#define INPUT2_AVAILABLE 1 +#define INPUT3_AVAILABLE 1 +#define INPUT4_AVAILABLE 1 +#define INPUT5_AVAILABLE 0 +#define INPUT6_AVAILABLE 0 +#define INPUT7_AVAILABLE 0 +#define INPUT8_AVAILABLE 0 +#define INPUT9_AVAILABLE 0 +#define INPUT10_AVAILABLE 0 +#define INPUT11_AVAILABLE 0 +#define INPUT12_AVAILABLE 0 +#define INPUT13_AVAILABLE 0 + +#define XIO_HAS_USB 1 +#define XIO_HAS_UART 1 +#define XIO_HAS_SPI 0 +#define XIO_HAS_I2C 0 + +#define TEMPERATURE_OUTPUT_ON 0 // NO ADC yet + +// Some pins, if the PWM capability is turned on, it will cause timer conflicts. +// So we have to explicitly enable them as PWM pins. +// Generated with: +// perl -e 'for($i=1;$i<14;$i++) { print "#define OUTPUT${i}_PWM 0\n";}' +#define OUTPUT1_PWM 1 // TC0.0 +#define OUTPUT2_PWM 1 // PWM0.0 +#define OUTPUT3_PWM 1 // TC0.1 +#define OUTPUT4_PWM 1 // PWM1.3 +#define OUTPUT5_PWM 0 // unused +#define OUTPUT6_PWM 0 // unused +#define OUTPUT7_PWM 0 // unused +#define OUTPUT8_PWM 0 // unused +#define OUTPUT9_PWM 0 // unused +#define OUTPUT10_PWM 0 // unused +#define OUTPUT11_PWM 0 // unused +#define OUTPUT12_PWM 0 // Unused +#define OUTPUT13_PWM 0 // Unused + +#define QUADRATIC_REVISION 'C' + +namespace Motate { + +// Arduino pin name & function +_MAKE_MOTATE_PIN(kOutput1_PinNumber, 'A', 0); // TC0.0 or PWM0 +_MAKE_MOTATE_PIN(kOutput2_PinNumber, 'A', 1); // TC0.1 or PWM1 +_MAKE_MOTATE_PIN(kUnassigned1, 'A', 2); // PWM1 +_MAKE_MOTATE_PIN(kI2C1_SDAPinNumber, 'A', 3); // +_MAKE_MOTATE_PIN(kI2C1_SCLPinNumber, 'A', 4); // +_MAKE_MOTATE_PIN(kUnassigned2, 'A', 5); // +_MAKE_MOTATE_PIN(kUnassigned3, 'A', 6); // Missing in 100-pin package +_MAKE_MOTATE_PIN(kUnassigned4, 'A', 7); // +_MAKE_MOTATE_PIN(kUnassigned5, 'A', 8); // +_MAKE_MOTATE_PIN(kSerial_RXPinNumber, 'A', 9); // +_MAKE_MOTATE_PIN(kSerial_TXPinNumber, 'A', 10); // +_MAKE_MOTATE_PIN(kSocket1_StepPinNumber, 'A', 11); // +_MAKE_MOTATE_PIN(kUnassigned6, 'A', 12); // +_MAKE_MOTATE_PIN(kUnassigned7, 'A', 13); // +_MAKE_MOTATE_PIN(kUnassigned8, 'A', 14); // +_MAKE_MOTATE_PIN(kUnassigned9, 'A', 15); // +_MAKE_MOTATE_PIN(kUnassigned10, 'A', 16); // +_MAKE_MOTATE_PIN(kUnassigned11, 'A', 17); // +_MAKE_MOTATE_PIN(kUnassigned12, 'A', 18); // +_MAKE_MOTATE_PIN(kUnassigned13, 'A', 19); // +_MAKE_MOTATE_PIN(kUnassigned14, 'A', 20); // +_MAKE_MOTATE_PIN(kUnassigned15, 'A', 21); // +_MAKE_MOTATE_PIN(kUnassigned16, 'A', 22); // +_MAKE_MOTATE_PIN(kUnassigned17, 'A', 23); // +_MAKE_MOTATE_PIN(kUnassigned18, 'A', 24); // DIAG0 +_MAKE_MOTATE_PIN(kUnassigned19, 'A', 25); // +_MAKE_MOTATE_PIN(kSocket1_DirPinNumber, 'A', 26); // +_MAKE_MOTATE_PIN(kUnassigned20, 'A', 27); // TC2.1 +_MAKE_MOTATE_PIN(kSerial_CTSPinNumber, 'A', 28); // +_MAKE_MOTATE_PIN(kUnassigned21, 'A', 29); // Missing in 100-pin package +_MAKE_MOTATE_PIN(kServo1_PinNumber, 'A', 30); // PWM2 - kOutput3_PinNumber +_MAKE_MOTATE_PIN(kInput4_PinNumber, 'A', 31); // + +_MAKE_MOTATE_PIN(kUnassigned22, 'B', 0); // +_MAKE_MOTATE_PIN(kUnassigned23, 'B', 1); // +_MAKE_MOTATE_PIN(kSocket3_SPISlaveSelectPinNumber, 'B', 2); // +_MAKE_MOTATE_PIN(kUnassigned24, 'B', 3); // +//_MAKE_MOTATE_PIN( , 'B', 4); // TDI +//_MAKE_MOTATE_PIN( , 'B', 5); // TRACESDO +//_MAKE_MOTATE_PIN( , 'B', 6); // SWDIO +//_MAKE_MOTATE_PIN( , 'B', 7); // SWDCLK +//_MAKE_MOTATE_PIN( , 'B', 8); // XOUT +//_MAKE_MOTATE_PIN( , 'B', 9); // XIN +//_MAKE_MOTATE_PIN( , 'B', 10); // USB_D- +//_MAKE_MOTATE_PIN( , 'B', 11); // USB_D+ +//_MAKE_MOTATE_PIN( , 'B', 12); // ERASE +_MAKE_MOTATE_PIN(kUnassigned25, 'B', 13); // + +_MAKE_MOTATE_PIN(kUSBVBUS_PinNumber, 'D', 0); // USB_VBUS +_MAKE_MOTATE_PIN(kInput1_PinNumber, 'D', 1); // +_MAKE_MOTATE_PIN(kInput2_PinNumber, 'D', 2); // +_MAKE_MOTATE_PIN(kUnassigned26, 'D', 3); // +_MAKE_MOTATE_PIN(kUnassigned27, 'D', 4); // +_MAKE_MOTATE_PIN(kUnassigned28, 'D', 5); // +_MAKE_MOTATE_PIN(kInput3_PinNumber, 'D', 6); // +_MAKE_MOTATE_PIN(kSerial_RTSPinNumber, 'D', 7); // +_MAKE_MOTATE_PIN(kUnassigned29, 'D', 8); // INTERRUPT_OUT +_MAKE_MOTATE_PIN(kUnassigned30, 'D', 9); // +_MAKE_MOTATE_PIN(kUnassigned31, 'D', 10); // +_MAKE_MOTATE_PIN(kLED_RGBWPixelPinNumber, 'D', 11); // PWM0 - kOutput4_PinNumber +_MAKE_MOTATE_PIN(kSocket4_SPISlaveSelectPinNumber, 'D', 12); // +_MAKE_MOTATE_PIN(kSocket2_EnablePinNumber, 'D', 13); // +_MAKE_MOTATE_PIN(kSocket2_StepPinNumber, 'D', 14); // +_MAKE_MOTATE_PIN(kOutputSAFE_PinNumber, 'D', 15); // +_MAKE_MOTATE_PIN(kSocket2_DirPinNumber, 'D', 16); // +_MAKE_MOTATE_PIN(kUnassigned32, 'D', 17); // +_MAKE_MOTATE_PIN(kUnassigned33, 'D', 18); // +_MAKE_MOTATE_PIN(kUnassigned34, 'D', 19); // +_MAKE_MOTATE_PIN(kSPI0_MISOPinNumber, 'D', 20); // +_MAKE_MOTATE_PIN(kSPI0_MOSIPinNumber, 'D', 21); // +_MAKE_MOTATE_PIN(kSPI0_SCKPinNumber, 'D', 22); // +_MAKE_MOTATE_PIN(kUnassigned35, 'D', 23); // Missing in 100-pin package +_MAKE_MOTATE_PIN(kUnassigned36, 'D', 24); // DIAG1 +_MAKE_MOTATE_PIN(kSocket1_SPISlaveSelectPinNumber, 'D', 25); // +_MAKE_MOTATE_PIN(kSocket1_EnablePinNumber, 'D', 26); // +_MAKE_MOTATE_PIN(kSocket2_SPISlaveSelectPinNumber, 'D', 27); // +_MAKE_MOTATE_PIN(kUnassigned37, 'D', 28); // +_MAKE_MOTATE_PIN(kUnassigned38, 'D', 29); // Missing in 100-pin package +_MAKE_MOTATE_PIN(kLEDPWM_PinNumber, 'D', 30); // +_MAKE_MOTATE_PIN(kUnassigned39, 'D', 31); // + +} // namespace Motate + +// We then allow each chip-type to have it's onw function definitions +// that will refer to these pin assignments. +#include "motate_chip_pin_functions.h" + +#endif + +// GQUADRATIC_C_PINOUT_H diff --git a/g2core/board/gquadratic/motate_pin_assignments.h b/g2core/board/gquadratic/motate_pin_assignments.h index 0057a9e4c..6eba44821 100755 --- a/g2core/board/gquadratic/motate_pin_assignments.h +++ b/g2core/board/gquadratic/motate_pin_assignments.h @@ -157,13 +157,14 @@ pin_number kDebug3_PinNumber = -1; // 116; //e Not the out-of-order numbering & pin_number kDebug4_PinNumber = -1; // 114; // END DEBUG PINS -pin_number kLED_USBRXPinNumber = 117; -pin_number kLED_USBTXPinNumber = 118; -pin_number kSD_CardDetectPinNumber = 119; -pin_number kSD_ChipSelectPinNumber = 120; -pin_number kInterlock_InPinNumber = 121; -pin_number kOutputSAFE_PinNumber = 122; // SAFE signal -pin_number kLEDPWM_PinNumber = 123; +pin_number kLED_USBRXPinNumber = 117; +pin_number kLED_USBTXPinNumber = 118; +pin_number kSD_CardDetectPinNumber = -1; +pin_number kSD_ChipSelectPinNumber = -1; +pin_number kUSBVBUS_PinNumber = 119; +pin_number kInterlock_InPinNumber = 121; +pin_number kOutputSAFE_PinNumber = 122; // SAFE signal +pin_number kLEDPWM_PinNumber = 123; pin_number kOutputInterrupt_PinNumber = 124; // to-host interrupt signal pin_number kLED_RGBWPixelPinNumber = 125; // 117; From 10f69bdc1567c2878f85ce2655e5c01bd854dff1 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Thu, 1 Mar 2018 10:16:15 -0600 Subject: [PATCH 174/193] Finishing touches on the qQuadratic board files (fixes to pinouts on rev C) --- g2core/board/gquadratic.mk | 6 +- g2core/board/gquadratic/0_hardware.cpp | 8 ++ g2core/board/gquadratic/board_stepper.cpp | 60 ++++++------- g2core/board/gquadratic/board_stepper.h | 40 ++++----- g2core/board/gquadratic/gquadratic-c-pinout.h | 86 +++++++++---------- g2core/board/gquadratic/hardware.h | 66 +++++--------- .../board/gquadratic/motate_pin_assignments.h | 2 + g2core/board/gquintic/board_stepper.cpp | 4 +- g2core/board/gquintic/hardware.h | 3 +- g2core/boards.mk | 4 +- g2core/settings/settings_axidraw_v3.h | 13 +-- 11 files changed, 134 insertions(+), 158 deletions(-) diff --git a/g2core/board/gquadratic.mk b/g2core/board/gquadratic.mk index c426b7cb4..35837519a 100755 --- a/g2core/board/gquadratic.mk +++ b/g2core/board/gquadratic.mk @@ -31,16 +31,16 @@ endif ifeq ("$(BASE_BOARD)","gquadratic") _BOARD_FOUND = 1 - DEVICE_DEFINES += MOTATE_CONFIG_HAS_USBSERIAL=0 + DEVICE_DEFINES += MOTATE_CONFIG_HAS_USBSERIAL=1 ENABLE_TCM=1 - FIRST_LINK_SOURCES += $(sort $(wildcard ${MOTATE_PATH}/Atmel_sam_common/*.cpp)) $(sort $(wildcard ${MOTATE_PATH}/Atmel_sams70/*.cpp)) + FIRST_LINK_SOURCES += $(sort $(wildcard ${MOTATE_PATH}/Atmel_sam_common/*.cpp)) $(sort $(wildcard ${MOTATE_PATH}/Atmel_sams70/*.cpp) $(wildcard ${BOARD_PATH}/*.cpp)) CHIP = SAMS70N19 export CHIP CHIP_LOWERCASE = sams70n19 BOARD_PATH = ./board/gquadratic - SOURCE_DIRS += ${BOARD_PATH} device/step_dir_driver device/step_dir_hobbyservo device/neopixel + SOURCE_DIRS += ${BOARD_PATH} device/trinamic device/step_dir_hobbyservo device/max31865 device/neopixel PLATFORM_BASE = ${MOTATE_PATH}/platform/atmel_sam include $(PLATFORM_BASE).mk diff --git a/g2core/board/gquadratic/0_hardware.cpp b/g2core/board/gquadratic/0_hardware.cpp index d3674a2ee..2a8fa86c0 100755 --- a/g2core/board/gquadratic/0_hardware.cpp +++ b/g2core/board/gquadratic/0_hardware.cpp @@ -73,12 +73,20 @@ namespace LEDs { } #endif // EXPERIMENTAL_NEOPIXEL_SUPPORT +#if QUADRATIC_REVISION == 'C' +HOT_DATA SPIBus_used_t spiBus; +#endif + /* * hardware_init() - lowest level hardware init */ void hardware_init() { +#if QUADRATIC_REVISION == 'C' + spiBus.init(); +#endif + board_hardware_init(); // external_clk_pin = 0; // Force external clock to 0 for now. diff --git a/g2core/board/gquadratic/board_stepper.cpp b/g2core/board/gquadratic/board_stepper.cpp index bc927558a..cfe461447 100755 --- a/g2core/board/gquadratic/board_stepper.cpp +++ b/g2core/board/gquadratic/board_stepper.cpp @@ -2,8 +2,8 @@ * board_stepper.cpp - board-specific code for stepper.cpp * This file is part of the g2core project * - * Copyright (c) 2016 Alden S. Hart, Jr. - * Copyright (c) 2016 Robert Giseburt + * Copyright (c) 2016-2018 Alden S. Hart, Jr. + * Copyright (c) 2016-2018 Robert Giseburt * * This file ("the software") is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License, version 2 as published by the @@ -29,54 +29,48 @@ #include "board_stepper.h" // These are identical to board_stepper.h, except for the word "extern" -StepDirStepper - motor_1{}; + motor_1 {}; -StepDirStepper - motor_2{}; + motor_2 {}; +#endif // QUADRATIC_REVISION == 'B' -StepDirHobbyServo motor_3; +#if QUADRATIC_REVISION == 'C' +#warning setting up trinamics +// Motate::SPIChipSelectPin motor_1_cs; +HOT_DATA Trinamic2130 + motor_1 {spiBus, Motate::SPIChipSelectPin{}}; -// StepDirStepper< -// Motate::kSocket4_StepPinNumber, -// Motate::kSocket4_DirPinNumber, -// Motate::kSocket4_EnablePinNumber, -// Motate::kSocket4_Microstep_0PinNumber, -// Motate::kSocket4_Microstep_1PinNumber, -// Motate::kSocket4_Microstep_2PinNumber, -// Motate::kSocket4_VrefPinNumber> motor_4 {}; -// -// StepDirStepper< -// Motate::kSocket5_StepPinNumber, -// Motate::kSocket5_DirPinNumber, -// Motate::kSocket5_EnablePinNumber, -// Motate::kSocket5_Microstep_0PinNumber, -// Motate::kSocket5_Microstep_1PinNumber, -// Motate::kSocket5_Microstep_2PinNumber, -// Motate::kSocket5_VrefPinNumber> motor_5 {}; +// Motate::SPIChipSelectPin motor_2_cs; +HOT_DATA Trinamic2130 + motor_2 {spiBus, Motate::SPIChipSelectPin{}}; +#endif // QUADRATIC_REVISION == 'C' -// StepDirStepper< -// Motate::kSocket6_StepPinNumber, -// Motate::kSocket6_DirPinNumber, -// Motate::kSocket6_EnablePinNumber, -// Motate::kSocket6_Microstep_0PinNumber, -// Motate::kSocket6_Microstep_1PinNumber, -// Motate::kSocket6_Microstep_2PinNumber, -// Motate::kSocket6_VrefPinNumber> motor_6 {}; -Stepper* Motors[MOTORS] = {&motor_1, &motor_2, &motor_3}; +HOT_DATA StepDirHobbyServo motor_3; + + +Stepper* const Motors[MOTORS] = {&motor_1, &motor_2, &motor_3}; void board_stepper_init() { for (uint8_t motor = 0; motor < MOTORS; motor++) { Motors[motor]->init(); } diff --git a/g2core/board/gquadratic/board_stepper.h b/g2core/board/gquadratic/board_stepper.h index 6e044efa3..8072ff338 100755 --- a/g2core/board/gquadratic/board_stepper.h +++ b/g2core/board/gquadratic/board_stepper.h @@ -29,9 +29,9 @@ #define BOARD_STEPPER_H_ONCE #include "hardware.h" // for MOTORS -#include "step_dir_driver.h" -#include "step_dir_hobbyservo.h" +#if QUADRATIC_REVISION == 'B' +#include "step_dir_driver.h" extern StepDirStepper motor_2; +#endif // QUADRATIC_REVISION == 'B' - extern StepDirHobbyServo motor_3; +#if QUADRATIC_REVISION == 'C' +#include "tmc2130.h" +extern Trinamic2130 + motor_1; +extern Trinamic2130 + motor_2; +#endif // QUADRATIC_REVISION == 'C' -// extern StepDirStepper< -// Motate::kSocket5_StepPinNumber, -// Motate::kSocket5_DirPinNumber, -// Motate::kSocket5_EnablePinNumber, -// Motate::kSocket5_Microstep_0PinNumber, -// Motate::kSocket5_Microstep_1PinNumber, -// Motate::kSocket5_Microstep_2PinNumber, -// Motate::kSocket5_VrefPinNumber> motor_5; -// -// extern StepDirStepper< -// Motate::kSocket6_StepPinNumber, -// Motate::kSocket6_DirPinNumber, -// Motate::kSocket6_EnablePinNumber, -// Motate::kSocket6_Microstep_0PinNumber, -// Motate::kSocket6_Microstep_1PinNumber, -// Motate::kSocket6_Microstep_2PinNumber, -// Motate::kSocket6_VrefPinNumber> motor_6 {}; +#include "step_dir_hobbyservo.h" +extern StepDirHobbyServo motor_3; -extern Stepper* Motors[MOTORS]; +extern Stepper* const Motors[MOTORS]; void board_stepper_init(); diff --git a/g2core/board/gquadratic/gquadratic-c-pinout.h b/g2core/board/gquadratic/gquadratic-c-pinout.h index dd8fd42f5..8c77c9d35 100644 --- a/g2core/board/gquadratic/gquadratic-c-pinout.h +++ b/g2core/board/gquadratic/gquadratic-c-pinout.h @@ -118,38 +118,38 @@ _MAKE_MOTATE_PIN(kOutput2_PinNumber, 'A', 1); // TC0.1 or PWM1 _MAKE_MOTATE_PIN(kUnassigned1, 'A', 2); // PWM1 _MAKE_MOTATE_PIN(kI2C1_SDAPinNumber, 'A', 3); // _MAKE_MOTATE_PIN(kI2C1_SCLPinNumber, 'A', 4); // -_MAKE_MOTATE_PIN(kUnassigned2, 'A', 5); // -_MAKE_MOTATE_PIN(kUnassigned3, 'A', 6); // Missing in 100-pin package -_MAKE_MOTATE_PIN(kUnassigned4, 'A', 7); // -_MAKE_MOTATE_PIN(kUnassigned5, 'A', 8); // +_MAKE_MOTATE_PIN(kSocket2_StepPinNumber, 'A', 5); // +_MAKE_MOTATE_PIN(kUnassigned2, 'A', 6); // Missing in 100-pin package +_MAKE_MOTATE_PIN(kUnassigned3, 'A', 7); // +_MAKE_MOTATE_PIN(kUnassigned4, 'A', 8); // _MAKE_MOTATE_PIN(kSerial_RXPinNumber, 'A', 9); // _MAKE_MOTATE_PIN(kSerial_TXPinNumber, 'A', 10); // _MAKE_MOTATE_PIN(kSocket1_StepPinNumber, 'A', 11); // -_MAKE_MOTATE_PIN(kUnassigned6, 'A', 12); // -_MAKE_MOTATE_PIN(kUnassigned7, 'A', 13); // -_MAKE_MOTATE_PIN(kUnassigned8, 'A', 14); // -_MAKE_MOTATE_PIN(kUnassigned9, 'A', 15); // -_MAKE_MOTATE_PIN(kUnassigned10, 'A', 16); // -_MAKE_MOTATE_PIN(kUnassigned11, 'A', 17); // -_MAKE_MOTATE_PIN(kUnassigned12, 'A', 18); // -_MAKE_MOTATE_PIN(kUnassigned13, 'A', 19); // -_MAKE_MOTATE_PIN(kUnassigned14, 'A', 20); // -_MAKE_MOTATE_PIN(kUnassigned15, 'A', 21); // -_MAKE_MOTATE_PIN(kUnassigned16, 'A', 22); // -_MAKE_MOTATE_PIN(kUnassigned17, 'A', 23); // -_MAKE_MOTATE_PIN(kUnassigned18, 'A', 24); // DIAG0 -_MAKE_MOTATE_PIN(kUnassigned19, 'A', 25); // +_MAKE_MOTATE_PIN(kUnassigned5, 'A', 12); // +_MAKE_MOTATE_PIN(kUnassigned6, 'A', 13); // +_MAKE_MOTATE_PIN(kUnassigned7, 'A', 14); // +_MAKE_MOTATE_PIN(kUnassigned8, 'A', 15); // +_MAKE_MOTATE_PIN(kUnassigned9, 'A', 16); // +_MAKE_MOTATE_PIN(kUnassigned10, 'A', 17); // +_MAKE_MOTATE_PIN(kUnassigned11, 'A', 18); // +_MAKE_MOTATE_PIN(kUnassigned12, 'A', 19); // +_MAKE_MOTATE_PIN(kUnassigned13, 'A', 20); // +_MAKE_MOTATE_PIN(kUnassigned14, 'A', 21); // +_MAKE_MOTATE_PIN(kUnassigned15, 'A', 22); // +_MAKE_MOTATE_PIN(kUnassigned16, 'A', 23); // +_MAKE_MOTATE_PIN(kInput5_PinNumber, 'A', 24); // DIAG0 +_MAKE_MOTATE_PIN(kUnassigned17, 'A', 25); // _MAKE_MOTATE_PIN(kSocket1_DirPinNumber, 'A', 26); // -_MAKE_MOTATE_PIN(kUnassigned20, 'A', 27); // TC2.1 +_MAKE_MOTATE_PIN(kSocket2_EnablePinNumber, 'A', 27); // TC2.1 _MAKE_MOTATE_PIN(kSerial_CTSPinNumber, 'A', 28); // -_MAKE_MOTATE_PIN(kUnassigned21, 'A', 29); // Missing in 100-pin package -_MAKE_MOTATE_PIN(kServo1_PinNumber, 'A', 30); // PWM2 - kOutput3_PinNumber +_MAKE_MOTATE_PIN(kUnassigned18, 'A', 29); // Missing in 100-pin package +_MAKE_MOTATE_PIN(kServo1_PinNumber, 'A', 30); // PWM2 - kOutput4_PinNumber _MAKE_MOTATE_PIN(kInput4_PinNumber, 'A', 31); // -_MAKE_MOTATE_PIN(kUnassigned22, 'B', 0); // -_MAKE_MOTATE_PIN(kUnassigned23, 'B', 1); // +_MAKE_MOTATE_PIN(kUnassigned19, 'B', 0); // +_MAKE_MOTATE_PIN(kUnassigned20, 'B', 1); // _MAKE_MOTATE_PIN(kSocket3_SPISlaveSelectPinNumber, 'B', 2); // -_MAKE_MOTATE_PIN(kUnassigned24, 'B', 3); // +_MAKE_MOTATE_PIN(kUnassigned21, 'B', 3); // //_MAKE_MOTATE_PIN( , 'B', 4); // TDI //_MAKE_MOTATE_PIN( , 'B', 5); // TRACESDO //_MAKE_MOTATE_PIN( , 'B', 6); // SWDIO @@ -159,40 +159,40 @@ _MAKE_MOTATE_PIN(kUnassigned24, 'B', 3); // //_MAKE_MOTATE_PIN( , 'B', 10); // USB_D- //_MAKE_MOTATE_PIN( , 'B', 11); // USB_D+ //_MAKE_MOTATE_PIN( , 'B', 12); // ERASE -_MAKE_MOTATE_PIN(kUnassigned25, 'B', 13); // +_MAKE_MOTATE_PIN(kUnassigned22, 'B', 13); // _MAKE_MOTATE_PIN(kUSBVBUS_PinNumber, 'D', 0); // USB_VBUS _MAKE_MOTATE_PIN(kInput1_PinNumber, 'D', 1); // _MAKE_MOTATE_PIN(kInput2_PinNumber, 'D', 2); // -_MAKE_MOTATE_PIN(kUnassigned26, 'D', 3); // -_MAKE_MOTATE_PIN(kUnassigned27, 'D', 4); // -_MAKE_MOTATE_PIN(kUnassigned28, 'D', 5); // +_MAKE_MOTATE_PIN(kUnassigned23, 'D', 3); // +_MAKE_MOTATE_PIN(kUnassigned24, 'D', 4); // +_MAKE_MOTATE_PIN(kUnassigned25, 'D', 5); // _MAKE_MOTATE_PIN(kInput3_PinNumber, 'D', 6); // _MAKE_MOTATE_PIN(kSerial_RTSPinNumber, 'D', 7); // -_MAKE_MOTATE_PIN(kUnassigned29, 'D', 8); // INTERRUPT_OUT -_MAKE_MOTATE_PIN(kUnassigned30, 'D', 9); // -_MAKE_MOTATE_PIN(kUnassigned31, 'D', 10); // -_MAKE_MOTATE_PIN(kLED_RGBWPixelPinNumber, 'D', 11); // PWM0 - kOutput4_PinNumber +_MAKE_MOTATE_PIN(kOutput5_PinNumber, 'D', 8); // INTERRUPT_OUT +_MAKE_MOTATE_PIN(kUnassigned26, 'D', 9); // +_MAKE_MOTATE_PIN(kUnassigned27, 'D', 10); // +_MAKE_MOTATE_PIN(kLED_RGBWPixelPinNumber, 'D', 11); // PWM0 - kOutput3_PinNumber _MAKE_MOTATE_PIN(kSocket4_SPISlaveSelectPinNumber, 'D', 12); // -_MAKE_MOTATE_PIN(kSocket2_EnablePinNumber, 'D', 13); // -_MAKE_MOTATE_PIN(kSocket2_StepPinNumber, 'D', 14); // +_MAKE_MOTATE_PIN(kUnassigned28, 'D', 13); // +_MAKE_MOTATE_PIN(kUnassigned29, 'D', 14); // _MAKE_MOTATE_PIN(kOutputSAFE_PinNumber, 'D', 15); // -_MAKE_MOTATE_PIN(kSocket2_DirPinNumber, 'D', 16); // -_MAKE_MOTATE_PIN(kUnassigned32, 'D', 17); // -_MAKE_MOTATE_PIN(kUnassigned33, 'D', 18); // -_MAKE_MOTATE_PIN(kUnassigned34, 'D', 19); // +_MAKE_MOTATE_PIN(kUnassigned30, 'D', 16); // +_MAKE_MOTATE_PIN(kUnassigned31, 'D', 17); // +_MAKE_MOTATE_PIN(kUnassigned32, 'D', 18); // +_MAKE_MOTATE_PIN(kUnassigned33, 'D', 19); // _MAKE_MOTATE_PIN(kSPI0_MISOPinNumber, 'D', 20); // _MAKE_MOTATE_PIN(kSPI0_MOSIPinNumber, 'D', 21); // _MAKE_MOTATE_PIN(kSPI0_SCKPinNumber, 'D', 22); // -_MAKE_MOTATE_PIN(kUnassigned35, 'D', 23); // Missing in 100-pin package -_MAKE_MOTATE_PIN(kUnassigned36, 'D', 24); // DIAG1 +_MAKE_MOTATE_PIN(kUnassigned34, 'D', 23); // Missing in 100-pin package +_MAKE_MOTATE_PIN(kInput6_PinNumber, 'D', 24); // DIAG1 _MAKE_MOTATE_PIN(kSocket1_SPISlaveSelectPinNumber, 'D', 25); // _MAKE_MOTATE_PIN(kSocket1_EnablePinNumber, 'D', 26); // _MAKE_MOTATE_PIN(kSocket2_SPISlaveSelectPinNumber, 'D', 27); // -_MAKE_MOTATE_PIN(kUnassigned37, 'D', 28); // -_MAKE_MOTATE_PIN(kUnassigned38, 'D', 29); // Missing in 100-pin package +_MAKE_MOTATE_PIN(kSocket2_DirPinNumber, 'D', 28); // +_MAKE_MOTATE_PIN(kUnassigned35, 'D', 29); // Missing in 100-pin package _MAKE_MOTATE_PIN(kLEDPWM_PinNumber, 'D', 30); // -_MAKE_MOTATE_PIN(kUnassigned39, 'D', 31); // +_MAKE_MOTATE_PIN(kUnassigned36, 'D', 31); // } // namespace Motate diff --git a/g2core/board/gquadratic/hardware.h b/g2core/board/gquadratic/hardware.h index 9c3b27504..827346fb4 100644 --- a/g2core/board/gquadratic/hardware.h +++ b/g2core/board/gquadratic/hardware.h @@ -29,6 +29,7 @@ */ #include "config.h" +#include "settings.h" #include "error.h" #ifndef HARDWARE_H_ONCE @@ -70,6 +71,11 @@ enum hwPlatform { // ARM specific code start here #include "MotatePins.h" +#if QUADRATIC_REVISION == 'C' +#define MOTOR_1_IS_TRINAMIC +#define MOTOR_2_IS_TRINAMIC +#include "MotateSPI.h" +#endif #include "MotateTimers.h" // for TimerChanel<> and related... #include "MotateServiceCall.h" // for ServiceCall<> @@ -89,43 +95,16 @@ using Motate::OutputPin; #define SYS_ID_DIGITS 12 // actual digits in system ID (up to 16) #define SYS_ID_LEN 24 // total length including dashes and NUL -/************************************************************************************ - **** ARM SAM3X8E SPECIFIC HARDWARE ************************************************* - ************************************************************************************/ - -/**** Resource Assignment via Motate **** - * - * This section defines resource usage for pins, timers, PWM channels, communications - * and other resources. Please refer to /motate/utility/SamPins.h, SamTimers.h and - * other files for pinouts and other configuration details. - * - * Commenting out or #ifdef'ing out definitions below will cause the compiler to - * drop references to these resources from the compiled code. This will reduce - * compiled code size and runtime CPU cycles. E.g. if you are compiling for a 3 motor, - * XYZ axis config commenting out the higher motors and axes here will remove them - * from later code (using the motate .isNull() test). - */ - -/* Interrupt usage and priority - * - * The following interrupts are defined w/indicated priorities - * - * 0 DDA_TIMER (9) for step pulse generation - * 1 DWELL_TIMER (10) for dwell timing - * 2 LOADER software generated interrupt (STIR / SGI) - * 3 Serial read character interrupt - * 4 EXEC software generated interrupt (STIR / SGI) - * 5 Serial write character interrupt - */ - /**** Stepper DDA and dwell timer settings ****/ //#define FREQUENCY_DDA 200000UL // Hz step frequency. Interrupts actually fire at 2x (400 KHz) -#define FREQUENCY_DDA 200000UL // Hz step frequency. Interrupts actually fire at 2x (300 KHz) +#define FREQUENCY_DDA 400000UL // Hz step frequency. Interrupts actually fire at 2x (300 KHz) #define FREQUENCY_DWELL 1000UL #define MIN_SEGMENT_MS ((float)0.125) // S70 can handle much much smaller segements +#define PLANNER_BUFFER_POOL_SIZE (60) + /**** Motate Definitions ****/ // Timer definitions. See stepper.h and other headers for setup @@ -137,14 +116,17 @@ typedef TimerChannel<11, 0> fwd_plan_timer_type; // request exec timer in step pin_number indicator_led_pin_num = Motate::kLEDPWM_PinNumber; static OutputPin IndicatorLed; +/**** SPI Setup ****/ +#if QUADRATIC_REVISION == 'C' +Motate::service_call_number kSPI_ServiceCallNumber = 3; + +typedef Motate::SPIBus SPIBus_used_t; +extern SPIBus_used_t spiBus; + +#endif + /**** Motate Global Pin Allocations ****/ -// static OutputPin spi_ss1_pin; -// static OutputPin spi_ss2_pin; -// static OutputPin spi_ss3_pin; -// static OutputPin spi_ss4_pin; -// static OutputPin spi_ss5_pin; -// static OutputPin spi_ss6_pin; static OutputPin kinen_sync_pin; static OutputPin grbl_reset_pin; @@ -152,14 +134,12 @@ static OutputPin grbl_feedhold_pin; static OutputPin grbl_cycle_start_pin; static OutputPin motor_common_enable_pin; -static OutputPin spindle_enable_pin; -static OutputPin spindle_dir_pin; - -// NOTE: In the v9 and the Due the flood and mist coolants are mapped to a the same pin -// static OutputPin coolant_enable_pin; -static OutputPin flood_enable_pin; -static OutputPin mist_enable_pin; +#define SPINDLE_OUTPUT_NUMBER 1 // drive our primary output as a spindle +#define SPINDLE_ENABLE_OUTPUT_NUMBER 2 // use output 2 as the enable line for the spindle +#define SPINDLE_DIRECTION_OUTPUT_NUMBER 0 // no direction control +#define MIST_ENABLE_OUTPUT_NUMBER 0 // no mist +#define FLOOD_ENABLE_OUTPUT_NUMBER 0 // no flood // Input pins are defined in gpio.cpp /******************************** diff --git a/g2core/board/gquadratic/motate_pin_assignments.h b/g2core/board/gquadratic/motate_pin_assignments.h index 6eba44821..57c099bb0 100755 --- a/g2core/board/gquadratic/motate_pin_assignments.h +++ b/g2core/board/gquadratic/motate_pin_assignments.h @@ -226,6 +226,8 @@ pin_number kServo3_PinNumber = 173; // // blank spots for unassigned pins - all unassigned pins need a unique number (do not re-use numbers) +pin_number kUnassigned40 = 215; +pin_number kUnassigned39 = 216; pin_number kUnassigned38 = 217; pin_number kUnassigned37 = 218; pin_number kUnassigned36 = 219; diff --git a/g2core/board/gquintic/board_stepper.cpp b/g2core/board/gquintic/board_stepper.cpp index 8d956b05c..a9606a768 100755 --- a/g2core/board/gquintic/board_stepper.cpp +++ b/g2core/board/gquintic/board_stepper.cpp @@ -2,8 +2,8 @@ * board_stepper.cpp - board-specific code for stepper.cpp * This file is part of the g2core project * - * Copyright (c) 2016 Alden S. Hart, Jr. - * Copyright (c) 2016 Robert Giseburt + * Copyright (c) 2016-2018 Alden S. Hart, Jr. + * Copyright (c) 2016-2018 Robert Giseburt * * This file ("the software") is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License, version 2 as published by the diff --git a/g2core/board/gquintic/hardware.h b/g2core/board/gquintic/hardware.h index 8d86f9d32..79ad75384 100644 --- a/g2core/board/gquintic/hardware.h +++ b/g2core/board/gquintic/hardware.h @@ -146,9 +146,8 @@ typedef TimerChannel<9, 0> dda_timer_type; // stepper pulse generation in ste typedef TimerChannel<10, 0> exec_timer_type; // request exec timer in stepper.cpp typedef TimerChannel<11, 0> fwd_plan_timer_type; // request exec timer in stepper.cpp -Motate::service_call_number kSPI_ServiceCallNumber = 3; - /**** SPI Setup ****/ +Motate::service_call_number kSPI_ServiceCallNumber = 3; typedef Motate::SPIBus SPIBus_used_t; extern SPIBus_used_t spiBus; diff --git a/g2core/boards.mk b/g2core/boards.mk index cb48f6845..4b7b7f534 100644 --- a/g2core/boards.mk +++ b/g2core/boards.mk @@ -170,13 +170,13 @@ endif ifeq ("$(CONFIG)","EggBot") ifeq ("$(BOARD)","NONE") - BOARD=gquadratic-b + BOARD=gquadratic-c endif SETTINGS_FILE="settings_eggbot.h" endif ifeq ("$(CONFIG)","AxiDrawv3") ifeq ("$(BOARD)","NONE") - BOARD=gquadratic-b + BOARD=gquadratic-c endif SETTINGS_FILE="settings_axidraw_v3.h" endif diff --git a/g2core/settings/settings_axidraw_v3.h b/g2core/settings/settings_axidraw_v3.h index 3b5df8ed7..c8ef282c6 100755 --- a/g2core/settings/settings_axidraw_v3.h +++ b/g2core/settings/settings_axidraw_v3.h @@ -91,18 +91,9 @@ #define KINEMATICS KINE_CORE_XY // X and Y MUST use the same settings! -#if MOTORS == 3 -// gQuadratic -#define A_B_POWER_LEVEL 0.4 -#define A_B_MICROSTEPS 32 -#define JERK_MAX 2000 -#endif -#if MOTORS == 6 -// gQuintic #define A_B_POWER_LEVEL 0.7 #define A_B_MICROSTEPS 64 #define JERK_MAX 3000 -#endif #define M1_MOTOR_MAP AXIS_COREXY_A // 1ma #define M1_STEP_ANGLE 1.8 // 1sa @@ -121,6 +112,8 @@ #define M2_POWER_LEVEL A_B_POWER_LEVEL #if MOTORS == 3 +// gQuadratic +#warning Autodetected gQuadratic settings #define M3_MOTOR_MAP AXIS_Z // This "stepper" is a hobby servo. Note that all hobby // servo settings are per full servo range, instead of @@ -135,6 +128,8 @@ #endif #if MOTORS == 6 +// gQuintic +#warning Autodetected gQuintic settings #define M6_MOTOR_MAP AXIS_Z // This "stepper" is a hobby servo. Note that all hobby // servo settings are per full servo range, instead of From 1c35c925c2262a68addc731714e8f5bc7cef0205 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Thu, 1 Mar 2018 10:16:31 -0600 Subject: [PATCH 175/193] Update reference to new Motate (fixes to SPI) --- Motate | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Motate b/Motate index f7e3cddc2..75b4f82bd 160000 --- a/Motate +++ b/Motate @@ -1 +1 @@ -Subproject commit f7e3cddc2188a39fd831ac6ce508f5006df7aceb +Subproject commit 75b4f82bd1155fd3d9bdb8bb91772d780d3d12fc From 9817e0b1dd1a0c47a169580c61d342c394bebae3 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Sun, 4 Mar 2018 17:13:05 -0600 Subject: [PATCH 176/193] Finishing fixes for gQuadratic rev C --- g2core/board/gquadratic/0_hardware.cpp | 6 +++--- g2core/board/gquadratic/board_xio.cpp | 2 +- g2core/controller.cpp | 8 +++----- 3 files changed, 7 insertions(+), 9 deletions(-) diff --git a/g2core/board/gquadratic/0_hardware.cpp b/g2core/board/gquadratic/0_hardware.cpp index 2a8fa86c0..465c7175d 100755 --- a/g2core/board/gquadratic/0_hardware.cpp +++ b/g2core/board/gquadratic/0_hardware.cpp @@ -83,13 +83,13 @@ HOT_DATA SPIBus_used_t spiBus; void hardware_init() { + board_hardware_init(); +// external_clk_pin = 0; // Force external clock to 0 for now. + #if QUADRATIC_REVISION == 'C' spiBus.init(); #endif - board_hardware_init(); -// external_clk_pin = 0; // Force external clock to 0 for now. - #if EXPERIMENTAL_NEOPIXEL_SUPPORT == 1 for (uint8_t pixel = 0; pixel < LEDs::rgbw_leds.count; pixel++) { LEDs::display_color[pixel].startTransition(100, 0, 0, 0); diff --git a/g2core/board/gquadratic/board_xio.cpp b/g2core/board/gquadratic/board_xio.cpp index 077df084d..d05ce1ff8 100755 --- a/g2core/board/gquadratic/board_xio.cpp +++ b/g2core/board/gquadratic/board_xio.cpp @@ -71,7 +71,7 @@ void board_hardware_init(void) // called 1st #if XIO_HAS_USB // Init USB usb.attach(); - usb.handleVbusChange(true); + usb.handleVbusChange(/*force:*/ true); #endif // XIO_HAS_USB } diff --git a/g2core/controller.cpp b/g2core/controller.cpp index 419c8a534..83fc8d397 100644 --- a/g2core/controller.cpp +++ b/g2core/controller.cpp @@ -297,7 +297,7 @@ static void _dispatch_kernel(const devflags_t flags) nv_copy_string(nv, cs.bufp); // copy the Gcode line nv->valuetype = TYPE_STRING; status = gcode_parser(cs.bufp); - + #if MARLIN_COMPAT_ENABLED == true if (js.json_mode == MARLIN_COMM_MODE) { // in case a marlin-specific M-code was found cs.comm_request_mode = MARLIN_COMM_MODE; // mode of this command @@ -340,7 +340,7 @@ static stat_t _controller_state() { if (cs.controller_state == CONTROLLER_CONNECTED) { // first time through after reset cs.controller_state = CONTROLLER_STARTUP; - + // This is here just to put a small delay in before the startup message. #if MARLIN_COMPAT_ENABLED == true // For Marlin compatibility, we need this to be long enough for the UI to say something and reveal @@ -349,7 +349,7 @@ static stat_t _controller_state() // xio_connected will only return true for USB and other non-permanent connections _connection_timeout.set(2000); } else { - _connection_timeout.set(1); + _connection_timeout.set(10); } #else _connection_timeout.set(10); @@ -558,5 +558,3 @@ stat_t _test_system_assertions() xio_test_assertions(); return (STAT_OK); } - - From 23194e9f929faf26976b068fda20279eadc005c4 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Sun, 4 Mar 2018 17:16:11 -0600 Subject: [PATCH 177/193] Initial GPIO action refactor (incomplete) --- g2core/canonical_machine.cpp | 116 ++++++++++++++++++--- g2core/canonical_machine.h | 1 + g2core/config_app.cpp | 25 ++--- g2core/cycle_homing.cpp | 27 ++++- g2core/cycle_probing.cpp | 80 +++++++++------ g2core/gpio.cpp | 36 +------ g2core/gpio.h | 194 +++++++++++++++++++++++------------ 7 files changed, 322 insertions(+), 157 deletions(-) diff --git a/g2core/canonical_machine.cpp b/g2core/canonical_machine.cpp index 068ebb015..6ecf1c88a 100644 --- a/g2core/canonical_machine.cpp +++ b/g2core/canonical_machine.cpp @@ -760,6 +760,13 @@ void canonical_machine_init() canonical_machine_init_assertions(); // establish assertions ACTIVE_MODEL = MODEL; // setup initial Gcode model pointer cm_arc_init(); // Note: spindle and coolant inits are independent + + din_listeners[INPUT_ACTION_STOP].registerListener(&_hold_listener); + din_listeners[INPUT_ACTION_FAST_STOP].registerListener(&_hold_listener); + din_listeners[INPUT_ACTION_HALT].registerListener(&_halt_listener); + din_listeners[INPUT_ACTION_ALARM].registerListener(&_alarm_listener); + din_listeners[INPUT_ACTION_SHUTDOWN].registerListener(&_shutdown_listener); + din_listeners[INPUT_ACTION_PANIC].registerListener(&_panic_listener); } void canonical_machine_reset_rotation() { @@ -785,7 +792,7 @@ void canonical_machine_reset() // NOTE: Should unhome axes here - // reset requests and flags + // reset requests and flags cm.queue_flush_state = FLUSH_OFF; cm.end_hold_requested = false; cm.limit_requested = 0; // resets switch closures that occurred during initialization @@ -872,6 +879,24 @@ stat_t cm_clr(nvObj_t *nv) // clear alarm or shutdown from comman return (STAT_OK); } +/* + * _alarm_listener - a gpioDigitalInputListener to capture pin change events + * Will be registered at init + */ +gpioDigitalInputListener _alarm_listener { + [&](const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { + if (edge != INPUT_EDGE_LEADING) { return false; } + + char msg[10]; + sprintf(msg, "input %d", triggering_pin_number); + cm_alarm(STAT_ALARM, msg); + + return false; // allow others to see this notice + }, + 5, // priority + nullptr // next - nullptr to start with +}; + /* * cm_clear() - clear ALARM and SHUTDOWN states * cm_parse_clear() - parse incoming gcode for M30 or M2 clears if in ALARM state @@ -938,6 +963,22 @@ void cm_halt_motion(void) cm.hold_state = FEEDHOLD_OFF; } +/* + * _hold_listener - a gpioDigitalInputListener to capture pin change events + * Will be registered at init + */ +gpioDigitalInputListener _halt_listener { + [&](const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { + if (edge != INPUT_EDGE_LEADING) { return false; } + + cm_halt_all(); + + return false; // allow others to see this notice + }, + 5, // priority + nullptr // next - nullptr to start with +}; + /* * cm_alarm() - enter ALARM state * @@ -1020,6 +1061,24 @@ stat_t cm_shutdown(const stat_t status, const char *msg) return (status); } +/* + * _shutdown_listener - a gpioDigitalInputListener to capture pin change events + * Will be registered at init + */ +gpioDigitalInputListener _shutdown_listener { + [&](const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { + if (edge != INPUT_EDGE_LEADING) { return false; } + + char msg[10]; + sprintf(msg, "input %d", triggering_pin_number); + cm_shutdown(STAT_SHUTDOWN, msg); + + return false; // allow others to see this notice + }, + 5, // priority + nullptr // next - nullptr to start with +}; + /* * cm_panic() - enter panic state * @@ -1048,6 +1107,24 @@ stat_t cm_panic(const stat_t status, const char *msg) return (status); } +/* + * _panic_listener - a gpioDigitalInputListener to capture pin change events + * Will be registered at init + */ +gpioDigitalInputListener _panic_listener { + [&](const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { + if (edge != INPUT_EDGE_LEADING) { return false; } + + char msg[10]; + sprintf(msg, "input %d", triggering_pin_number); + cm_panic(STAT_PANIC, msg); + + return false; // allow others to see this notice + }, + 5, // priority + nullptr // next - nullptr to start with +}; + /************************** * Representation (4.3.3) * **************************/ @@ -1119,7 +1196,7 @@ stat_t cm_set_g10_data(const uint8_t P_word, const bool P_flag, cm.offset[P_word][axis] = _to_millimeters(offset[axis]); } else { // Should L20 take into account G92 offsets? - cm.offset[P_word][axis] = + cm.offset[P_word][axis] = cm.gmx.position[axis] - _to_millimeters(offset[axis]) - cm.tl_offset[axis]; @@ -1223,7 +1300,7 @@ static void _exec_offset(float *value, bool *flag) float offsets[AXES]; for (uint8_t axis = AXIS_X; axis < AXES; axis++) { - offsets[axis] = cm.offset[coord_system][axis] + cm.tl_offset[axis] + + offsets[axis] = cm.offset[coord_system][axis] + cm.tl_offset[axis] + (cm.gmx.origin_offset[axis] * cm.gmx.origin_offset_enable); } mp_set_runtime_work_offset(offsets); @@ -1318,7 +1395,7 @@ stat_t cm_set_origin_offsets(const float offset[], const bool flag[]) for (uint8_t axis = AXIS_X; axis < AXES; axis++) { if (flag[axis]) { cm.gmx.origin_offset[axis] = cm.gmx.position[axis] - - cm.offset[cm.gm.coord_system][axis] - + cm.offset[cm.gm.coord_system][axis] - cm.tl_offset[axis] - _to_millimeters(offset[axis]); } @@ -1382,7 +1459,7 @@ stat_t cm_straight_traverse(const float target[], const bool flags[]) cm_cycle_start(); // required for homing & other cycles stat_t status = mp_aline(&cm.gm); // send the move to the planner cm_finalize_move(); - + if (status == STAT_MINIMUM_LENGTH_MOVE) { if (!mp_has_runnable_buffer()) { // handle condition where zero-length move is last or only move cm_cycle_end(); // ...otherwise cycle will not end properly @@ -1416,7 +1493,7 @@ stat_t _goto_stored_position(const float stored_position[], // always in mm target[i] *= INCHES_PER_MM; } } - + // Run the stored position move while (mp_planner_is_full()); // Make sure you have available buffers @@ -1905,7 +1982,6 @@ void cm_start_hold() cm.hold_state = FEEDHOLD_SYNC; // invokes hold from aline execution } } - void cm_end_hold() { if (cm.hold_state == FEEDHOLD_HOLD) { @@ -1930,7 +2006,6 @@ void cm_end_hold() } } } - void cm_queue_flush() { if (mp_runtime_is_idle()) { // can't flush planner during movement @@ -1947,6 +2022,23 @@ void cm_queue_flush() } } +/* + * _hold_listener - a gpioDigitalInputListener to capture pin change events + * Will be registered at init + */ +gpioDigitalInputListener _hold_listener { + [&](const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { + if (edge != INPUT_EDGE_LEADING) { return false; } + + cm_start_hold(); + + return false; // allow others to see this notice + }, + 5, // priority + nullptr // next - nullptr to start with +}; + + /****************************** * Program Functions (4.3.10) * ******************************/ @@ -2283,7 +2375,7 @@ static const char *const msg_frmo[] = { msg_g93, msg_g94, msg_g95 }; static int8_t _get_axis(const index_t index) { - // test if this is a SYS parameter (global), in which case there will be no axis + // test if this is a SYS parameter (global), in which case there will be no axis if (strcmp("sys", cfgArray[index].group) == 0) { return (AXIS_TYPE_SYSTEM); } @@ -2293,7 +2385,7 @@ static int8_t _get_axis(const index_t index) if (isdigit(cfgArray[index].token[0])) { return(st_cfg.mot[c-0x31].motor_map); } - + // otherwise it's an axis. Or undefined, which is usually a global. char *ptr; char axes[] = {"xyzabc"}; @@ -2487,12 +2579,12 @@ stat_t cm_get_am(nvObj_t *nv) stat_t cm_set_am(nvObj_t *nv) // axis mode { if (cm_get_axis_type(nv->index) == 0) { // linear - if (nv->value > AXIS_MODE_MAX_LINEAR) { + if (nv->value > AXIS_MODE_MAX_LINEAR) { nv->valuetype = TYPE_NULL; return (STAT_INPUT_EXCEEDS_MAX_VALUE); } } else { - if (nv->value > AXIS_MODE_MAX_ROTARY) { + if (nv->value > AXIS_MODE_MAX_ROTARY) { nv->valuetype = TYPE_NULL; return (STAT_INPUT_EXCEEDS_MAX_VALUE); } diff --git a/g2core/canonical_machine.h b/g2core/canonical_machine.h index 8db99bc63..f54493426 100644 --- a/g2core/canonical_machine.h +++ b/g2core/canonical_machine.h @@ -437,6 +437,7 @@ typedef struct cmSingleton { // struct to manage cm globals and c bool probe_report_enable; // 0=disabled, 1=enabled cmProbeState probe_state[PROBES_STORED]; // probing state machine (simple) + uint8_t probe_input; // probing digital input float probe_results[PROBES_STORED][AXES]; // probing results float rotation_matrix[3][3]; // three-by-three rotation matrix. We ignore rotary axes. diff --git a/g2core/config_app.cpp b/g2core/config_app.cpp index 549fd6fb1..9a3fb035e 100644 --- a/g2core/config_app.cpp +++ b/g2core/config_app.cpp @@ -174,6 +174,7 @@ const cfgItem_t cfgArray[] = { { "prb","prbc",_f0, 3, tx_print_nul, get_flt, set_ro, (float *)&cm.probe_results[0][AXIS_C], 0 }, { "prb","prbs",_f0, 0, tx_print_nul, get_nul, cm_set_probe, (float *)&cs.null, 0 }, // store probe { "prb","prbr",_f0, 0, tx_print_nul, cm_get_prbr, cm_set_prbr, nullptr, 0 }, // enable probe report. Init in cm_init + { "prb","prbin",_f0, 0, tx_print_nul, get_ui8, cm_set_hi, (float *)&cm.probe_input, PROBING_INPUT }, // probing state { "jog","jogx",_f0, 0, tx_print_nul, get_nul, cm_run_jogx, (float *)&cm.jogging_dest, 0}, { "jog","jogy",_f0, 0, tx_print_nul, get_nul, cm_run_jogy, (float *)&cm.jogging_dest, 0}, @@ -486,83 +487,83 @@ const cfgItem_t cfgArray[] = { { "di1","di1en",_fip, 0, din_print_en, din_get_en, din_set_en, (float *)&din1, DI1_ENABLED }, { "di1","di1po",_fip, 0, din_print_po, din_get_po, din_set_po, (float *)&din1, DI1_POLARITY }, { "di1","di1ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din1, DI1_ACTION }, - { "di1","di1fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din1, DI1_FUNCTION }, + // { "di1","di1fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din1, DI1_FUNCTION }, { "di1","di1in",_fip, 0, din_print_in, din_get_in, din_set_in, (float *)&din1, DI1_EXTERNAL_NUMBER }, { "di2","di2en",_fip, 0, din_print_en, din_get_en, din_set_en, (float *)&din2, DI2_ENABLED }, { "di2","di2po",_fip, 0, din_print_po, din_get_po, din_set_po, (float *)&din2, DI2_POLARITY }, { "di2","di2ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din2, DI2_ACTION }, - { "di2","di2fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din2, DI2_FUNCTION }, + // { "di2","di2fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din2, DI2_FUNCTION }, { "di2","di2in",_fip, 0, din_print_in, din_get_in, din_set_in, (float *)&din2, DI2_EXTERNAL_NUMBER }, #if (D_IN_CHANNELS >= 3) { "di3","di3en",_fip, 0, din_print_en, din_get_en, din_set_en, (float *)&din3, DI3_ENABLED }, { "di3","di3po",_fip, 0, din_print_po, din_get_po, din_set_po, (float *)&din3, DI3_POLARITY }, { "di3","di3ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din3, DI3_ACTION }, - { "di3","di3fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din3, DI3_FUNCTION }, + // { "di3","di3fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din3, DI3_FUNCTION }, { "di3","di3in",_fip, 0, din_print_in, din_get_in, din_set_in, (float *)&din3, DI3_EXTERNAL_NUMBER }, #endif #if (D_IN_CHANNELS >= 4) { "di4","di4en",_fip, 0, din_print_en, din_get_en, din_set_en, (float *)&din4, DI4_ENABLED }, { "di4","di4po",_fip, 0, din_print_po, din_get_po, din_set_po, (float *)&din4, DI4_POLARITY }, { "di4","di4ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din4, DI4_ACTION }, - { "di4","di4fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din4, DI4_FUNCTION }, + // { "di4","di4fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din4, DI4_FUNCTION }, { "di4","di4in",_fip, 0, din_print_in, din_get_in, din_set_in, (float *)&din4, DI4_EXTERNAL_NUMBER }, #endif #if (D_IN_CHANNELS >= 5) { "di5","di5en",_fip, 0, din_print_en, din_get_en, din_set_en, (float *)&din5, DI5_ENABLED }, { "di5","di5po",_fip, 0, din_print_po, din_get_po, din_set_po, (float *)&din5, DI5_POLARITY }, { "di5","di5ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din5, DI5_ACTION }, - { "di5","di5fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din5, DI5_FUNCTION }, + // { "di5","di5fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din5, DI5_FUNCTION }, { "di5","di5in",_fip, 0, din_print_in, din_get_in, din_set_in, (float *)&din5, DI5_EXTERNAL_NUMBER }, #endif #if (D_IN_CHANNELS >= 6) { "di6","di6en",_fip, 0, din_print_en, din_get_en, din_set_en, (float *)&din6, DI6_ENABLED }, { "di6","di6po",_fip, 0, din_print_po, din_get_po, din_set_po, (float *)&din6, DI6_POLARITY }, { "di6","di6ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din6, DI6_ACTION }, - { "di6","di6fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din6, DI6_FUNCTION }, + // { "di6","di6fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din6, DI6_FUNCTION }, { "di6","di6in",_fip, 0, din_print_in, din_get_in, din_set_in, (float *)&din6, DI6_EXTERNAL_NUMBER }, #endif #if (D_IN_CHANNELS >= 7) { "di7","di7en",_fip, 0, din_print_en, din_get_en, din_set_en, (float *)&din7, DI7_ENABLED }, { "di7","di7po",_fip, 0, din_print_po, din_get_po, din_set_po, (float *)&din7, DI7_POLARITY }, { "di7","di7ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din7, DI7_ACTION }, - { "di7","di7fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din7, DI7_FUNCTION }, + // { "di7","di7fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din7, DI7_FUNCTION }, { "di7","di7in",_fip, 0, din_print_in, din_get_in, din_set_in, (float *)&din7, DI7_EXTERNAL_NUMBER }, #endif #if (D_IN_CHANNELS >= 8) { "di8","di8en",_fip, 0, din_print_en, din_get_en, din_set_en, (float *)&din8, DI8_ENABLED }, { "di3","di8po",_fip, 0, din_print_po, din_get_po, din_set_po, (float *)&din8, DI8_POLARITY }, { "di8","di8ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din8, DI8_ACTION }, - { "di8","di8fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din8, DI8_FUNCTION }, + // { "di8","di8fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din8, DI8_FUNCTION }, { "di8","di8in",_fip, 0, din_print_in, din_get_in, din_set_in, (float *)&din8, DI8_EXTERNAL_NUMBER }, #endif #if (D_IN_CHANNELS >= 9) { "di9","di9en",_fip, 0, din_print_en, din_get_en, din_set_en, (float *)&din9, DI9_ENABLED }, { "di9","di9po",_fip, 0, din_print_po, din_get_po, din_set_po, (float *)&din9, DI9_POLARITY }, { "di9","di9ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din9, DI9_ACTION }, - { "di9","di9fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din9, DI9_FUNCTION }, + // { "di9","di9fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din9, DI9_FUNCTION }, { "di9","di9in",_fip, 0, din_print_in, din_get_in, din_set_in, (float *)&din9, DI9_EXTERNAL_NUMBER }, #endif #if (D_IN_CHANNELS >= 10) { "di10","di10en",_fip, 0, din_print_en, din_get_en, din_set_en, (float *)&din10, DI10_ENABLED }, { "di10","di10po",_fip, 0, din_print_po, din_get_po, din_set_po, (float *)&din10, DI10_POLARITY }, { "di10","di10ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din10, DI10_ACTION }, - { "di10","di10fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din10, DI10_FUNCTION }, + // { "di10","di10fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din10, DI10_FUNCTION }, { "di10","di10in",_fip, 0, din_print_in, din_get_in, din_set_in, (float *)&din10, DI10_EXTERNAL_NUMBER }, #endif #if (D_IN_CHANNELS >= 11) { "di11","di11en",_fip, 0, din_print_en, din_get_en, din_set_en, (float *)&din11, DI11_ENABLED }, { "di11","di11po",_fip, 0, din_print_po, din_get_po, din_set_po, (float *)&din11, DI11_POLARITY }, { "di11","di11ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din11, DI11_ACTION }, - { "di11","di11fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din11, DI11_FUNCTION }, + // { "di11","di11fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din11, DI11_FUNCTION }, { "di11","di11in",_fip, 0, din_print_in, din_get_in, din_set_in, (float *)&din11, DI11_EXTERNAL_NUMBER }, #endif #if (D_IN_CHANNELS >= 12) { "di12","di12en",_fip, 0, din_print_en, din_get_en, din_set_en, (float *)&din12, DI12_ENABLED }, { "di12","di12po",_fip, 0, din_print_po, din_get_po, din_set_po, (float *)&din12, DI12_POLARITY }, { "di12","di12ac",_fip, 0, din_print_ac, din_get_ac, din_set_ac, (float *)&din12, DI12_ACTION }, - { "di12","di12fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din12, DI12_FUNCTION }, + // { "di12","di12fn",_fip, 0, din_print_fn, din_get_fn, din_set_fn, (float *)&din12, DI12_FUNCTION }, { "di12","di12in",_fip, 0, din_print_in, din_get_in, din_set_in, (float *)&din12, DI12_EXTERNAL_NUMBER }, #endif diff --git a/g2core/cycle_homing.cpp b/g2core/cycle_homing.cpp index 93c4d130c..63a976b62 100644 --- a/g2core/cycle_homing.cpp +++ b/g2core/cycle_homing.cpp @@ -96,6 +96,26 @@ static stat_t _set_homing_func(stat_t (*func)(int8_t axis)) { return (STAT_EAGAIN); } +/* + * _homing_listener - a gpioDigitalInputListener to capture pin change events + * Will be registered only during homing mode - see gpio.h for more info + */ +gpioDigitalInputListener _homing_listener { + [&](const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { + if (cm.cycle_state != CYCLE_HOMING) { return false; } + if (triggering_pin_number != hm.homing_input) { return false; } + if (edge != INPUT_EDGE_LEADING) { return false; } + + en_take_encoder_snapshot(); + cm_start_hold(); + + return false; // allow others to see this notice + }, + 100, // priority + nullptr // next - nullptr to start with +}; + + /*********************************************************************************** **** G28.2 Homing Cycle *********************************************************** ***********************************************************************************/ @@ -224,7 +244,7 @@ static stat_t _homing_axis_start(int8_t axis) { cm.homed[axis] = false; // trap axis mis-configurations - if (fp_ZERO(cm.a[axis].homing_input)) { + if (cm.a[axis].homing_input) { return (_homing_error_exit(axis, STAT_HOMING_ERROR_HOMING_INPUT_MISCONFIGURED)); } if (fp_ZERO(cm.a[axis].search_velocity)) { @@ -243,7 +263,8 @@ static stat_t _homing_axis_start(int8_t axis) { // Nothing to do about direction now that direction is explicit // However, here's a good place to stash the homing_switch: hm.homing_input = cm.a[axis].homing_input; - gpio_set_homing_mode(hm.homing_input, true); + din_listeners[INPUT_ACTION_INTERNAL].registerListener(&_homing_listener); + hm.axis = axis; // persist the axis hm.search_velocity = std::abs(cm.a[axis].search_velocity); // search velocity is always positive hm.latch_velocity = std::abs(cm.a[axis].latch_velocity); // latch velocity is always positive @@ -328,7 +349,7 @@ static stat_t _homing_axis_set_position(int8_t axis) // set axis zero / max and } cm_set_axis_jerk(axis, hm.saved_jerk); // restore the max jerk value - gpio_set_homing_mode(hm.homing_input, false); // end homing mode + din_listeners[INPUT_ACTION_INTERNAL].deregisterListener(&_homing_listener); // end homing mode return (_set_homing_func(_homing_axis_start)); } diff --git a/g2core/cycle_probing.cpp b/g2core/cycle_probing.cpp index 1e49f6af1..c003217aa 100644 --- a/g2core/cycle_probing.cpp +++ b/g2core/cycle_probing.cpp @@ -123,6 +123,24 @@ static void _motion_end_callback(float* vect, bool* flag) pb.wait_for_motion_end = false; } +/* + * _probing_listener - a gpioDigitalInputListener to capture pin change events + * Will be registered only during homing mode - see gpio.h for more info + */ +gpioDigitalInputListener _probing_listener { + [&](const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { + if (cm.cycle_state != CYCLE_PROBE) { return false; } + if (triggering_pin_number != pb.probe_input) { return false; } + + en_take_encoder_snapshot(); + cm_start_hold(); + + return false; // allow others to see this notice + }, + 100, // priority + nullptr // next - nullptr to start with +}; + /*********************************************************************************** **** G38.x Probing Cycle ********************************************************** ***********************************************************************************/ @@ -130,8 +148,8 @@ static void _motion_end_callback(float* vect, bool* flag) /*********************************************************************************** * cm_probing_cycle_start() - G38.x probing cycle using contact (digital input) * - * cm_probe_cycle_start() is the entry point for a probe cycle. It checks for - * some errors, sets up the cycle, then prevents any new commands from queuing + * cm_probe_cycle_start() is the entry point for a probe cycle. It checks for + * some errors, sets up the cycle, then prevents any new commands from queuing * to the planner so that the planner can move to a stop and report motion stopped. * * --- Some further details --- @@ -154,12 +172,12 @@ static void _motion_end_callback(float* vect, bool* flag) * PROBE_SUCCEEDED, then we roll 0 to 1, and 1 to 2, up to PROBES_STORED-1. * The oldest probe is "lost." * - * Alarms and exceptions: It is *not* necessarily an error condition for the - * probe not to trigger, depending on the G38.x command received. It is an error + * Alarms and exceptions: It is *not* necessarily an error condition for the + * probe not to trigger, depending on the G38.x command received. It is an error * for the limit or homing switches to fire, or for some other configuration error. * These are trapped and cause Alarms. - * - * Note: Spindle and coolant are not affected during probing. Some probes require + * + * Note: Spindle and coolant are not affected during probing. Some probes require * the spindle to be turned on. * * Note: When coding a cycle (like this one) you get to perform one queued @@ -168,15 +186,15 @@ static void _motion_end_callback(float* vect, bool* flag) * sets a flag in the probing object (pb.waiting_for_motion_end) to tell us that * the move has finished. The runtime has a special exception for probing and * homing where if a move is interrupted it clears it out of the queue. - * - * You must also wait until the last move has actually completed before declaring - * the cycle to be done. Otherwise there is a nasty race condition in the - * _controller_HSM() that may accept the next command before the position of the - * final move has been recorded in the Gcode model. That's part of what what the + * + * You must also wait until the last move has actually completed before declaring + * the cycle to be done. Otherwise there is a nasty race condition in the + * _controller_HSM() that may accept the next command before the position of the + * final move has been recorded in the Gcode model. That's part of what what the * wait_for_motion_end callback is about. */ -uint8_t cm_straight_probe(float target[], bool flags[], bool trip_sense, bool alarm_flag) +uint8_t cm_straight_probe(float target[], bool flags[], bool trip_sense, bool alarm_flag) { // error if zero feed rate if (fp_ZERO(cm.gm.feed_rate)) { @@ -213,19 +231,19 @@ uint8_t cm_straight_probe(float target[], bool flags[], bool trip_sense, bool al pb.wait_for_motion_end = true; mp_queue_command(_motion_end_callback, nullptr, nullptr); // note: these args are ignored return (STAT_OK); -} +} /*********************************************************************************** * cm_probing_cycle_callback() - handle probing progress * - * This is called regularly from the controller. If we report NOOP, the controller - * will continue with other tasks. Otherwise the controller will not execute any + * This is called regularly from the controller. If we report NOOP, the controller + * will continue with other tasks. Otherwise the controller will not execute any * later tasks, including read any more "data". */ -uint8_t cm_probing_cycle_callback(void) +uint8_t cm_probing_cycle_callback(void) { - if ((cm.cycle_state != CYCLE_PROBE) && (cm.probe_state[0] != PROBE_WAITING)) { + if ((cm.cycle_state != CYCLE_PROBE) && (cm.probe_state[0] != PROBE_WAITING)) { return (STAT_NOOP); // exit if not in a probing cycle } if (pb.wait_for_motion_end) { // sync to planner move ends (using callback) @@ -238,14 +256,14 @@ uint8_t cm_probing_cycle_callback(void) * _probing_start() - start the probe or skip it if contact is already active */ -static uint8_t _probing_start() +static uint8_t _probing_start() { // so optimistic... ;) // These initializations are required before starting the probing cycle but must - // be done after the planner has exhausted all current moves as they affect the - // runtime (specifically the digital input modes). Side effects would include + // be done after the planner has exhausted all current moves as they affect the + // runtime (specifically the digital input modes). Side effects would include // limit switches initiating probe actions instead of just killing movement - + cm.probe_state[0] = PROBE_FAILED; cm.machine_state = MACHINE_CYCLE; cm.cycle_state = CYCLE_PROBE; @@ -255,7 +273,7 @@ static uint8_t _probing_start() pb.saved_units_mode = (cmUnitsMode)cm_get_units_mode(ACTIVE_MODEL); pb.saved_soft_limits = cm_get_soft_limits(); cm_set_soft_limits(false); - + // set working values cm_set_distance_mode(ABSOLUTE_DISTANCE_MODE); cm_set_units_mode(MILLIMETERS); @@ -271,7 +289,7 @@ static uint8_t _probing_start() return(_probing_exception_exit(STAT_PROBE_TRAVEL_TOO_SMALL)); } - gpio_set_probing_mode(pb.probe_input, true); + din_listeners[INPUT_ACTION_INTERNAL].registerListener(&_probing_listener); // Get initial probe state, and don't probe if we're already tripped. // If the initial input is the same as the trip_sense it's an error. @@ -279,7 +297,7 @@ static uint8_t _probing_start() return(_probing_exception_exit(STAT_PROBE_IS_ALREADY_TRIPPED)); } - // Everything checks out. Run the probe move + // Everything checks out. Run the probe move _probe_move(pb.target, pb.flags); pb.func = _probing_backoff; return (STAT_EAGAIN); @@ -291,10 +309,10 @@ static uint8_t _probing_start() * Back off to the measured touch position captured by encoder snapshot */ -static stat_t _probing_backoff() +static stat_t _probing_backoff() { - // Test if we've contacted. If so, do the backoff. Convert the contact position - // captured from the encoder in step space to steps to mm. The encoder snapshot + // Test if we've contacted. If so, do the backoff. Convert the contact position + // captured from the encoder in step space to steps to mm. The encoder snapshot // was taken by input interrupt at the time of closure. if (pb.trip_sense == gpio_read_input(pb.probe_input)) { // exclusive or for booleans @@ -318,7 +336,7 @@ static stat_t _probing_backoff() static stat_t _probe_move(const float target[], const bool flags[]) { - cm_set_absolute_override(MODEL, ABSOLUTE_OVERRIDE_ON); + cm_set_absolute_override(MODEL, ABSOLUTE_OVERRIDE_ON); pb.wait_for_motion_end = true; // set this BEFORE the motion starts cm_straight_feed(target, flags); mp_queue_command(_motion_end_callback, nullptr, nullptr); // the last two arguments are ignored anyway @@ -331,12 +349,12 @@ static stat_t _probe_move(const float target[], const bool flags[]) * _probing_finish() - exit for successful and non-contacted (failed) probes */ -static void _probe_restore_settings() +static void _probe_restore_settings() { - gpio_set_probing_mode(pb.probe_input, false); // set input back to normal operation + din_listeners[INPUT_ACTION_INTERNAL].deregisterListener(&_probing_listener); for (uint8_t axis = 0; axis < AXES; axis++) { // restore axis jerks - cm.a[axis].jerk_max = pb.saved_jerk[axis]; + cm.a[axis].jerk_max = pb.saved_jerk[axis]; } cm_set_absolute_override(MODEL, ABSOLUTE_OVERRIDE_OFF); // release abs override and restore work offsets cm_set_distance_mode(pb.saved_distance_mode); diff --git a/g2core/gpio.cpp b/g2core/gpio.cpp index 49f0528f4..34bd57196 100644 --- a/g2core/gpio.cpp +++ b/g2core/gpio.cpp @@ -100,30 +100,8 @@ void gpio_reset(void) * Note: input_num_ext means EXTERNAL input number -- 1-based * TODO: lookup the external number to find the internal input, don't assume */ -void gpio_set_homing_mode(const uint8_t input_num_ext, const bool is_homing) -{ - if (input_num_ext == 0) { - return; - } - d_in[input_num_ext-1]->setIsHoming(is_homing); -} - -void gpio_set_probing_mode(const uint8_t input_num_ext, const bool is_probing) -{ - if (input_num_ext == 0) { - return; - } - d_in[input_num_ext-1]->setIsProbing(is_probing); -} - int8_t gpio_get_probing_input(void) { - for (uint8_t i = 1; i <= D_IN_CHANNELS; i++) { - if (d_in[i-1]->getFunction() == INPUT_FUNCTION_PROBE) { - return (i); - } - } - return (-1); } bool gpio_read_input(const uint8_t input_num_ext) @@ -146,7 +124,7 @@ bool gpio_read_input(const uint8_t input_num_ext) template type* _io(const nvObj_t *nv) { - return reinterpret_cast(cfgArray[nv->index].target); + return reinterpret_cast(cfgArray[nv->index].target); }; gpioDigitalInput* _i(const nvObj_t *nv) { return _io(nv); } @@ -189,6 +167,10 @@ gpioDigitalOutputReader out14; gpioDigitalOutputReader* const out_r[14] = {&out1 ,&out2 ,&out3 ,&out4 ,&out5 ,&out6 ,&out7 ,&out8 ,&out9 ,&out10 ,&out11 ,&out12 ,&out13 ,&out14}; +// lists for the various inputAction events +gpioDigitalInputListenerList din_listeners[INPUT_ACTION_ACTUAL_MAX+1]; + + /* * Get/set enabled */ @@ -228,14 +210,6 @@ stat_t din_set_ac(nvObj_t *nv) /* * Get/set input function */ -stat_t din_get_fn(nvObj_t *nv) -{ - return _i(nv)->getFunction(nv); -} -stat_t din_set_fn(nvObj_t *nv) -{ - return _i(nv)->setFunction(nv); -} /* * Get/set input function diff --git a/g2core/gpio.h b/g2core/gpio.h index 708957593..75c220ec8 100644 --- a/g2core/gpio.h +++ b/g2core/gpio.h @@ -69,25 +69,22 @@ typedef enum { typedef enum { // actions are initiated from within the input's ISR INPUT_ACTION_NONE = 0, - INPUT_ACTION_STOP, // stop at normal jerk - preserves positional accuracy - INPUT_ACTION_FAST_STOP, // stop at high jerk - preserves positional accuracy - INPUT_ACTION_HALT, // stop immediately - not guaranteed to preserve position - INPUT_ACTION_CYCLE_START, // start / restart cycle after feedhold (RESERVED) - INPUT_ACTION_ALARM, // initiate an alarm. stops everything immediately - preserves position - INPUT_ACTION_SHUTDOWN, // initiate a shutdown. stops everything immediately - does not preserve position - INPUT_ACTION_PANIC, // initiate a panic. stops everything immediately - does not preserve position - INPUT_ACTION_RESET, // reset system + INPUT_ACTION_STOP, // 1 - stop at normal jerk - preserves positional accuracy + INPUT_ACTION_FAST_STOP, // 2 - stop at high jerk - preserves positional accuracy + INPUT_ACTION_HALT, // 3 - stop immediately - not guaranteed to preserve position + INPUT_ACTION_CYCLE_START, // 4 - start / restart cycle after feedhold (RESERVED) + INPUT_ACTION_ALARM, // 5 - initiate an alarm. stops everything immediately - preserves position + INPUT_ACTION_SHUTDOWN, // 6 - initiate a shutdown. stops everything immediately - does not preserve position + INPUT_ACTION_PANIC, // 7 - initiate a panic. stops everything immediately - does not preserve position + INPUT_ACTION_RESET, // 8 - reset system + + INPUT_ACTION_LIMIT, // 9 - limit switch processing + INPUT_ACTION_INTERLOCK, // 10 - interlock processing + + INPUT_ACTION_INTERNAL, // 11 - homing/probing processing (internal only) } inputAction; -#define INPUT_ACTION_MAX INPUT_ACTION_RESET // for range checking - -typedef enum { // functions are requested from the ISR, run from the main loop - INPUT_FUNCTION_NONE = 0, - INPUT_FUNCTION_LIMIT = 1, // limit switch processing - INPUT_FUNCTION_INTERLOCK = 2, // interlock processing - INPUT_FUNCTION_SHUTDOWN = 3, // shutdown in support of external emergency stop - INPUT_FUNCTION_PROBE = 4, // assign input as probe input -} inputFunc; -#define INPUT_FUNCTION_MAX INPUT_FUNCTION_PROBE +#define INPUT_ACTION_MAX INPUT_ACTION_INTERLOCK // for range checking +#define INPUT_ACTION_ACTUAL_MAX INPUT_ACTION_INTERNAL // for internal checking and resource allocation typedef enum { INPUT_INACTIVE = 0, // aka switch open, also read as 'false' @@ -105,6 +102,105 @@ typedef enum { struct gpioDigitalInputReader; extern gpioDigitalInputReader* const in_r[14]; +/* + * gpioDigitalInputListener - superclass of objects that wish to be informed of + * digital input changes + * + * Notes about the callback function: + * The first parameter is the current state (honoring polarity) - true = ACTIVE + * The second parameter is the inputEdgeFlag value + * The third parameter is the external number (N in `diN`) of the pin that changed + * The return value indicates if it has been "handled" - return true and no other + * gpioDigitalInputListener callbacks will be triggered *for this event* + * Generally, return false unless there is a good reason to stop propagation. + * + * Example gpioDigitalInputListener object creation: + + gpioDigitalInputListener limitListener { + [&](const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { + if (edge != INPUT_EDGE_LEADING) { return; } + limit_requested = true; // record that a limit was requested for later processing + return false; // allow others to see this notice + }, + 5, // priority + nullptr // next - nullptr to start with + }; + + // register this listener for limit events: + din_listeners[INPUT_ACTION_LIMIT].registerListener(limitListener); + */ + +struct gpioDigitalInputListener { + // const means it must be provided at compile time + const std::function callback; // the function to call + const int8_t priority; // higher is higher + + gpioDigitalInputListener *next; // form a simple linked list +}; + + +struct gpioDigitalInputListenerList { + gpioDigitalInputListener * _first_listener; + + void registerListener(gpioDigitalInputListener * const new_listener) { + if (!_first_listener) { + // there is only one - now + _first_listener = new_listener; + return; + } else if (new_listener->priority > _first_listener->priority) { + // this is the new first one + new_listener->next = _first_listener; + _first_listener = new_listener; + return; + } + + gpioDigitalInputListener * current_listener = _first_listener; + + while (current_listener != nullptr) { + if (new_listener->priority <= current_listener->priority) { + // new_listener will be immediately after current_listener + new_listener->next = current_listener->next; + current_listener->next = new_listener; + return; + } + current_listener = current_listener->next; + } + }; + + void deregisterListener(gpioDigitalInputListener * const old_listener) { + if (!_first_listener) { + return; + } else if (_first_listener == old_listener) { + _first_listener = _first_listener->next; + return; + } + + gpioDigitalInputListener * current_listener = _first_listener; + + while (current_listener->next != nullptr) { + if (current_listener->next == old_listener) { + current_listener->next = old_listener->next; + return; + } + current_listener = current_listener->next; + } + }; + + bool call(const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { + gpioDigitalInputListener * current_listener = _first_listener; + while (current_listener != nullptr) { + if (current_listener->callback(state, edge, triggering_pin_number)) { + return true; + } + current_listener = current_listener->next; + } + return false; + } +}; + +// lists for the various inputAction events +extern gpioDigitalInputListenerList din_listeners[INPUT_ACTION_ACTUAL_MAX+1]; + /* * gpioDigitalInput - digital input base class */ @@ -116,8 +212,6 @@ struct gpioDigitalInput { virtual bool getState(); - virtual inputFunc getFunction(); - virtual bool setFunction(const inputFunc); virtual inputAction getAction(); virtual bool setAction(const inputAction); @@ -131,8 +225,6 @@ struct gpioDigitalInput { virtual bool setExternalNumber(const uint8_t); virtual const uint8_t getExternalNumber(); - virtual void setIsHoming(const bool); - virtual void setIsProbing(const bool); // functions that take nvObj_t* and return stat_t, NOT overridden @@ -200,22 +292,6 @@ struct gpioDigitalInput { return (STAT_OK); }; - stat_t getFunction(nvObj_t *nv) - { - nv->value = getFunction(); - nv->valuetype = TYPE_INT; - return (STAT_OK); - }; - stat_t setFunction(nvObj_t *nv) - { - if ((nv->value < INPUT_FUNCTION_NONE) || (nv->value > INPUT_FUNCTION_MAX)) { - return (STAT_INPUT_VALUE_RANGE_ERROR); - } - if (!setFunction((inputFunc)nv->value)) { - return STAT_PARAMETER_IS_READ_ONLY; - } - return (STAT_OK); - }; stat_t getExternalNumber(nvObj_t *nv) { @@ -240,7 +316,7 @@ struct gpioDigitalInput { * gpioDigitalInputReader - digital input reader class - the "in1" - "inX" objects */ -struct gpioDigitalInputReader { +struct gpioDigitalInputReader final { gpioDigitalInput* pin; // functions for use by other parts of the code @@ -293,11 +369,11 @@ extern gpioDigitalInputReader in14; * gpioDigitalInputPin - concrete child of gpioDigitalInput */ template -struct gpioDigitalInputPin : gpioDigitalInput { +struct gpioDigitalInputPin final : gpioDigitalInput { ioEnabled enabled; // -1=unavailable, 0=disabled, 1=enabled ioPolarity polarity; // 0=normal/active high, 1=inverted/active low inputAction action; // 0=none, 1=stop, 2=halt, 3=stop_steps, 4=reset - inputFunc input_function; // function to perform when activated / deactivated + // inputFunc input_function; // function to perform when activated / deactivated inputEdgeFlag edge; // keeps a transient record of edges for immediate inquiry @@ -342,15 +418,6 @@ struct gpioDigitalInputPin : gpioDigitalInput { return (polarity == IO_ACTIVE_HIGH) ? v : !v; }; - inputFunc getFunction() override - { - return input_function; - } - bool setFunction(const inputFunc f) override - { - input_function = f; - return true; - }; inputAction getAction() override { @@ -406,17 +473,6 @@ struct gpioDigitalInputPin : gpioDigitalInput { return proxy_pin_number; }; - void setIsHoming(const bool m) override - { - homing_mode = m; - }; - - void setIsProbing(const bool m) override - { - probing_mode = m; - }; - - // support function for pin change interrupt handling @@ -450,6 +506,11 @@ struct gpioDigitalInputPin : gpioDigitalInput { edge = INPUT_EDGE_TRAILING; } + // start with INPUT_ACTION_INTERNAL for transient event processing like homing and probing + if (!din_listeners[INPUT_ACTION_INTERNAL].call(pin_value_corrected, edge, ext_pin_number)) { + din_listeners[action].call(pin_value_corrected, edge, ext_pin_number); + } +#if 0 // TODO - refactor homing_mode and probing_mode out to use a dynamically // configured linked list of functions @@ -506,7 +567,7 @@ struct gpioDigitalInputPin : gpioDigitalInput { // these functions also trigger on the leading edge - if (input_function == INPUT_FUNCTION_LIMIT) { + if (input_function == INPUT_ACTION_LIMIT) { cm.limit_requested = ext_pin_number; } else if (input_function == INPUT_FUNCTION_SHUTDOWN) { @@ -523,6 +584,7 @@ struct gpioDigitalInputPin : gpioDigitalInput { cm.safety_interlock_reengaged = ext_pin_number; } } +#endif sr_request_status_report(SR_REQUEST_TIMED); //+++++ Put this one back in. }; @@ -654,7 +716,7 @@ struct gpioDigitalOutput { * gpioDigitalOutputReader - digital output reader class - the "out1" - "outX" objects */ -struct gpioDigitalOutputReader { +struct gpioDigitalOutputReader final { gpioDigitalOutput* pin; // functions for use by other parts of the code @@ -720,7 +782,7 @@ extern gpioDigitalOutputReader out14; * gpioDigitalOutputPin - concrete child of gpioDigitalOutput */ template -struct gpioDigitalOutputPin : gpioDigitalOutput { +struct gpioDigitalOutputPin final : gpioDigitalOutput { ioEnabled enabled; // -1=unavailable, 0=disabled, 1=enabled ioPolarity polarity; // 0=normal/active high, 1=inverted/active low uint8_t proxy_pin_number; // the number used externally for this pin ("in" + proxy_pin_number) @@ -1176,8 +1238,6 @@ void inputs_reset(void); void outputs_reset(void); bool gpio_read_input(const uint8_t input_num); -void gpio_set_homing_mode(const uint8_t input_num, const bool is_homing); -void gpio_set_probing_mode(const uint8_t input_num, const bool is_probing); int8_t gpio_get_probing_input(void); stat_t din_get_en(nvObj_t *nv); // enabled @@ -1186,8 +1246,6 @@ stat_t din_get_po(nvObj_t *nv); // input sense stat_t din_set_po(nvObj_t *nv); stat_t din_get_ac(nvObj_t *nv); // input action stat_t din_set_ac(nvObj_t *nv); -stat_t din_get_fn(nvObj_t *nv); // input function -stat_t din_set_fn(nvObj_t *nv); stat_t din_get_in(nvObj_t *nv); // input external number stat_t din_set_in(nvObj_t *nv); stat_t din_get_input(nvObj_t *nv); From 02ef06a0ee0a775e35df88a0d2c03c2fb2507e74 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Sun, 4 Mar 2018 17:17:08 -0600 Subject: [PATCH 178/193] Fix default settings. --- g2core/settings/settings_default.h | 43 +++++------------------------- 1 file changed, 6 insertions(+), 37 deletions(-) diff --git a/g2core/settings/settings_default.h b/g2core/settings/settings_default.h index 298cfc409..9c5da27d4 100644 --- a/g2core/settings/settings_default.h +++ b/g2core/settings/settings_default.h @@ -933,7 +933,7 @@ INPUT_ACTION_RESET INPUT_FUNCTION_NONE - INPUT_FUNCTION_LIMIT + INPUT_ACTION_LIMIT INPUT_FUNCTION_INTERLOCK INPUT_FUNCTION_SHUTDOWN INPUT_FUNCTION_PANIC @@ -949,9 +949,6 @@ #ifndef DI1_ACTION #define DI1_ACTION INPUT_ACTION_NONE #endif -#ifndef DI1_FUNCTION -#define DI1_FUNCTION INPUT_FUNCTION_NONE -#endif #ifndef DI1_EXTERNAL_NUMBER #define DI1_EXTERNAL_NUMBER 1 #endif @@ -966,9 +963,6 @@ #ifndef DI2_ACTION #define DI2_ACTION INPUT_ACTION_NONE #endif -#ifndef DI2_FUNCTION -#define DI2_FUNCTION INPUT_FUNCTION_NONE -#endif #ifndef DI2_EXTERNAL_NUMBER #define DI2_EXTERNAL_NUMBER 2 #endif @@ -983,9 +977,6 @@ #ifndef DI3_ACTION #define DI3_ACTION INPUT_ACTION_NONE #endif -#ifndef DI3_FUNCTION -#define DI3_FUNCTION INPUT_FUNCTION_NONE -#endif #ifndef DI3_EXTERNAL_NUMBER #define DI3_EXTERNAL_NUMBER 3 #endif @@ -1000,9 +991,6 @@ #ifndef DI4_ACTION #define DI4_ACTION INPUT_ACTION_NONE #endif -#ifndef DI4_FUNCTION -#define DI4_FUNCTION INPUT_FUNCTION_NONE -#endif #ifndef DI4_EXTERNAL_NUMBER #define DI4_EXTERNAL_NUMBER 4 #endif @@ -1017,9 +1005,6 @@ #ifndef DI5_ACTION #define DI5_ACTION INPUT_ACTION_NONE #endif -#ifndef DI5_FUNCTION -#define DI5_FUNCTION INPUT_FUNCTION_PROBE -#endif #ifndef DI5_EXTERNAL_NUMBER #define DI5_EXTERNAL_NUMBER 5 #endif @@ -1034,9 +1019,6 @@ #ifndef DI6_ACTION #define DI6_ACTION INPUT_ACTION_NONE #endif -#ifndef DI6_FUNCTION -#define DI6_FUNCTION INPUT_FUNCTION_NONE -#endif #ifndef DI6_EXTERNAL_NUMBER #define DI6_EXTERNAL_NUMBER 6 #endif @@ -1051,9 +1033,6 @@ #ifndef DI7_ACTION #define DI7_ACTION INPUT_ACTION_NONE #endif -#ifndef DI7_FUNCTION -#define DI7_FUNCTION INPUT_FUNCTION_NONE -#endif #ifndef DI7_EXTERNAL_NUMBER #define DI7_EXTERNAL_NUMBER 7 #endif @@ -1068,9 +1047,6 @@ #ifndef DI8_ACTION #define DI8_ACTION INPUT_ACTION_NONE #endif -#ifndef DI8_FUNCTION -#define DI8_FUNCTION INPUT_FUNCTION_NONE -#endif #ifndef DI8_EXTERNAL_NUMBER #define DI8_EXTERNAL_NUMBER 8 #endif @@ -1085,9 +1061,6 @@ #ifndef DI9_ACTION #define DI9_ACTION INPUT_ACTION_NONE #endif -#ifndef DI9_FUNCTION -#define DI9_FUNCTION INPUT_FUNCTION_NONE -#endif #ifndef DI9_EXTERNAL_NUMBER #define DI9_EXTERNAL_NUMBER 9 #endif @@ -1101,9 +1074,6 @@ #ifndef DI10_ACTION #define DI10_ACTION INPUT_ACTION_NONE #endif -#ifndef DI10_FUNCTION -#define DI10_FUNCTION INPUT_FUNCTION_NONE -#endif #ifndef DI10_EXTERNAL_NUMBER #define DI10_EXTERNAL_NUMBER 10 #endif @@ -1117,9 +1087,6 @@ #ifndef DI11_ACTION #define DI11_ACTION INPUT_ACTION_NONE #endif -#ifndef DI11_FUNCTION -#define DI11_FUNCTION INPUT_FUNCTION_NONE -#endif #ifndef DI11_EXTERNAL_NUMBER #define DI11_EXTERNAL_NUMBER 11 #endif @@ -1133,13 +1100,15 @@ #ifndef DI12_ACTION #define DI12_ACTION INPUT_ACTION_NONE #endif -#ifndef DI12_FUNCTION -#define DI12_FUNCTION INPUT_FUNCTION_NONE -#endif #ifndef DI12_EXTERNAL_NUMBER #define DI12_EXTERNAL_NUMBER 12 #endif + +#ifndef PROBING_INPUT +#define PROBING_INPUT Z_HOMING_INPUT // default to the z homing input +#endif + // DIGITAL OUTPUTS - Currently these are hard-wired to extruders //Extruder1_PWM From 9b46efbb8a7564bfd767e6e46994c6e8ac349326 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Sun, 4 Mar 2018 17:17:32 -0600 Subject: [PATCH 179/193] Fix Axidraw settings --- g2core/settings/settings_axidraw_v3.h | 148 ++------------------------ 1 file changed, 7 insertions(+), 141 deletions(-) diff --git a/g2core/settings/settings_axidraw_v3.h b/g2core/settings/settings_axidraw_v3.h index c8ef282c6..f4795dd9b 100755 --- a/g2core/settings/settings_axidraw_v3.h +++ b/g2core/settings/settings_axidraw_v3.h @@ -113,7 +113,7 @@ #if MOTORS == 3 // gQuadratic -#warning Autodetected gQuadratic settings +// #warning Autodetected gQuadratic settings #define M3_MOTOR_MAP AXIS_Z // This "stepper" is a hobby servo. Note that all hobby // servo settings are per full servo range, instead of @@ -189,153 +189,19 @@ #define Z_ZERO_BACKOFF 2 //*** Input / output settings *** -/* - IO_MODE_DISABLED - IO_ACTIVE_LOW aka NORMALLY_OPEN - IO_ACTIVE_HIGH aka NORMALLY_CLOSED - - INPUT_ACTION_NONE - INPUT_ACTION_STOP - INPUT_ACTION_FAST_STOP - INPUT_ACTION_HALT - INPUT_ACTION_RESET - - INPUT_FUNCTION_NONE - INPUT_FUNCTION_LIMIT - INPUT_FUNCTION_INTERLOCK - INPUT_FUNCTION_SHUTDOWN - INPUT_FUNCTION_PANIC -*/ -// Inputs are defined for the g2ref(a) board -// Xmn (board label) -#define DI1_MODE IO_ACTIVE_HIGH -#define DI1_ACTION INPUT_ACTION_NONE -#define DI1_FUNCTION INPUT_FUNCTION_NONE - -// Xmax -#define DI2_MODE IO_MODE_DISABLED +#define DI1_POLARITY IO_ACTIVE_HIGH +#define DI1_ACTION INPUT_ACTION_STOP + +#define DI2_POLARITY IO_ACTIVE_HIGH #define DI2_ACTION INPUT_ACTION_NONE -#define DI2_FUNCTION INPUT_FUNCTION_NONE -// Ymin -#define DI3_MODE IO_MODE_DISABLED +#define DI3_POLARITY IO_ACTIVE_HIGH #define DI3_ACTION INPUT_ACTION_NONE -#define DI3_FUNCTION INPUT_FUNCTION_NONE -// Ymax #define DI4_MODE IO_ACTIVE_HIGH #define DI4_ACTION INPUT_ACTION_NONE -#define DI4_FUNCTION INPUT_FUNCTION_NONE - -// Zmin -#define DI5_MODE IO_ACTIVE_LOW // Z probe -#define DI5_ACTION INPUT_ACTION_NONE -#define DI5_FUNCTION INPUT_FUNCTION_NONE - -// Zmax -#define DI6_MODE IO_MODE_DISABLED -#define DI6_ACTION INPUT_ACTION_STOP -#define DI6_FUNCTION INPUT_FUNCTION_NONE - -// Shutdown (Amin on v9 board) -#define DI7_MODE IO_MODE_DISABLED -#define DI7_ACTION INPUT_ACTION_NONE -#define DI7_FUNCTION INPUT_FUNCTION_NONE - -// High Voltage Z Probe In (Amax on v9 board) -#define DI8_MODE IO_ACTIVE_LOW -#define DI8_ACTION INPUT_ACTION_NONE -#define DI8_FUNCTION INPUT_FUNCTION_NONE - -// Hardware interlock input -#define DI9_MODE IO_MODE_DISABLED -#define DI9_ACTION INPUT_ACTION_NONE -#define DI9_FUNCTION INPUT_FUNCTION_NONE - -//Extruder1_PWM -#define DO1_MODE IO_ACTIVE_HIGH -//Extruder2_PWM +#define DO1_MODE IO_ACTIVE_HIGH #define DO2_MODE IO_ACTIVE_HIGH - -//Fan1A_PWM #define DO3_MODE IO_ACTIVE_HIGH - -//Fan1B_PWM #define DO4_MODE IO_ACTIVE_HIGH - -#define DO5_MODE IO_ACTIVE_HIGH -#define DO6_MODE IO_ACTIVE_HIGH -#define DO7_MODE IO_ACTIVE_HIGH -#define DO8_MODE IO_ACTIVE_HIGH - -//SAFEin (Output) signal -#define DO9_MODE IO_ACTIVE_HIGH - -#define DO10_MODE IO_ACTIVE_HIGH - -//Header Bed FET -#define DO11_MODE IO_ACTIVE_HIGH - -//Indicator_LED -#define DO12_MODE IO_ACTIVE_HIGH - -#define DO13_MODE IO_ACTIVE_HIGH - - -// *** PWM SPINDLE CONTROL *** - -#define P1_PWM_FREQUENCY 100 // in Hz -#define P1_CW_SPEED_LO 1000 // in RPM (arbitrary units) -#define P1_CW_SPEED_HI 2000 -#define P1_CW_PHASE_LO 0.125 // phase [0..1] -#define P1_CW_PHASE_HI 0.2 -#define P1_CCW_SPEED_LO 1000 -#define P1_CCW_SPEED_HI 2000 -#define P1_CCW_PHASE_LO 0.125 -#define P1_CCW_PHASE_HI 0.2 -#define P1_PWM_PHASE_OFF 0.1 - -// *** DEFAULT COORDINATE SYSTEM OFFSETS *** - -#define G54_X_OFFSET 0 // G54 is traditionally set to all zeros -#define G54_Y_OFFSET 0 -#define G54_Z_OFFSET 0 -#define G54_A_OFFSET 0 -#define G54_B_OFFSET 0 -#define G54_C_OFFSET 0 - -#define G55_X_OFFSET (X_TRAVEL_MAX/2) // set to middle of table -#define G55_Y_OFFSET (Y_TRAVEL_MAX/2) -#define G55_Z_OFFSET 0 -#define G55_A_OFFSET 0 -#define G55_B_OFFSET 0 -#define G55_C_OFFSET 0 - -#define G56_X_OFFSET 0 -#define G56_Y_OFFSET 0 -#define G56_Z_OFFSET 0 -#define G56_A_OFFSET 0 -#define G56_B_OFFSET 0 -#define G56_C_OFFSET 0 - -#define G57_X_OFFSET 0 -#define G57_Y_OFFSET 0 -#define G57_Z_OFFSET 0 -#define G57_A_OFFSET 0 -#define G57_B_OFFSET 0 -#define G57_C_OFFSET 0 - -#define G58_X_OFFSET 0 -#define G58_Y_OFFSET 0 -#define G58_Z_OFFSET 0 -#define G58_A_OFFSET 0 -#define G58_B_OFFSET 0 -#define G58_C_OFFSET 0 - -#define G59_X_OFFSET 0 -#define G59_Y_OFFSET 0 -#define G59_Z_OFFSET 0 -#define G59_A_OFFSET 0 -#define G59_B_OFFSET 0 -#define G59_C_OFFSET 0 From b83323027897a42e13ddfd8ce0b4030ef2c46fef Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Sun, 4 Mar 2018 17:35:01 -0600 Subject: [PATCH 180/193] Finsihed adding reset, limit, and interlock event handlers --- g2core/canonical_machine.cpp | 36 +++++++++++++--------------- g2core/controller.cpp | 46 ++++++++++++++++++++++++++++++++++++ 2 files changed, 63 insertions(+), 19 deletions(-) diff --git a/g2core/canonical_machine.cpp b/g2core/canonical_machine.cpp index 6ecf1c88a..b8cfe55a0 100644 --- a/g2core/canonical_machine.cpp +++ b/g2core/canonical_machine.cpp @@ -765,8 +765,8 @@ void canonical_machine_init() din_listeners[INPUT_ACTION_FAST_STOP].registerListener(&_hold_listener); din_listeners[INPUT_ACTION_HALT].registerListener(&_halt_listener); din_listeners[INPUT_ACTION_ALARM].registerListener(&_alarm_listener); - din_listeners[INPUT_ACTION_SHUTDOWN].registerListener(&_shutdown_listener); din_listeners[INPUT_ACTION_PANIC].registerListener(&_panic_listener); + din_listeners[INPUT_ACTION_RESET].registerListener(&_reset_listener); } void canonical_machine_reset_rotation() { @@ -1061,24 +1061,6 @@ stat_t cm_shutdown(const stat_t status, const char *msg) return (status); } -/* - * _shutdown_listener - a gpioDigitalInputListener to capture pin change events - * Will be registered at init - */ -gpioDigitalInputListener _shutdown_listener { - [&](const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { - if (edge != INPUT_EDGE_LEADING) { return false; } - - char msg[10]; - sprintf(msg, "input %d", triggering_pin_number); - cm_shutdown(STAT_SHUTDOWN, msg); - - return false; // allow others to see this notice - }, - 5, // priority - nullptr // next - nullptr to start with -}; - /* * cm_panic() - enter panic state * @@ -1125,6 +1107,22 @@ gpioDigitalInputListener _panic_listener { nullptr // next - nullptr to start with }; +/* + * _reset_listener - a gpioDigitalInputListener to capture pin change events + * Will be registered at init + */ +gpioDigitalInputListener _reset_listener { + [&](const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { + if (edge != INPUT_EDGE_LEADING) { return false; } + + hw_hard_reset(); + + return false; // this likely won't be seen, but just in case... + }, + 5, // priority + nullptr // next - nullptr to start with +}; + /************************** * Representation (4.3.3) * **************************/ diff --git a/g2core/controller.cpp b/g2core/controller.cpp index 83fc8d397..ec873fd30 100644 --- a/g2core/controller.cpp +++ b/g2core/controller.cpp @@ -105,6 +105,10 @@ void controller_init() cs.controller_state = CONTROLLER_CONNECTED; } // IndicatorLed.setFrequency(100000); + + din_listeners[INPUT_ACTION_SHUTDOWN].registerListener(&_shutdown_listener); + din_listeners[INPUT_ACTION_LIMIT].registerListener(&_limit_listener); + din_listeners[INPUT_ACTION_INTERLOCK].registerListener(&_interlock_listener); } void controller_request_enquiry() @@ -462,8 +466,11 @@ static stat_t _sync_to_planner() /* ALARM STATE HANDLERS * * _shutdown_handler() - put system into shutdown state + * _shutdown_listener - a gpioDigitalInputListener to capture pin change events * _limit_switch_handler() - shut down system if limit switch fired + * _limit_listener - a gpioDigitalInputListener to capture pin change events * _interlock_handler() - feedhold and resume depending on edge + * _interlock_listener - a gpioDigitalInputListener to capture pin change events * * Some handlers return EAGAIN causing the control loop to never advance beyond that point. * @@ -472,6 +479,19 @@ static stat_t _sync_to_planner() * - safety_interlock_requested == INPUT_EDGE_LEADING is interlock onset * - safety_interlock_requested == INPUT_EDGE_TRAILING is interlock offset */ + +gpioDigitalInputListener _shutdown_listener { + [&](const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { + if (edge != INPUT_EDGE_LEADING) { return false; } + + cm.shutdown_requested = triggering_pin_number; + + return false; // allow others to see this notice + }, + 5, // priority + nullptr // next - nullptr to start with +}; + static stat_t _shutdown_handler(void) { if (cm.shutdown_requested != 0) { // request may contain the (non-zero) input number @@ -483,6 +503,18 @@ static stat_t _shutdown_handler(void) return(STAT_OK); } +gpioDigitalInputListener _limit_listener { + [&](const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { + if (edge != INPUT_EDGE_LEADING) { return false; } + + cm.limit_requested = triggering_pin_number; + + return false; // allow others to see this notice + }, + 5, // priority + nullptr // next - nullptr to start with +}; + static stat_t _limit_switch_handler(void) { auto machine_state = cm_get_machine_state(); @@ -501,6 +533,20 @@ static stat_t _limit_switch_handler(void) return (STAT_OK); } +gpioDigitalInputListener _interlock_listener { + [&](const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { + if (edge == INPUT_EDGE_LEADING) { + cm.safety_interlock_disengaged = triggering_pin_number; + } else { // edge == INPUT_EDGE_TRAILING + cm.safety_interlock_reengaged = triggering_pin_number; + } + + return false; // allow others to see this notice + }, + 5, // priority + nullptr // next - nullptr to start with +}; + static stat_t _interlock_handler(void) { if (cm.safety_interlock_enable) { From 8a07cee6650abdc35bb9f070acadfccccf373579 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Sun, 4 Mar 2018 17:39:47 -0600 Subject: [PATCH 181/193] Renaming "Listener" to "Handler" --- g2core/canonical_machine.cpp | 32 +++++++-------- g2core/controller.cpp | 18 ++++----- g2core/cycle_homing.cpp | 8 ++-- g2core/cycle_probing.cpp | 8 ++-- g2core/gpio.cpp | 2 +- g2core/gpio.h | 78 ++++++++++++++++++------------------ 6 files changed, 73 insertions(+), 73 deletions(-) diff --git a/g2core/canonical_machine.cpp b/g2core/canonical_machine.cpp index b8cfe55a0..bda764105 100644 --- a/g2core/canonical_machine.cpp +++ b/g2core/canonical_machine.cpp @@ -761,12 +761,12 @@ void canonical_machine_init() ACTIVE_MODEL = MODEL; // setup initial Gcode model pointer cm_arc_init(); // Note: spindle and coolant inits are independent - din_listeners[INPUT_ACTION_STOP].registerListener(&_hold_listener); - din_listeners[INPUT_ACTION_FAST_STOP].registerListener(&_hold_listener); - din_listeners[INPUT_ACTION_HALT].registerListener(&_halt_listener); - din_listeners[INPUT_ACTION_ALARM].registerListener(&_alarm_listener); - din_listeners[INPUT_ACTION_PANIC].registerListener(&_panic_listener); - din_listeners[INPUT_ACTION_RESET].registerListener(&_reset_listener); + din_handlers[INPUT_ACTION_STOP].registerHandler(&_hold_handler); + din_handlers[INPUT_ACTION_FAST_STOP].registerHandler(&_hold_handler); + din_handlers[INPUT_ACTION_HALT].registerHandler(&_halt_handler); + din_handlers[INPUT_ACTION_ALARM].registerHandler(&_alarm_handler); + din_handlers[INPUT_ACTION_PANIC].registerHandler(&_panic_handler); + din_handlers[INPUT_ACTION_RESET].registerHandler(&_reset_handler); } void canonical_machine_reset_rotation() { @@ -880,10 +880,10 @@ stat_t cm_clr(nvObj_t *nv) // clear alarm or shutdown from comman } /* - * _alarm_listener - a gpioDigitalInputListener to capture pin change events + * _alarm_handler - a gpioDigitalInputHandler to capture pin change events * Will be registered at init */ -gpioDigitalInputListener _alarm_listener { +gpioDigitalInputHandler _alarm_handler { [&](const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { if (edge != INPUT_EDGE_LEADING) { return false; } @@ -964,10 +964,10 @@ void cm_halt_motion(void) } /* - * _hold_listener - a gpioDigitalInputListener to capture pin change events + * _hold_handler - a gpioDigitalInputHandler to capture pin change events * Will be registered at init */ -gpioDigitalInputListener _halt_listener { +gpioDigitalInputHandler _halt_handler { [&](const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { if (edge != INPUT_EDGE_LEADING) { return false; } @@ -1090,10 +1090,10 @@ stat_t cm_panic(const stat_t status, const char *msg) } /* - * _panic_listener - a gpioDigitalInputListener to capture pin change events + * _panic_handler - a gpioDigitalInputHandler to capture pin change events * Will be registered at init */ -gpioDigitalInputListener _panic_listener { +gpioDigitalInputHandler _panic_handler { [&](const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { if (edge != INPUT_EDGE_LEADING) { return false; } @@ -1108,10 +1108,10 @@ gpioDigitalInputListener _panic_listener { }; /* - * _reset_listener - a gpioDigitalInputListener to capture pin change events + * _reset_handler - a gpioDigitalInputHandler to capture pin change events * Will be registered at init */ -gpioDigitalInputListener _reset_listener { +gpioDigitalInputHandler _reset_handler { [&](const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { if (edge != INPUT_EDGE_LEADING) { return false; } @@ -2021,10 +2021,10 @@ void cm_queue_flush() } /* - * _hold_listener - a gpioDigitalInputListener to capture pin change events + * _hold_handler - a gpioDigitalInputHandler to capture pin change events * Will be registered at init */ -gpioDigitalInputListener _hold_listener { +gpioDigitalInputHandler _hold_handler { [&](const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { if (edge != INPUT_EDGE_LEADING) { return false; } diff --git a/g2core/controller.cpp b/g2core/controller.cpp index ec873fd30..63b778a09 100644 --- a/g2core/controller.cpp +++ b/g2core/controller.cpp @@ -106,9 +106,9 @@ void controller_init() } // IndicatorLed.setFrequency(100000); - din_listeners[INPUT_ACTION_SHUTDOWN].registerListener(&_shutdown_listener); - din_listeners[INPUT_ACTION_LIMIT].registerListener(&_limit_listener); - din_listeners[INPUT_ACTION_INTERLOCK].registerListener(&_interlock_listener); + din_handlers[INPUT_ACTION_SHUTDOWN].registerHandler(&_shutdown_handler); + din_handlers[INPUT_ACTION_LIMIT].registerHandler(&_limit_handler); + din_handlers[INPUT_ACTION_INTERLOCK].registerHandler(&_interlock_handler); } void controller_request_enquiry() @@ -466,11 +466,11 @@ static stat_t _sync_to_planner() /* ALARM STATE HANDLERS * * _shutdown_handler() - put system into shutdown state - * _shutdown_listener - a gpioDigitalInputListener to capture pin change events + * _shutdown_handler - a gpioDigitalInputHandler to capture pin change events * _limit_switch_handler() - shut down system if limit switch fired - * _limit_listener - a gpioDigitalInputListener to capture pin change events + * _limit_handler - a gpioDigitalInputHandler to capture pin change events * _interlock_handler() - feedhold and resume depending on edge - * _interlock_listener - a gpioDigitalInputListener to capture pin change events + * _interlock_handler - a gpioDigitalInputHandler to capture pin change events * * Some handlers return EAGAIN causing the control loop to never advance beyond that point. * @@ -480,7 +480,7 @@ static stat_t _sync_to_planner() * - safety_interlock_requested == INPUT_EDGE_TRAILING is interlock offset */ -gpioDigitalInputListener _shutdown_listener { +gpioDigitalInputHandler _shutdown_handler { [&](const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { if (edge != INPUT_EDGE_LEADING) { return false; } @@ -503,7 +503,7 @@ static stat_t _shutdown_handler(void) return(STAT_OK); } -gpioDigitalInputListener _limit_listener { +gpioDigitalInputHandler _limit_handler { [&](const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { if (edge != INPUT_EDGE_LEADING) { return false; } @@ -533,7 +533,7 @@ static stat_t _limit_switch_handler(void) return (STAT_OK); } -gpioDigitalInputListener _interlock_listener { +gpioDigitalInputHandler _interlock_handler { [&](const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { if (edge == INPUT_EDGE_LEADING) { cm.safety_interlock_disengaged = triggering_pin_number; diff --git a/g2core/cycle_homing.cpp b/g2core/cycle_homing.cpp index 63a976b62..c05767d9a 100644 --- a/g2core/cycle_homing.cpp +++ b/g2core/cycle_homing.cpp @@ -97,10 +97,10 @@ static stat_t _set_homing_func(stat_t (*func)(int8_t axis)) { } /* - * _homing_listener - a gpioDigitalInputListener to capture pin change events + * _homing_handler - a gpioDigitalInputHandler to capture pin change events * Will be registered only during homing mode - see gpio.h for more info */ -gpioDigitalInputListener _homing_listener { +gpioDigitalInputHandler _homing_handler { [&](const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { if (cm.cycle_state != CYCLE_HOMING) { return false; } if (triggering_pin_number != hm.homing_input) { return false; } @@ -263,7 +263,7 @@ static stat_t _homing_axis_start(int8_t axis) { // Nothing to do about direction now that direction is explicit // However, here's a good place to stash the homing_switch: hm.homing_input = cm.a[axis].homing_input; - din_listeners[INPUT_ACTION_INTERNAL].registerListener(&_homing_listener); + din_handlers[INPUT_ACTION_INTERNAL].registerHandler(&_homing_handler); hm.axis = axis; // persist the axis hm.search_velocity = std::abs(cm.a[axis].search_velocity); // search velocity is always positive @@ -349,7 +349,7 @@ static stat_t _homing_axis_set_position(int8_t axis) // set axis zero / max and } cm_set_axis_jerk(axis, hm.saved_jerk); // restore the max jerk value - din_listeners[INPUT_ACTION_INTERNAL].deregisterListener(&_homing_listener); // end homing mode + din_handlers[INPUT_ACTION_INTERNAL].deregisterHandler(&_homing_handler); // end homing mode return (_set_homing_func(_homing_axis_start)); } diff --git a/g2core/cycle_probing.cpp b/g2core/cycle_probing.cpp index c003217aa..20464a01c 100644 --- a/g2core/cycle_probing.cpp +++ b/g2core/cycle_probing.cpp @@ -124,10 +124,10 @@ static void _motion_end_callback(float* vect, bool* flag) } /* - * _probing_listener - a gpioDigitalInputListener to capture pin change events + * _probing_handler - a gpioDigitalInputHandler to capture pin change events * Will be registered only during homing mode - see gpio.h for more info */ -gpioDigitalInputListener _probing_listener { +gpioDigitalInputHandler _probing_handler { [&](const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { if (cm.cycle_state != CYCLE_PROBE) { return false; } if (triggering_pin_number != pb.probe_input) { return false; } @@ -289,7 +289,7 @@ static uint8_t _probing_start() return(_probing_exception_exit(STAT_PROBE_TRAVEL_TOO_SMALL)); } - din_listeners[INPUT_ACTION_INTERNAL].registerListener(&_probing_listener); + din_handlers[INPUT_ACTION_INTERNAL].registerHandler(&_probing_handler); // Get initial probe state, and don't probe if we're already tripped. // If the initial input is the same as the trip_sense it's an error. @@ -351,7 +351,7 @@ static stat_t _probe_move(const float target[], const bool flags[]) static void _probe_restore_settings() { - din_listeners[INPUT_ACTION_INTERNAL].deregisterListener(&_probing_listener); + din_handlers[INPUT_ACTION_INTERNAL].deregisterHandler(&_probing_handler); for (uint8_t axis = 0; axis < AXES; axis++) { // restore axis jerks cm.a[axis].jerk_max = pb.saved_jerk[axis]; diff --git a/g2core/gpio.cpp b/g2core/gpio.cpp index 34bd57196..7d7c05575 100644 --- a/g2core/gpio.cpp +++ b/g2core/gpio.cpp @@ -168,7 +168,7 @@ gpioDigitalOutputReader out14; gpioDigitalOutputReader* const out_r[14] = {&out1 ,&out2 ,&out3 ,&out4 ,&out5 ,&out6 ,&out7 ,&out8 ,&out9 ,&out10 ,&out11 ,&out12 ,&out13 ,&out14}; // lists for the various inputAction events -gpioDigitalInputListenerList din_listeners[INPUT_ACTION_ACTUAL_MAX+1]; +gpioDigitalInputHandlerList din_handlers[INPUT_ACTION_ACTUAL_MAX+1]; /* diff --git a/g2core/gpio.h b/g2core/gpio.h index 75c220ec8..97ceb7ce6 100644 --- a/g2core/gpio.h +++ b/g2core/gpio.h @@ -103,7 +103,7 @@ struct gpioDigitalInputReader; extern gpioDigitalInputReader* const in_r[14]; /* - * gpioDigitalInputListener - superclass of objects that wish to be informed of + * gpioDigitalInputHandler - superclass of objects that wish to be informed of * digital input changes * * Notes about the callback function: @@ -111,12 +111,12 @@ extern gpioDigitalInputReader* const in_r[14]; * The second parameter is the inputEdgeFlag value * The third parameter is the external number (N in `diN`) of the pin that changed * The return value indicates if it has been "handled" - return true and no other - * gpioDigitalInputListener callbacks will be triggered *for this event* + * gpioDigitalInputHandler callbacks will be triggered *for this event* * Generally, return false unless there is a good reason to stop propagation. * - * Example gpioDigitalInputListener object creation: + * Example gpioDigitalInputHandler object creation: - gpioDigitalInputListener limitListener { + gpioDigitalInputHandler limitHandler { [&](const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { if (edge != INPUT_EDGE_LEADING) { return; } limit_requested = true; // record that a limit was requested for later processing @@ -127,79 +127,79 @@ extern gpioDigitalInputReader* const in_r[14]; }; // register this listener for limit events: - din_listeners[INPUT_ACTION_LIMIT].registerListener(limitListener); + din_handlers[INPUT_ACTION_LIMIT].registerHandler(limitHandler); */ -struct gpioDigitalInputListener { +struct gpioDigitalInputHandler { // const means it must be provided at compile time const std::function callback; // the function to call const int8_t priority; // higher is higher - gpioDigitalInputListener *next; // form a simple linked list + gpioDigitalInputHandler *next; // form a simple linked list }; -struct gpioDigitalInputListenerList { - gpioDigitalInputListener * _first_listener; +struct gpioDigitalInputHandlerList { + gpioDigitalInputHandler * _first_handler; - void registerListener(gpioDigitalInputListener * const new_listener) { - if (!_first_listener) { + void registerHandler(gpioDigitalInputHandler * const new_handler) { + if (!_first_handler) { // there is only one - now - _first_listener = new_listener; + _first_handler = new_handler; return; - } else if (new_listener->priority > _first_listener->priority) { + } else if (new_handler->priority > _first_handler->priority) { // this is the new first one - new_listener->next = _first_listener; - _first_listener = new_listener; + new_handler->next = _first_handler; + _first_handler = new_handler; return; } - gpioDigitalInputListener * current_listener = _first_listener; + gpioDigitalInputHandler * current_handler = _first_handler; - while (current_listener != nullptr) { - if (new_listener->priority <= current_listener->priority) { - // new_listener will be immediately after current_listener - new_listener->next = current_listener->next; - current_listener->next = new_listener; + while (current_handler != nullptr) { + if (new_handler->priority <= current_handler->priority) { + // new_handler will be immediately after current_handler + new_handler->next = current_handler->next; + current_handler->next = new_handler; return; } - current_listener = current_listener->next; + current_handler = current_handler->next; } }; - void deregisterListener(gpioDigitalInputListener * const old_listener) { - if (!_first_listener) { + void deregisterHandler(gpioDigitalInputHandler * const old_handler) { + if (!_first_handler) { return; - } else if (_first_listener == old_listener) { - _first_listener = _first_listener->next; + } else if (_first_handler == old_handler) { + _first_handler = _first_handler->next; return; } - gpioDigitalInputListener * current_listener = _first_listener; + gpioDigitalInputHandler * current_handler = _first_handler; - while (current_listener->next != nullptr) { - if (current_listener->next == old_listener) { - current_listener->next = old_listener->next; + while (current_handler->next != nullptr) { + if (current_handler->next == old_handler) { + current_handler->next = old_handler->next; return; } - current_listener = current_listener->next; + current_handler = current_handler->next; } }; bool call(const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { - gpioDigitalInputListener * current_listener = _first_listener; - while (current_listener != nullptr) { - if (current_listener->callback(state, edge, triggering_pin_number)) { + gpioDigitalInputHandler * current_handler = _first_handler; + while (current_handler != nullptr) { + if (current_handler->callback(state, edge, triggering_pin_number)) { return true; } - current_listener = current_listener->next; + current_handler = current_handler->next; } return false; } }; // lists for the various inputAction events -extern gpioDigitalInputListenerList din_listeners[INPUT_ACTION_ACTUAL_MAX+1]; +extern gpioDigitalInputHandlerList din_handlers[INPUT_ACTION_ACTUAL_MAX+1]; /* * gpioDigitalInput - digital input base class @@ -507,8 +507,8 @@ struct gpioDigitalInputPin final : gpioDigitalInput { } // start with INPUT_ACTION_INTERNAL for transient event processing like homing and probing - if (!din_listeners[INPUT_ACTION_INTERNAL].call(pin_value_corrected, edge, ext_pin_number)) { - din_listeners[action].call(pin_value_corrected, edge, ext_pin_number); + if (!din_handlers[INPUT_ACTION_INTERNAL].call(pin_value_corrected, edge, ext_pin_number)) { + din_handlers[action].call(pin_value_corrected, edge, ext_pin_number); } #if 0 // TODO - refactor homing_mode and probing_mode out to use a dynamically @@ -570,7 +570,7 @@ struct gpioDigitalInputPin final : gpioDigitalInput { if (input_function == INPUT_ACTION_LIMIT) { cm.limit_requested = ext_pin_number; - } else if (input_function == INPUT_FUNCTION_SHUTDOWN) { + } else if (input_function == INPUT_ACTION_SHUTDOWN) { cm.shutdown_requested = ext_pin_number; } else if (input_function == INPUT_FUNCTION_INTERLOCK) { From f2f42a326272e239224bf8e25118eedb6eb09de1 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Sun, 4 Mar 2018 17:49:55 -0600 Subject: [PATCH 182/193] Name collision fix with "_handler" and some code rarrangement. --- g2core/canonical_machine.cpp | 184 ++++++++++++++++++----------------- g2core/controller.cpp | 88 ++++++++--------- 2 files changed, 137 insertions(+), 135 deletions(-) diff --git a/g2core/canonical_machine.cpp b/g2core/canonical_machine.cpp index bda764105..1d6a2e388 100644 --- a/g2core/canonical_machine.cpp +++ b/g2core/canonical_machine.cpp @@ -116,6 +116,91 @@ cmSingleton_t cm; // canonical machine controller singleton +/* + * _hold_input_handler - a gpioDigitalInputHandler to capture pin change events + * Will be registered at init + */ +gpioDigitalInputHandler _hold_input_handler { + [&](const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { + if (edge != INPUT_EDGE_LEADING) { return false; } + + cm_start_hold(); + + return false; // allow others to see this notice + }, + 5, // priority + nullptr // next - nullptr to start with +}; + +/* + * _halt_input_handler - a gpioDigitalInputHandler to capture pin change events + * Will be registered at init + */ +gpioDigitalInputHandler _halt_input_handler { + [&](const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { + if (edge != INPUT_EDGE_LEADING) { return false; } + + cm_halt_all(); + + return false; // allow others to see this notice + }, + 5, // priority + nullptr // next - nullptr to start with +}; + + +/* + * _alarm_input_handler - a gpioDigitalInputHandler to capture pin change events + * Will be registered at init + */ +gpioDigitalInputHandler _alarm_input_handler { + [&](const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { + if (edge != INPUT_EDGE_LEADING) { return false; } + + char msg[10]; + sprintf(msg, "input %d", triggering_pin_number); + cm_alarm(STAT_ALARM, msg); + + return false; // allow others to see this notice + }, + 5, // priority + nullptr // next - nullptr to start with +}; + +/* + * _panic_input_handler - a gpioDigitalInputHandler to capture pin change events + * Will be registered at init + */ +gpioDigitalInputHandler _panic_input_handler { + [&](const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { + if (edge != INPUT_EDGE_LEADING) { return false; } + + char msg[10]; + sprintf(msg, "input %d", triggering_pin_number); + cm_panic(STAT_PANIC, msg); + + return false; // allow others to see this notice + }, + 5, // priority + nullptr // next - nullptr to start with +}; + +/* + * _reset_input_handler - a gpioDigitalInputHandler to capture pin change events + * Will be registered at init + */ +gpioDigitalInputHandler _reset_input_handler { + [&](const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { + if (edge != INPUT_EDGE_LEADING) { return false; } + + hw_hard_reset(); + + return false; // this likely won't be seen, but just in case... + }, + 5, // priority + nullptr // next - nullptr to start with +}; + /*********************************************************************************** **** GENERIC STATIC FUNCTIONS AND VARIABLES *************************************** ***********************************************************************************/ @@ -748,7 +833,7 @@ stat_t cm_test_soft_limits(const float target[]) * canonical_machine_init() - initialize cm struct * canonical_machine_reset() - apply startup settings or reset to startup * run profile initialization beforehand - */ +*/ void canonical_machine_init() { @@ -761,12 +846,12 @@ void canonical_machine_init() ACTIVE_MODEL = MODEL; // setup initial Gcode model pointer cm_arc_init(); // Note: spindle and coolant inits are independent - din_handlers[INPUT_ACTION_STOP].registerHandler(&_hold_handler); - din_handlers[INPUT_ACTION_FAST_STOP].registerHandler(&_hold_handler); - din_handlers[INPUT_ACTION_HALT].registerHandler(&_halt_handler); - din_handlers[INPUT_ACTION_ALARM].registerHandler(&_alarm_handler); - din_handlers[INPUT_ACTION_PANIC].registerHandler(&_panic_handler); - din_handlers[INPUT_ACTION_RESET].registerHandler(&_reset_handler); + din_handlers[INPUT_ACTION_STOP].registerHandler(&_hold_input_handler); + din_handlers[INPUT_ACTION_FAST_STOP].registerHandler(&_hold_input_handler); + din_handlers[INPUT_ACTION_HALT].registerHandler(&_halt_input_handler); + din_handlers[INPUT_ACTION_ALARM].registerHandler(&_alarm_input_handler); + din_handlers[INPUT_ACTION_PANIC].registerHandler(&_panic_input_handler); + din_handlers[INPUT_ACTION_RESET].registerHandler(&_reset_input_handler); } void canonical_machine_reset_rotation() { @@ -879,24 +964,6 @@ stat_t cm_clr(nvObj_t *nv) // clear alarm or shutdown from comman return (STAT_OK); } -/* - * _alarm_handler - a gpioDigitalInputHandler to capture pin change events - * Will be registered at init - */ -gpioDigitalInputHandler _alarm_handler { - [&](const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { - if (edge != INPUT_EDGE_LEADING) { return false; } - - char msg[10]; - sprintf(msg, "input %d", triggering_pin_number); - cm_alarm(STAT_ALARM, msg); - - return false; // allow others to see this notice - }, - 5, // priority - nullptr // next - nullptr to start with -}; - /* * cm_clear() - clear ALARM and SHUTDOWN states * cm_parse_clear() - parse incoming gcode for M30 or M2 clears if in ALARM state @@ -963,21 +1030,6 @@ void cm_halt_motion(void) cm.hold_state = FEEDHOLD_OFF; } -/* - * _hold_handler - a gpioDigitalInputHandler to capture pin change events - * Will be registered at init - */ -gpioDigitalInputHandler _halt_handler { - [&](const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { - if (edge != INPUT_EDGE_LEADING) { return false; } - - cm_halt_all(); - - return false; // allow others to see this notice - }, - 5, // priority - nullptr // next - nullptr to start with -}; /* * cm_alarm() - enter ALARM state @@ -1089,40 +1141,6 @@ stat_t cm_panic(const stat_t status, const char *msg) return (status); } -/* - * _panic_handler - a gpioDigitalInputHandler to capture pin change events - * Will be registered at init - */ -gpioDigitalInputHandler _panic_handler { - [&](const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { - if (edge != INPUT_EDGE_LEADING) { return false; } - - char msg[10]; - sprintf(msg, "input %d", triggering_pin_number); - cm_panic(STAT_PANIC, msg); - - return false; // allow others to see this notice - }, - 5, // priority - nullptr // next - nullptr to start with -}; - -/* - * _reset_handler - a gpioDigitalInputHandler to capture pin change events - * Will be registered at init - */ -gpioDigitalInputHandler _reset_handler { - [&](const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { - if (edge != INPUT_EDGE_LEADING) { return false; } - - hw_hard_reset(); - - return false; // this likely won't be seen, but just in case... - }, - 5, // priority - nullptr // next - nullptr to start with -}; - /************************** * Representation (4.3.3) * **************************/ @@ -2004,6 +2022,7 @@ void cm_end_hold() } } } + void cm_queue_flush() { if (mp_runtime_is_idle()) { // can't flush planner during movement @@ -2020,23 +2039,6 @@ void cm_queue_flush() } } -/* - * _hold_handler - a gpioDigitalInputHandler to capture pin change events - * Will be registered at init - */ -gpioDigitalInputHandler _hold_handler { - [&](const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { - if (edge != INPUT_EDGE_LEADING) { return false; } - - cm_start_hold(); - - return false; // allow others to see this notice - }, - 5, // priority - nullptr // next - nullptr to start with -}; - - /****************************** * Program Functions (4.3.10) * ******************************/ diff --git a/g2core/controller.cpp b/g2core/controller.cpp index 63b778a09..14ab71498 100644 --- a/g2core/controller.cpp +++ b/g2core/controller.cpp @@ -81,6 +81,44 @@ static stat_t _controller_state(void); // manage controller state trans static Motate::OutputPin safe_pin; +gpioDigitalInputHandler _shutdown_input_handler { + [&](const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { + if (edge != INPUT_EDGE_LEADING) { return false; } + + cm.shutdown_requested = triggering_pin_number; + + return false; // allow others to see this notice + }, + 5, // priority + nullptr // next - nullptr to start with +}; + +gpioDigitalInputHandler _limit_input_handler { + [&](const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { + if (edge != INPUT_EDGE_LEADING) { return false; } + + cm.limit_requested = triggering_pin_number; + + return false; // allow others to see this notice + }, + 5, // priority + nullptr // next - nullptr to start with +}; + +gpioDigitalInputHandler _interlock_input_handler { + [&](const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { + if (edge == INPUT_EDGE_LEADING) { + cm.safety_interlock_disengaged = triggering_pin_number; + } else { // edge == INPUT_EDGE_TRAILING + cm.safety_interlock_reengaged = triggering_pin_number; + } + + return false; // allow others to see this notice + }, + 5, // priority + nullptr // next - nullptr to start with +}; + /*********************************************************************************** **** CODE ************************************************************************* ***********************************************************************************/ @@ -106,9 +144,9 @@ void controller_init() } // IndicatorLed.setFrequency(100000); - din_handlers[INPUT_ACTION_SHUTDOWN].registerHandler(&_shutdown_handler); - din_handlers[INPUT_ACTION_LIMIT].registerHandler(&_limit_handler); - din_handlers[INPUT_ACTION_INTERLOCK].registerHandler(&_interlock_handler); + din_handlers[INPUT_ACTION_SHUTDOWN].registerHandler(&_shutdown_input_handler); + din_handlers[INPUT_ACTION_LIMIT].registerHandler(&_limit_input_handler); + din_handlers[INPUT_ACTION_INTERLOCK].registerHandler(&_interlock_input_handler); } void controller_request_enquiry() @@ -466,10 +504,10 @@ static stat_t _sync_to_planner() /* ALARM STATE HANDLERS * * _shutdown_handler() - put system into shutdown state - * _shutdown_handler - a gpioDigitalInputHandler to capture pin change events + * _shutdown_input_handler - a gpioDigitalInputHandler to capture pin change events * _limit_switch_handler() - shut down system if limit switch fired - * _limit_handler - a gpioDigitalInputHandler to capture pin change events - * _interlock_handler() - feedhold and resume depending on edge + * _limit_input_handler - a gpioDigitalInputHandler to capture pin change events + * _interlock_input_handler() - feedhold and resume depending on edge * _interlock_handler - a gpioDigitalInputHandler to capture pin change events * * Some handlers return EAGAIN causing the control loop to never advance beyond that point. @@ -480,18 +518,6 @@ static stat_t _sync_to_planner() * - safety_interlock_requested == INPUT_EDGE_TRAILING is interlock offset */ -gpioDigitalInputHandler _shutdown_handler { - [&](const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { - if (edge != INPUT_EDGE_LEADING) { return false; } - - cm.shutdown_requested = triggering_pin_number; - - return false; // allow others to see this notice - }, - 5, // priority - nullptr // next - nullptr to start with -}; - static stat_t _shutdown_handler(void) { if (cm.shutdown_requested != 0) { // request may contain the (non-zero) input number @@ -503,18 +529,6 @@ static stat_t _shutdown_handler(void) return(STAT_OK); } -gpioDigitalInputHandler _limit_handler { - [&](const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { - if (edge != INPUT_EDGE_LEADING) { return false; } - - cm.limit_requested = triggering_pin_number; - - return false; // allow others to see this notice - }, - 5, // priority - nullptr // next - nullptr to start with -}; - static stat_t _limit_switch_handler(void) { auto machine_state = cm_get_machine_state(); @@ -533,20 +547,6 @@ static stat_t _limit_switch_handler(void) return (STAT_OK); } -gpioDigitalInputHandler _interlock_handler { - [&](const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { - if (edge == INPUT_EDGE_LEADING) { - cm.safety_interlock_disengaged = triggering_pin_number; - } else { // edge == INPUT_EDGE_TRAILING - cm.safety_interlock_reengaged = triggering_pin_number; - } - - return false; // allow others to see this notice - }, - 5, // priority - nullptr // next - nullptr to start with -}; - static stat_t _interlock_handler(void) { if (cm.safety_interlock_enable) { From 29db38007c0e81910229fe00f6e38f4402a7632f Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Sun, 4 Mar 2018 18:26:19 -0600 Subject: [PATCH 183/193] Updated Motate reference for SamS70 USB fixes --- Motate | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Motate b/Motate index 75b4f82bd..ee04b276a 160000 --- a/Motate +++ b/Motate @@ -1 +1 @@ -Subproject commit 75b4f82bd1155fd3d9bdb8bb91772d780d3d12fc +Subproject commit ee04b276a9301e4e4542471b2c461dc2532e0543 From f41ec454777d26ef80a5131ed04b6d4203cc15db Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Mon, 26 Mar 2018 14:34:46 -0500 Subject: [PATCH 184/193] Adjust analog inputs: cache computed value, and default to lowest resolution --- g2core/gpio.h | 16 ++++++++++++---- 1 file changed, 12 insertions(+), 4 deletions(-) diff --git a/g2core/gpio.h b/g2core/gpio.h index 97ceb7ce6..85e1d2f34 100644 --- a/g2core/gpio.h +++ b/g2core/gpio.h @@ -1035,6 +1035,8 @@ struct ValueHistory { float rolling_sum_sq = 0; float rolling_mean = 0; void add_sample(float t) { + last_value_valid = false; + rolling_sum -= samples[next_sample].value; rolling_sum_sq -= samples[next_sample].value_sq; @@ -1052,10 +1054,13 @@ struct ValueHistory { float get_std_dev() { // Important note: this is a POPULATION standard deviation, not a population standard deviation float variance = (rolling_sum_sq/(float)sampled) - (rolling_mean*rolling_mean); - return sqrt(std::abs(variance)); + return std::sqrt(std::abs(variance)); }; + float last_value = 0; + bool last_value_valid = false; float value() { + if (last_value_valid) { return last_value; } // we'll shoot through the samples and ignore the outliers uint16_t samples_kept = 0; float temp = 0; @@ -1073,7 +1078,10 @@ struct ValueHistory { return rolling_mean; } - return (temp / (float)samples_kept); + last_value = (temp / (float)samples_kept); + last_value_valid = true; + + return last_value; }; }; @@ -1087,7 +1095,7 @@ struct gpioAnalogInputPin : gpioAnalogInput { uint8_t ext_pin_number; // the number used externally for this pin ("in" + ext_pin_number) const float variance_max = 1.1; - ValueHistory<20> history {variance_max}; + ValueHistory<40> history {variance_max}; float last_raw_value; @@ -1104,7 +1112,7 @@ struct gpioAnalogInputPin : gpioAnalogInput { pin{Motate::kNormal, [&]{this->adc_has_new_value();}, std::forward(additional_values)...} { pin.setInterrupts(Motate::kPinInterruptOnChange|Motate::kInterruptPriorityLow); - pin.setVoltageRange(3.29, 0.0, 3.29, 1000000.0); + pin.setVoltageRange(3.29, 0.0, 3.29, 100.0); }; // functions for use by other parts of the code, and are overridden From f9ac1c7a6f01d5c6f2900e0ed4d53d32054d24c4 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Mon, 26 Mar 2018 14:36:19 -0500 Subject: [PATCH 185/193] Remove leftover ifdefs --- g2core/plan_exec.cpp | 3 --- 1 file changed, 3 deletions(-) diff --git a/g2core/plan_exec.cpp b/g2core/plan_exec.cpp index ac8528cb2..948e64052 100644 --- a/g2core/plan_exec.cpp +++ b/g2core/plan_exec.cpp @@ -1017,8 +1017,6 @@ static stat_t _exec_aline_segment() float adjusted_target[AXES]; for (uint8_t a=0; a Date: Mon, 26 Mar 2018 15:07:43 -0500 Subject: [PATCH 186/193] Remove spring offset code --- g2core/canonical_machine.cpp | 27 -------- g2core/canonical_machine.h | 9 --- g2core/config_app.cpp | 3 - g2core/plan_exec.cpp | 48 +------------ g2core/plan_line.cpp | 21 +++--- g2core/planner.h | 76 ++++++++++----------- g2core/settings/settings_Ultimaker_2_Plus.h | 2 - g2core/settings/settings_default.h | 6 -- 8 files changed, 48 insertions(+), 144 deletions(-) diff --git a/g2core/canonical_machine.cpp b/g2core/canonical_machine.cpp index 1d6a2e388..4c6375680 100644 --- a/g2core/canonical_machine.cpp +++ b/g2core/canonical_machine.cpp @@ -2757,26 +2757,6 @@ stat_t cm_set_mto(nvObj_t *nv) return(STAT_OK); } -/* - * cm_get_so() - get spring factor offset - * - */ - -stat_t cm_get_so(nvObj_t *nv) -{ - if (cm_get_motion_state() == MOTION_STOP) { - nv->value = 0; - } else { - nv->value = mp_get_runtime_spring_value(_get_axis(nv->index)); - if (cm_get_units_mode(RUNTIME) == INCHES) { - nv->value *= INCHES_PER_MM; - } - } - nv->precision = GET_TABLE_WORD(precision); - nv->valuetype = TYPE_FLOAT; - return (STAT_OK); -} - /* * Commands * @@ -2992,9 +2972,6 @@ static const char fmt_Xtn[] = "[%s%s] %s travel minimum%17.3f%s\n"; static const char fmt_Xjm[] = "[%s%s] %s jerk maximum%15.0f%s/min^3 * 1 million\n"; static const char fmt_Xjh[] = "[%s%s] %s jerk homing%16.0f%s/min^3 * 1 million\n"; static const char fmt_Xra[] = "[%s%s] %s radius value%20.4f%s\n"; -static const char fmt_Xsf[] = "[%s%s] %s spring offset factor%20.4f%s\n"; -static const char fmt_Xsm[] = "[%s%s] %s spring offset max%20.4f%s\n"; -static const char fmt_Xso[] = "[%s%s] %s spring offset%20.4f%s\n"; static const char fmt_Xhi[] = "[%s%s] %s homing input%15d [input 1-N or 0 to disable homing this axis]\n"; static const char fmt_Xhd[] = "[%s%s] %s homing direction%11d [0=search-to-negative, 1=search-to-positive]\n"; static const char fmt_Xsv[] = "[%s%s] %s search velocity%12.0f%s/min\n"; @@ -3072,10 +3049,6 @@ void cm_print_jm(nvObj_t *nv) { _print_axis_flt(nv, fmt_Xjm);} void cm_print_jh(nvObj_t *nv) { _print_axis_flt(nv, fmt_Xjh);} void cm_print_ra(nvObj_t *nv) { _print_axis_flt(nv, fmt_Xra);} -void cm_print_sf(nvObj_t *nv) { _print_axis_flt(nv, fmt_Xsf);} -void cm_print_sm(nvObj_t *nv) { _print_axis_flt(nv, fmt_Xsm);} -void cm_print_so(nvObj_t *nv) { _print_axis_flt(nv, fmt_Xso);} - void cm_print_hi(nvObj_t *nv) { _print_axis_ui8(nv, fmt_Xhi);} void cm_print_hd(nvObj_t *nv) { _print_axis_ui8(nv, fmt_Xhd);} void cm_print_sv(nvObj_t *nv) { _print_axis_flt(nv, fmt_Xsv);} diff --git a/g2core/canonical_machine.h b/g2core/canonical_machine.h index f54493426..2dfddb9a3 100644 --- a/g2core/canonical_machine.h +++ b/g2core/canonical_machine.h @@ -384,9 +384,6 @@ typedef struct cmAxis { float latch_velocity; // homing latch velocity float latch_backoff; // backoff sufficient to clear a switch float zero_backoff; // backoff from switches for machine zero - - float spring_offset_factor; // factor of feed offset (sof * velocity = spring_offset) - float spring_offset_max; // max amount of spring offset compensation allowed } cfgAxis_t; typedef struct cmSingleton { // struct to manage cm globals and cycles @@ -708,8 +705,6 @@ stat_t cm_set_jh(nvObj_t *nv); // set jerk high with 1,000,000 correcti stat_t cm_set_mfo(nvObj_t *nv); // set manual feedrate override factor stat_t cm_set_mto(nvObj_t *nv); // set manual traverse override factor -stat_t cm_get_so(nvObj_t *nv); // get spring factor offset - stat_t cm_set_probe(nvObj_t *nv); // store current position as the latest probe @@ -780,10 +775,6 @@ stat_t cm_get_nxln(nvObj_t *nv); // return what value we expect the next line void cm_print_jh(nvObj_t *nv); void cm_print_ra(nvObj_t *nv); - void cm_print_sf(nvObj_t *nv); - void cm_print_sm(nvObj_t *nv); - void cm_print_so(nvObj_t *nv); - void cm_print_hi(nvObj_t *nv); void cm_print_hd(nvObj_t *nv); void cm_print_sv(nvObj_t *nv); diff --git a/g2core/config_app.cpp b/g2core/config_app.cpp index 9a3fb035e..754314b2f 100644 --- a/g2core/config_app.cpp +++ b/g2core/config_app.cpp @@ -443,9 +443,6 @@ const cfgItem_t cfgArray[] = { { "a","ajm",_fip, 0, cm_print_jm, get_flt, cm_set_jm, (float *)&cm.a[AXIS_A].jerk_max, A_JERK_MAX }, { "a","ajh",_fip, 0, cm_print_jh, get_flt, cm_set_jh, (float *)&cm.a[AXIS_A].jerk_high, A_JERK_HIGH_SPEED }, { "a","ara",_fipc, 3, cm_print_ra, get_flt, set_flt, (float *)&cm.a[AXIS_A].radius, A_RADIUS}, - { "a","asf",_fipc, 3, cm_print_sf, get_flt, set_flt, (float *)&cm.a[AXIS_A].spring_offset_factor, A_SPRING_OFFSET_FACTOR}, - { "a","asm",_fipc, 3, cm_print_sm, get_flt, set_flt, (float *)&cm.a[AXIS_A].spring_offset_max, A_SPRING_OFFSET_MAX}, - { "a","aso", _f0, 3, cm_print_so, cm_get_so, set_ro, (float *)&cs.null, 0 }, { "a","ahi",_fip, 0, cm_print_hi, get_ui8, cm_set_hi, (float *)&cm.a[AXIS_A].homing_input, A_HOMING_INPUT }, { "a","ahd",_fip, 0, cm_print_hd, get_ui8, set_01, (float *)&cm.a[AXIS_A].homing_dir, A_HOMING_DIRECTION }, { "a","asv",_fip, 0, cm_print_sv, get_flt, set_fltp, (float *)&cm.a[AXIS_A].search_velocity,A_SEARCH_VELOCITY }, diff --git a/g2core/plan_exec.cpp b/g2core/plan_exec.cpp index 948e64052..e43f3b0d7 100644 --- a/g2core/plan_exec.cpp +++ b/g2core/plan_exec.cpp @@ -1013,46 +1013,6 @@ static stat_t _exec_aline_tail(mpBuf_t *bf) static stat_t _exec_aline_segment() { float travel_steps[MOTORS]; - // we don't want to keep the adjusted target in the recorded position, so we'll adjust after - float adjusted_target[AXES]; - - for (uint8_t a=0; a= 0.0) ? cm.a[a].velocity_max : -cm.a[a].velocity_max; - float max_axis_travel = (mr.segment_velocity+directional_velocity_max) * 0.5 * mr.segment_time; - - // if the A axis is still, OR is the only axis moving, kill the remaining spring offset - if ((mr.axis_flags[a] || !(mr.axis_flags[AXIS_X] || mr.axis_flags[AXIS_Y] || mr.axis_flags[AXIS_Z])) && - mr.spring_offset[a] > 0.0001 - ) - { - // this axis isn't moving, so return offset to zero - // retract backward as fast as allowed, but don't go past 0.0 (positively or negatively) - new_spring_offset = mr.spring_offset[a] + (max_axis_travel - axis_travel); - new_spring_offset = (mr.unit[a] >= 0.0) ? - std::max(0.0f, new_spring_offset) : - std::min(0.0f, new_spring_offset); - } else { - new_spring_offset = cm.a[a].spring_offset_factor * avg_axis_velocity; - - if (std::abs(max_axis_travel) < std::abs(axis_travel+(new_spring_offset - mr.spring_offset[a]))) { - // adjust new_spring_offset down to meet maximum velocity - new_spring_offset = mr.spring_offset[a] + (max_axis_travel - axis_travel); - } - } - new_spring_offset = std::max(-cm.a[a].spring_offset_max, std::min(cm.a[a].spring_offset_max, new_spring_offset)); - mr.spring_offset[a] = new_spring_offset; - } else - { - mr.spring_offset[a] = 0; - } - } - // Set target position for the segment // If the segment ends on a section waypoint synchronize to the head, body or tail end @@ -1078,11 +1038,6 @@ static stat_t _exec_aline_segment() mr.gm.target[a] = target; } } - copy_vector(adjusted_target, mr.gm.target); - { - uint8_t a = AXIS_A; - adjusted_target[a] += mr.spring_offset[a]; - } // Convert target position to steps // Bucket-brigade the old target down the chain before getting the new target from kinematics @@ -1090,14 +1045,13 @@ static stat_t _exec_aline_segment() // NB: The direct manipulation of steps to compute travel_steps only works for Cartesian kinematics. // Other kinematics may require transforming travel distance as opposed to simply subtracting steps. - for (uint8_t m=0; mtarget[0] * cm.rotation_matrix[0][0] + + target_rotated[0] = gm_in->target[0] * cm.rotation_matrix[0][0] + gm_in->target[1] * cm.rotation_matrix[0][1] + gm_in->target[2] * cm.rotation_matrix[0][2]; - target_rotated[1] = gm_in->target[0] * cm.rotation_matrix[1][0] + + target_rotated[1] = gm_in->target[0] * cm.rotation_matrix[1][0] + gm_in->target[1] * cm.rotation_matrix[1][1] + gm_in->target[2] * cm.rotation_matrix[1][2]; - target_rotated[2] = gm_in->target[0] * cm.rotation_matrix[2][0] + + target_rotated[2] = gm_in->target[0] * cm.rotation_matrix[2][0] + gm_in->target[1] * cm.rotation_matrix[2][1] + - gm_in->target[2] * cm.rotation_matrix[2][2] + + gm_in->target[2] * cm.rotation_matrix[2][2] + cm.rotation_z_offset; // copy rotation axes ABC @@ -240,7 +239,7 @@ stat_t mp_aline(GCodeState_t* gm_in) * a replan, which is useful for feedholds and feed overrides. */ -void mp_plan_block_list() +void mp_plan_block_list() { mpBuf_t* bf = mp.p; bool planned_something = false; @@ -274,7 +273,7 @@ void mp_plan_block_list() * _plan_block() - the block chain using pessimistic assumptions */ -static mpBuf_t* _plan_block(mpBuf_t* bf) +static mpBuf_t* _plan_block(mpBuf_t* bf) { // First time blocks - set vmaxes for as many blocks as possible (forward loading of priming blocks) // Note: cruise_vmax was computed in _calculate_vmaxes() in aline() @@ -610,7 +609,7 @@ static void _calculate_jerk(mpBuf_t* bf) * so that the elapsed time from the start to the end of the motion is T plus * any time required for acceleration or deceleration. */ -static void _calculate_vmaxes(mpBuf_t* bf, const float axis_length[], const float axis_square[]) +static void _calculate_vmaxes(mpBuf_t* bf, const float axis_length[], const float axis_square[]) { float feed_time = 0; // one of: XYZ time, ABC time or inverse time. Mutually exclusive float max_time = 0; // time required for the rate-limiting axis @@ -695,7 +694,7 @@ static void _calculate_vmaxes(mpBuf_t* bf, const float axis_length[], const floa * C) The last move (there is not "next move" yet) will have to compate to a unit vector of zero. */ -static void _calculate_junction_vmax(mpBuf_t* bf) +static void _calculate_junction_vmax(mpBuf_t* bf) { // (C) special case for planning the last block if (bf->nx->buffer_state == MP_BUFFER_EMPTY) { diff --git a/g2core/planner.h b/g2core/planner.h index 791426ad8..a10cac314 100644 --- a/g2core/planner.h +++ b/g2core/planner.h @@ -28,7 +28,7 @@ /*x * --- Planner Background --- * - * The planner is a complicated beast that takes a lot of things into account. + * The planner is a complicated beast that takes a lot of things into account. * Planner documentation is scattered about and co-located with the functions * that perform the actions. Key files are: * @@ -42,31 +42,31 @@ * * --- Planner Overview --- * - * At high level the planner's job is to reconstruct smooth motion from a set of linear - * approximations while observing and operating within the physical constraints of the - * machine and the physics of motion. Gcode - which consists of a series of into linear - * motion segments - is interpreted, queued to the planner, and joined together to produce - * continuous, synchronized motion. Non-motion commands such as pauses (dwells) and - * peripheral controls such as spindles can also be synchronized in the queue. Arcs are + * At high level the planner's job is to reconstruct smooth motion from a set of linear + * approximations while observing and operating within the physical constraints of the + * machine and the physics of motion. Gcode - which consists of a series of into linear + * motion segments - is interpreted, queued to the planner, and joined together to produce + * continuous, synchronized motion. Non-motion commands such as pauses (dwells) and + * peripheral controls such as spindles can also be synchronized in the queue. Arcs are * just a special case consisting of many linear moves. Arcs are not interpreted directly. * - * The planner sits in the middle of three system layers: + * The planner sits in the middle of three system layers: * - The Gcode interpreter and canonical machine (the 'model'), which feeds... * - The planner - taking generic commands from the model and queuing them for... * - The runtime layer - pulling from the planner and driving stepper motors or other devices - * + * * The planner queue is the heart of the planner. It's a circular list of ~48 complex structures * that carry the state of the system needs to execute a linear motion, run a pre-planned command, * like turning on a spindle, or executing an arbitrary JSON command such as an active comment. * * The queue can be viewed as a list of instructions that will execute in exact sequence. - * Some instructions control motion and need to be joined to their forward and backwards - * neighbors so that position, velocity, acceleration, and jerk constraints are not - * violated when moving from one motion to the next. + * Some instructions control motion and need to be joined to their forward and backwards + * neighbors so that position, velocity, acceleration, and jerk constraints are not + * violated when moving from one motion to the next. * * Others are "commands" that are actually just function callbacks that happen to execute * at a particular point in time (synchronized with motion commands). Commands can control - * anything you can reasonably program, such as digital IO, serial communications, or + * anything you can reasonably program, such as digital IO, serial communications, or * interpreted commands encoded in JSON. * * The buffers in the planner queue are treated as a 'closure' - with all state needed for @@ -79,56 +79,56 @@ * - mp_aline() - plan and queue a move with acceleration management * - mp_dwell() - plan and queue a pause (dwell) to the planner queue * - mp_queue_command() - queue a canned command - * - mp_json_command() - queue a JSON command for run-time interpretation and execution (M100) + * - mp_json_command() - queue a JSON command for run-time interpretation and execution (M100) * - mp_json_wait() - queue a JSON wait for run-time interpretation and execution (M101) - * - - * In addition, cm_arc_feed() valaidates and sets up a arc paramewters and calls mp_aline() + * - + * In addition, cm_arc_feed() valaidates and sets up a arc paramewters and calls mp_aline() * repeatedly to spool out the arc segments into the planner queue. * * All the above queueing commands other than mp_aline() are relatively trivial; they just - * post callbacks into the next available planner buffer. Command functions are in 2 parts: - * the part that posts to the queue, and the callback that is executed when the command is + * post callbacks into the next available planner buffer. Command functions are in 2 parts: + * the part that posts to the queue, and the callback that is executed when the command is * finally reached in the queue - the _exec(). * - * All mp_aline() does is some preliminary math and then posts an initialized buffer to + * All mp_aline() does is some preliminary math and then posts an initialized buffer to * the planner queue. The rest of the move planning operations takes place in background; - * via mp_planner_callback() called from the main loop, and as 'pulls' from the runtime + * via mp_planner_callback() called from the main loop, and as 'pulls' from the runtime * stepper operations. * - * Motion planning is separated into backward planning and forward planning stages. - * Backward planning is initiated by mp_planner_callback() which is called repeatedly - * from the main loop. Backwards planning is performed by mp_plan_block_list() and - * _plan_block(). It starts at the most recently arrived Gcode block. Backward - * planning can occur multiple times for a given buffer, as new moves arriving + * Motion planning is separated into backward planning and forward planning stages. + * Backward planning is initiated by mp_planner_callback() which is called repeatedly + * from the main loop. Backwards planning is performed by mp_plan_block_list() and + * _plan_block(). It starts at the most recently arrived Gcode block. Backward + * planning can occur multiple times for a given buffer, as new moves arriving * can make the motion profile more optimal. * * Backward planning uses velocity and jerk constraints to set maximum entry, - * travel (cruise) and exit velocities for the moves in the queue. In addition, - * it observes the maximum cornering velocities that adjoining moves can sustain - * in a corner or a 'kink' to ensure that the jerk limit of any axis participating + * travel (cruise) and exit velocities for the moves in the queue. In addition, + * it observes the maximum cornering velocities that adjoining moves can sustain + * in a corner or a 'kink' to ensure that the jerk limit of any axis participating * in the move is not violated. See mp_planner_callback() header comments for more detail. * - * Forward planning is performed just-in-time and only once, right before the + * Forward planning is performed just-in-time and only once, right before the * planner runtime needs the next buffer. Forward planning provides the final - * contouring of the move. It is invoked by mp_forward_plan() and executed by + * contouring of the move. It is invoked by mp_forward_plan() and executed by * mp_calculate_ramps() in plan_zoid.cpp. * * Planner timing operates at a few different levels: * - * - New lines of ASCII containing commands and moves arriving from the USB are + * - New lines of ASCII containing commands and moves arriving from the USB are * parsed and executed as the lowest priority background task from the main loop. * - * - Backward planning is invoked by a main loop callback, so it also executes as + * - Backward planning is invoked by a main loop callback, so it also executes as * a background task, albeit a higher priority one. * - * - Forward planning and the ultimate preparation of the move for the runtime runs - * as an interrupt as a 'pull' from the planner queue that uses a series of - * interrupts at progressively lower priorities to ensure that the next planner + * - Forward planning and the ultimate preparation of the move for the runtime runs + * as an interrupt as a 'pull' from the planner queue that uses a series of + * interrupts at progressively lower priorities to ensure that the next planner * buffer is ready before the runtime runs out of forward-planned moves and starves. * * Some other functions performed by the planner include: * - * - Velocity throttling to ensure that very short moves do not execute faster + * - Velocity throttling to ensure that very short moves do not execute faster * than the serial interface can deliver them * * - Feed hold and cycle start (resume) operations @@ -364,7 +364,7 @@ struct mpBuffer_to_clear { void reset() { //memset((void *)(this), 0, sizeof(mpBuffer_to_clear)); - + bf_func = nullptr; cm_func = nullptr; @@ -487,7 +487,6 @@ typedef struct mpMotionRuntimeSingleton { // persistent runtime variables sectionState section_state; // state within a move section float unit[AXES]; // unit vector for axis scaling & planning - float spring_offset[AXES]; // amount of spring offset compensation in effect per axis bool axis_flags[AXES]; // set true for axes participating in the move float target[AXES]; // final target for bf (used to correct rounding errors) float position[AXES]; // current move position @@ -591,7 +590,6 @@ float mp_get_runtime_work_position(uint8_t axis); void mp_set_runtime_work_offset(float offset[]); bool mp_get_runtime_busy(void) HOT_FUNC; bool mp_runtime_is_idle(void) HOT_FUNC; -float mp_get_runtime_spring_value(uint8_t axis); stat_t mp_aline(GCodeState_t *gm_in) HOT_FUNC; // line planning... void mp_plan_block_list(void) HOT_FUNC; diff --git a/g2core/settings/settings_Ultimaker_2_Plus.h b/g2core/settings/settings_Ultimaker_2_Plus.h index 0fb64f28f..350ebeb7f 100644 --- a/g2core/settings/settings_Ultimaker_2_Plus.h +++ b/g2core/settings/settings_Ultimaker_2_Plus.h @@ -336,8 +336,6 @@ #define A_JERK_HIGH_SPEED 2000.0 // NYLON //#define A_JERK_HIGH_SPEED 35000.0 // ~30 million mm/min^3 {ajh:35000.0} -#define A_SPRING_OFFSET_FACTOR 0 -#define A_SPRING_OFFSET_MAX 100 #define B_AXIS_MODE AXIS_RADIUS diff --git a/g2core/settings/settings_default.h b/g2core/settings/settings_default.h index 9c5da27d4..8a2713863 100644 --- a/g2core/settings/settings_default.h +++ b/g2core/settings/settings_default.h @@ -817,12 +817,6 @@ #ifndef A_ZERO_BACKOFF #define A_ZERO_BACKOFF 2.0 #endif -#ifndef A_SPRING_OFFSET_FACTOR -#define A_SPRING_OFFSET_FACTOR 0 -#endif -#ifndef A_SPRING_OFFSET_MAX -#define A_SPRING_OFFSET_MAX 0 -#endif // B AXIS #ifndef B_AXIS_MODE From 71e0400f6f985a80944eca1390fa7c92c8af9044 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Wed, 28 Mar 2018 14:17:02 -0500 Subject: [PATCH 187/193] Minor adjustments to GPIO --- g2core/gpio.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/g2core/gpio.h b/g2core/gpio.h index 85e1d2f34..8ed75527e 100644 --- a/g2core/gpio.h +++ b/g2core/gpio.h @@ -380,13 +380,13 @@ struct gpioDigitalInputPin final : gpioDigitalInput { bool homing_mode; // set true when input is in homing mode. bool probing_mode; // set true when input is in probing mode. - const uint8_t ext_pin_number; // the number used externally for this pin ("din" + ext_pin_number) - uint8_t proxy_pin_number; // the number used externally for this pin ("in" + proxy_pin_number) + const uint8_t ext_pin_number; // the number used externally for this pin ("din" + ext_pin_number) + uint8_t proxy_pin_number; // the number used externally for this pin ("in" + proxy_pin_number) uint16_t lockout_ms; // number of milliseconds for debounce lockout Motate::Timeout lockout_timer; // time to expire current debounce lockout, or 0 if no lockout - Pin_t pin; // the actual pin object itself + Pin_t pin; // the actual pin object itself // In constructor, simply forward all values to the Pin_t // To get a different behavior, override this object. @@ -827,7 +827,7 @@ struct gpioDigitalOutputPin final : gpioDigitalOutput { bool setPolarity(const ioPolarity new_polarity) override { polarity = new_polarity; - pin.setOptions((polarity == IO_ACTIVE_LOW) ? kPullUp|kDebounce : kDebounce); + pin.setOptions((polarity == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow); return true; }; From fc93693d39eb246ae258de277130b708a9d610b0 Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Wed, 28 Mar 2018 14:29:08 -0500 Subject: [PATCH 188/193] gpioDigitalOutputReader -> gpioDigitalOutputWriter, and 16 instead of 14 --- g2core/gpio.cpp | 54 ++++++++++++++++++++++++++----------------------- g2core/gpio.h | 40 ++++++++++++++++++------------------ 2 files changed, 49 insertions(+), 45 deletions(-) diff --git a/g2core/gpio.cpp b/g2core/gpio.cpp index 7d7c05575..1a146ea0b 100644 --- a/g2core/gpio.cpp +++ b/g2core/gpio.cpp @@ -130,7 +130,7 @@ type* _io(const nvObj_t *nv) { gpioDigitalInput* _i(const nvObj_t *nv) { return _io(nv); } gpioDigitalInputReader* _ir(const nvObj_t *nv) { return _io(nv); } gpioDigitalOutput* _o(const nvObj_t *nv) { return _io(nv); } -gpioDigitalOutputReader* _or(const nvObj_t *nv) { return _io(nv); } +gpioDigitalOutputWriter* _ow(const nvObj_t *nv) { return _io(nv); } gpioAnalogInput* _ai(const nvObj_t *nv) { return _io(nv); } gpioDigitalInputReader in1; @@ -147,25 +147,29 @@ gpioDigitalInputReader in11; gpioDigitalInputReader in12; gpioDigitalInputReader in13; gpioDigitalInputReader in14; - -gpioDigitalInputReader* const in_r[14] = {&in1, &in2, &in3, &in4, &in5, &in6, &in7, &in8, &in9, &in10, &in11, &in12, &in13, &in14}; - -gpioDigitalOutputReader out1; -gpioDigitalOutputReader out2; -gpioDigitalOutputReader out3; -gpioDigitalOutputReader out4; -gpioDigitalOutputReader out5; -gpioDigitalOutputReader out6; -gpioDigitalOutputReader out7; -gpioDigitalOutputReader out8; -gpioDigitalOutputReader out9; -gpioDigitalOutputReader out10; -gpioDigitalOutputReader out11; -gpioDigitalOutputReader out12; -gpioDigitalOutputReader out13; -gpioDigitalOutputReader out14; - -gpioDigitalOutputReader* const out_r[14] = {&out1 ,&out2 ,&out3 ,&out4 ,&out5 ,&out6 ,&out7 ,&out8 ,&out9 ,&out10 ,&out11 ,&out12 ,&out13 ,&out14}; +gpioDigitalInputReader in15; +gpioDigitalInputReader in16; + +gpioDigitalInputReader* const in_r[16] = {&in1, &in2, &in3, &in4, &in5, &in6, &in7, &in8, &in9, &in10, &in11, &in12, &in13, &in14, &in15, &in16}; + +gpioDigitalOutputWriter out1; +gpioDigitalOutputWriter out2; +gpioDigitalOutputWriter out3; +gpioDigitalOutputWriter out4; +gpioDigitalOutputWriter out5; +gpioDigitalOutputWriter out6; +gpioDigitalOutputWriter out7; +gpioDigitalOutputWriter out8; +gpioDigitalOutputWriter out9; +gpioDigitalOutputWriter out10; +gpioDigitalOutputWriter out11; +gpioDigitalOutputWriter out12; +gpioDigitalOutputWriter out13; +gpioDigitalOutputWriter out14; +gpioDigitalOutputWriter out15; +gpioDigitalOutputWriter out16; + +gpioDigitalOutputWriter* const out_w[14] = {&out1, &out2, &out3, &out4, &out5, &out6, &out7, &out8, &out9, &out10, &out11, &out12, &out13, &out14, &out15, &out16}; // lists for the various inputAction events gpioDigitalInputHandlerList din_handlers[INPUT_ACTION_ACTUAL_MAX+1]; @@ -247,7 +251,7 @@ stat_t dout_set_en(nvObj_t *nv) } /* - * Get/set input polarity + * Get/set output polarity */ stat_t dout_get_po(nvObj_t *nv) { @@ -259,7 +263,7 @@ stat_t dout_set_po(nvObj_t *nv) } /* - * Get/set input polarity + * Get/set output external number */ stat_t dout_get_out(nvObj_t *nv) { @@ -272,15 +276,15 @@ stat_t dout_set_out(nvObj_t *nv) /* - * Gget/set output state given an nv object + * Get/set output state given an nv object */ stat_t dout_get_output(nvObj_t *nv) { - return _or(nv)->getValue(nv); + return _ow(nv)->getValue(nv); } stat_t dout_set_output(nvObj_t *nv) { - return _or(nv)->setValue(nv); + return _ow(nv)->setValue(nv); } diff --git a/g2core/gpio.h b/g2core/gpio.h index 8ed75527e..b2f080abe 100644 --- a/g2core/gpio.h +++ b/g2core/gpio.h @@ -592,8 +592,8 @@ struct gpioDigitalInputPin final : gpioDigitalInput { // forward declare -struct gpioDigitalOutputReader; -extern gpioDigitalOutputReader* const out_r[14]; +struct gpioDigitalOutputWriter; +extern gpioDigitalOutputWriter* const out_w[16]; /* * gpioDigitalOutput - digital/PWM output base class @@ -713,10 +713,10 @@ struct gpioDigitalOutput { /* - * gpioDigitalOutputReader - digital output reader class - the "out1" - "outX" objects + * gpioDigitalOutputWriter - digital output reader class - the "out1" - "outX" objects */ -struct gpioDigitalOutputReader final { +struct gpioDigitalOutputWriter final { gpioDigitalOutput* pin; // functions for use by other parts of the code @@ -762,20 +762,20 @@ struct gpioDigitalOutputReader final { }; // setup the gpioDigitalInputReader objects as extern -extern gpioDigitalOutputReader out1; -extern gpioDigitalOutputReader out2; -extern gpioDigitalOutputReader out3; -extern gpioDigitalOutputReader out4; -extern gpioDigitalOutputReader out5; -extern gpioDigitalOutputReader out6; -extern gpioDigitalOutputReader out7; -extern gpioDigitalOutputReader out8; -extern gpioDigitalOutputReader out9; -extern gpioDigitalOutputReader out10; -extern gpioDigitalOutputReader out11; -extern gpioDigitalOutputReader out12; -extern gpioDigitalOutputReader out13; -extern gpioDigitalOutputReader out14; +extern gpioDigitalOutputWriter out1; +extern gpioDigitalOutputWriter out2; +extern gpioDigitalOutputWriter out3; +extern gpioDigitalOutputWriter out4; +extern gpioDigitalOutputWriter out5; +extern gpioDigitalOutputWriter out6; +extern gpioDigitalOutputWriter out7; +extern gpioDigitalOutputWriter out8; +extern gpioDigitalOutputWriter out9; +extern gpioDigitalOutputWriter out10; +extern gpioDigitalOutputWriter out11; +extern gpioDigitalOutputWriter out12; +extern gpioDigitalOutputWriter out13; +extern gpioDigitalOutputWriter out14; /* @@ -862,12 +862,12 @@ struct gpioDigitalOutputPin final : gpioDigitalOutput { if (e == proxy_pin_number) { return true; } if (proxy_pin_number > 0) { // clear the old pin - out_r[proxy_pin_number-1]->setPin(nullptr); + out_w[proxy_pin_number-1]->setPin(nullptr); } proxy_pin_number = e; if (proxy_pin_number > 0) { // set the new pin - out_r[proxy_pin_number-1]->setPin(this); + out_w[proxy_pin_number-1]->setPin(this); } return true; }; From 57b34d1a5724bcb9469cd789596d1059da5cdb9c Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Thu, 29 Mar 2018 10:25:27 -0500 Subject: [PATCH 189/193] `inM` and `outM` go to `M`=16, `ainN`->`aiN`, added `ainM`, added `aiNen`, removed `gpio_get_probing_input()` --- g2core/board/gquintic/board_gpio.cpp | 26 +-- g2core/board/gquintic/board_gpio.h | 32 +++- g2core/boards.mk | 2 +- g2core/config_app.cpp | 89 +++++---- g2core/cycle_probing.cpp | 2 +- g2core/device/max31865/max31865.h | 28 ++- g2core/gpio.cpp | 102 +++++----- g2core/gpio.h | 271 ++++++++++++++++++++++----- 8 files changed, 405 insertions(+), 147 deletions(-) diff --git a/g2core/board/gquintic/board_gpio.cpp b/g2core/board/gquintic/board_gpio.cpp index 2d3183cef..76f1ed70f 100644 --- a/g2core/board/gquintic/board_gpio.cpp +++ b/g2core/board/gquintic/board_gpio.cpp @@ -91,10 +91,10 @@ gpioDigitalOutput* const d_out[] = {&dout1, &dout2, &dout3, &dout4, &dout5, &dou #if QUINTIC_REVISION == 'C' -gpioAnalogInputPin> ain1 {gpioAnalogInput::AIN_TYPE_EXTERNAL, 1, spiBus, spiCSPinMux.getCS(5)}; -gpioAnalogInputPin> ain2 {gpioAnalogInput::AIN_TYPE_EXTERNAL, 2, spiBus, spiCSPinMux.getCS(6)}; -gpioAnalogInputPin> ain3 {gpioAnalogInput::AIN_TYPE_INTERNAL, 3}; -gpioAnalogInputPin> ain4 {gpioAnalogInput::AIN_TYPE_INTERNAL, 4}; +gpioAnalogInputPin> ai1 {AI1_ENABLED, gpioAnalogInput::AIN_TYPE_EXTERNAL, 1, AI1_EXTERNAL_NUMBER, spiBus, spiCSPinMux.getCS(5)}; +gpioAnalogInputPin> ai2 {AI2_ENABLED, gpioAnalogInput::AIN_TYPE_EXTERNAL, 2, AI2_EXTERNAL_NUMBER, spiBus, spiCSPinMux.getCS(6)}; +gpioAnalogInputPin> ai3 {AI3_ENABLED, gpioAnalogInput::AIN_TYPE_INTERNAL, 3, AI3_EXTERNAL_NUMBER}; +gpioAnalogInputPin> ai4 {AI4_ENABLED, gpioAnalogInput::AIN_TYPE_INTERNAL, 4, AI4_EXTERNAL_NUMBER}; gpioAnalogInput* const a_in[] = {&ain1, &ain2, &ain3, &ain4}; @@ -102,12 +102,12 @@ gpioAnalogInput* const a_in[] = {&ain1, &ain2, &ain3, &ain4}; #if QUINTIC_REVISION == 'D' -gpioAnalogInputPin> ain1 {gpioAnalogInput::AIN_TYPE_INTERNAL, 1}; -gpioAnalogInputPin> ain2 {gpioAnalogInput::AIN_TYPE_INTERNAL, 2}; -gpioAnalogInputPin> ain3 {gpioAnalogInput::AIN_TYPE_INTERNAL, 3}; -gpioAnalogInputPin> ain4 {gpioAnalogInput::AIN_TYPE_INTERNAL, 4}; +gpioAnalogInputPin> ai1 {AI1_ENABLED, gpioAnalogInput::AIN_TYPE_INTERNAL, 1, AI1_EXTERNAL_NUMBER}; +gpioAnalogInputPin> ai2 {AI2_ENABLED, gpioAnalogInput::AIN_TYPE_INTERNAL, 2, AI2_EXTERNAL_NUMBER}; +gpioAnalogInputPin> ai3 {AI3_ENABLED, gpioAnalogInput::AIN_TYPE_INTERNAL, 3, AI3_EXTERNAL_NUMBER}; +gpioAnalogInputPin> ai4 {AI4_ENABLED, gpioAnalogInput::AIN_TYPE_INTERNAL, 4, AI4_EXTERNAL_NUMBER}; -gpioAnalogInput* const a_in[] = {&ain1, &ain2, &ain3, &ain4}; +gpioAnalogInput* const a_in[] = {&ai1, &ai2, &ai3, &ai4}; #endif // 'D' @@ -122,10 +122,10 @@ gpioAnalogInput* const a_in[] = {&ain1, &ain2, &ain3, &ain4}; int16_t ain_sample_counter = ain_sample_freq; Motate::SysTickEvent ain_tick_event {[&] { if (!--ain_sample_counter) { - ain1.startSampling(); - ain2.startSampling(); - ain3.startSampling(); - ain4.startSampling(); + ai1.startSampling(); + ai2.startSampling(); + ai3.startSampling(); + ai4.startSampling(); ain_sample_counter = ain_sample_freq; } }, nullptr}; diff --git a/g2core/board/gquintic/board_gpio.h b/g2core/board/gquintic/board_gpio.h index ea4182464..1dedb7ad8 100644 --- a/g2core/board/gquintic/board_gpio.h +++ b/g2core/board/gquintic/board_gpio.h @@ -96,6 +96,9 @@ extern gpioDigitalOutput* const d_out[D_OUT_CHANNELS]; #include "device/max31865/max31865.h" #define USING_A_MAX31865 1 +#ifndef AI1_ENABLED +#define AI1_ENABLED IO_ENABLED +#endif #ifndef AI1_TYPE #define AI1_TYPE gpioAnalogInput::AIN_TYPE_EXTERNAL #endif @@ -104,6 +107,9 @@ extern gpioDigitalOutput* const d_out[D_OUT_CHANNELS]; #endif extern gpioAnalogInputPin> ain1; +#ifndef AI2_ENABLED +#define AI2_ENABLED IO_ENABLED +#endif #ifndef AI2_TYPE #define AI2_TYPE gpioAnalogInput::AIN_TYPE_EXTERNAL #endif @@ -112,6 +118,9 @@ extern gpioAnalogInputPin> ain1; #endif extern gpioAnalogInputPin> ain2; +#ifndef AI3_ENABLED +#define AI3_ENABLED IO_ENABLED +#endif #ifndef AI3_TYPE #define AI3_TYPE gpioAnalogInput::AIN_TYPE_INTERNAL #endif @@ -120,6 +129,9 @@ extern gpioAnalogInputPin> ain2; #endif extern gpioAnalogInputPin> ain3; +#ifndef AI4_ENABLED +#define AI4_ENABLED IO_ENABLED +#endif #ifndef AI4_TYPE #define AI4_TYPE gpioAnalogInput::AIN_TYPE_INTERNAL #endif @@ -134,37 +146,49 @@ extern gpioAnalogInputPin> ain1; +extern gpioAnalogInputPin> ai1; +#ifndef AI2_ENABLED +#define AI2_ENABLED IO_ENABLED +#endif #ifndef AI2_TYPE #define AI2_TYPE gpioAnalogInput::AIN_TYPE_INTERNAL #endif #ifndef AI2_CIRCUIT #define AI2_CIRCUIT gpioAnalogInput::AIN_CIRCUIT_CC_INV_OPAMP #endif -extern gpioAnalogInputPin> ain2; +extern gpioAnalogInputPin> ai2; +#ifndef AI3_ENABLED +#define AI3_ENABLED IO_ENABLED +#endif #ifndef AI3_TYPE #define AI3_TYPE gpioAnalogInput::AIN_TYPE_INTERNAL #endif #ifndef AI3_CIRCUIT #define AI3_CIRCUIT gpioAnalogInput::AIN_CIRCUIT_INV_OPAMP #endif -extern gpioAnalogInputPin> ain3; +extern gpioAnalogInputPin> ai3; +#ifndef AI4_ENABLED +#define AI4_ENABLED IO_ENABLED +#endif #ifndef AI4_TYPE #define AI4_TYPE gpioAnalogInput::AIN_TYPE_INTERNAL #endif #ifndef AI4_CIRCUIT #define AI4_CIRCUIT gpioAnalogInput::AIN_CIRCUIT_INV_OPAMP #endif -extern gpioAnalogInputPin> ain4; +extern gpioAnalogInputPin> ai4; #endif // 'D' diff --git a/g2core/boards.mk b/g2core/boards.mk index 4b7b7f534..16e553ab6 100644 --- a/g2core/boards.mk +++ b/g2core/boards.mk @@ -143,7 +143,7 @@ endif ifeq ("$(CONFIG)","PrintrbotPlayQuintic") ifeq ("$(BOARD)","NONE") - BOARD=gquintic-c + BOARD=gquintic-d endif SETTINGS_FILE="settings_Printrbot_Play.h" endif diff --git a/g2core/config_app.cpp b/g2core/config_app.cpp index 754314b2f..16ecc087d 100644 --- a/g2core/config_app.cpp +++ b/g2core/config_app.cpp @@ -579,6 +579,8 @@ const cfgItem_t cfgArray[] = { { "in","in12", _f0, 0, din_print_state, din_get_input, set_ro, (float *)&in12, 0 }, { "in","in13", _f0, 0, din_print_state, din_get_input, set_ro, (float *)&in13, 0 }, { "in","in14", _f0, 0, din_print_state, din_get_input, set_ro, (float *)&in14, 0 }, + { "in","in15", _f0, 0, din_print_state, din_get_input, set_ro, (float *)&in15, 0 }, + { "in","in16", _f0, 0, din_print_state, din_get_input, set_ro, (float *)&in16, 0 }, // digital output configs { "do1", "do1en", _fip, 0, dout_print_en, dout_get_en, dout_set_en, (float *)&dout1, DO1_ENABLED }, @@ -664,53 +666,68 @@ const cfgItem_t cfgArray[] = { { "out","out12", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&out12, 0 }, { "out","out13", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&out13, 0 }, { "out","out14", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&out14, 0 }, + { "out","out15", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&out15, 0 }, + { "out","out16", _f0, 2, dout_print_out, dout_get_output, dout_set_output, (float *)&out16, 0 }, // Analog input configs #if (A_IN_CHANNELS >= 1) - { "ain1","ain1ty",_fip, 0, ain_print_type, ain_get_type, ain_set_type, (float *)&ain1, AI1_TYPE }, - { "ain1","ain1ct",_fip, 0, ain_print_circuit, ain_get_circuit, ain_set_circuit, (float *)&ain1, AI1_CIRCUIT }, - { "ain1","ain1p1",_fip, 4, ain_print_p, ain_get_p1, ain_set_p1, (float *)&ain1, AI1_P1 }, - { "ain1","ain1p2",_fip, 4, ain_print_p, ain_get_p2, ain_set_p2, (float *)&ain1, AI1_P2 }, - { "ain1","ain1p3",_fip, 4, ain_print_p, ain_get_p3, ain_set_p3, (float *)&ain1, AI1_P3 }, - { "ain1","ain1p4",_fip, 4, ain_print_p, ain_get_p4, ain_set_p4, (float *)&ain1, AI1_P4 }, - { "ain1","ain1p5",_fip, 4, ain_print_p, ain_get_p5, ain_set_p5, (float *)&ain1, AI1_P5 }, - { "ain1","ain1vv",_f0, 4, ain_print_value, ain_get_value, set_ro, (float *)&ain1, 0 }, - { "ain1","ain1rv",_f0, 2, ain_print_resistance, ain_get_resistance, set_ro, (float *)&ain1, 0 }, + { "ai1","ai1en",_fip, 0, ai_print_en, ai_get_en, ai_set_en, (float *)&ai1, AI1_ENABLED }, + { "ai1","ai1ty",_fip, 0, ai_print_type, ai_get_type, ai_set_type, (float *)&ai1, AI1_TYPE }, + { "ai1","ai1ct",_fip, 0, ai_print_circuit, ai_get_circuit, ai_set_circuit, (float *)&ai1, AI1_CIRCUIT }, + { "ai1","ai1p1",_fip, 4, ai_print_p, ai_get_p1, ai_set_p1, (float *)&ai1, AI1_P1 }, + { "ai1","ai1p2",_fip, 4, ai_print_p, ai_get_p2, ai_set_p2, (float *)&ai1, AI1_P2 }, + { "ai1","ai1p3",_fip, 4, ai_print_p, ai_get_p3, ai_set_p3, (float *)&ai1, AI1_P3 }, + { "ai1","ai1p4",_fip, 4, ai_print_p, ai_get_p4, ai_set_p4, (float *)&ai1, AI1_P4 }, + { "ai1","ai1p5",_fip, 4, ai_print_p, ai_get_p5, ai_set_p5, (float *)&ai1, AI1_P5 }, #endif #if (A_IN_CHANNELS >= 2) - { "ain2","ain2ty",_fip, 0, ain_print_type, ain_get_type, ain_set_type, (float *)&ain2, AI2_TYPE }, - { "ain2","ain2ct",_fip, 0, ain_print_circuit, ain_get_circuit, ain_set_circuit, (float *)&ain2, AI2_CIRCUIT }, - { "ain2","ain2p1",_fip, 4, ain_print_p, ain_get_p1, ain_set_p1, (float *)&ain2, AI2_P1 }, - { "ain2","ain2p2",_fip, 4, ain_print_p, ain_get_p2, ain_set_p2, (float *)&ain2, AI2_P2 }, - { "ain2","ain2p3",_fip, 4, ain_print_p, ain_get_p3, ain_set_p3, (float *)&ain2, AI2_P3 }, - { "ain2","ain2p4",_fip, 4, ain_print_p, ain_get_p4, ain_set_p4, (float *)&ain2, AI2_P4 }, - { "ain2","ain2p5",_fip, 4, ain_print_p, ain_get_p5, ain_set_p5, (float *)&ain2, AI2_P5 }, - { "ain2","ain2vv",_f0, 4, ain_print_value, ain_get_value, set_ro, (float *)&ain2, 0 }, - { "ain2","ain2rv",_f0, 2, ain_print_resistance, ain_get_resistance, set_ro, (float *)&ain2, 0 }, + { "ai2","ai2en",_fip, 0, ai_print_en, ai_get_en, ai_set_en, (float *)&ai2, AI2_ENABLED }, + { "ai2","ai2ty",_fip, 0, ai_print_type, ai_get_type, ai_set_type, (float *)&ai2, AI2_TYPE }, + { "ai2","ai2ct",_fip, 0, ai_print_circuit, ai_get_circuit, ai_set_circuit, (float *)&ai2, AI2_CIRCUIT }, + { "ai2","ai2p1",_fip, 4, ai_print_p, ai_get_p1, ai_set_p1, (float *)&ai2, AI2_P1 }, + { "ai2","ai2p2",_fip, 4, ai_print_p, ai_get_p2, ai_set_p2, (float *)&ai2, AI2_P2 }, + { "ai2","ai2p3",_fip, 4, ai_print_p, ai_get_p3, ai_set_p3, (float *)&ai2, AI2_P3 }, + { "ai2","ai2p4",_fip, 4, ai_print_p, ai_get_p4, ai_set_p4, (float *)&ai2, AI2_P4 }, + { "ai2","ai2p5",_fip, 4, ai_print_p, ai_get_p5, ai_set_p5, (float *)&ai2, AI2_P5 }, #endif #if (A_IN_CHANNELS >= 3) - { "ain3","ain3ty",_fip, 0, ain_print_type, ain_get_type, ain_set_type, (float *)&ain3, AI3_TYPE }, - { "ain3","ain3ct",_fip, 0, ain_print_circuit, ain_get_circuit, ain_set_circuit, (float *)&ain3, AI3_CIRCUIT }, - { "ain3","ain3p1",_fip, 4, ain_print_p, ain_get_p1, ain_set_p1, (float *)&ain3, AI3_P1 }, - { "ain3","ain3p2",_fip, 4, ain_print_p, ain_get_p2, ain_set_p2, (float *)&ain3, AI3_P2 }, - { "ain3","ain3p3",_fip, 4, ain_print_p, ain_get_p3, ain_set_p3, (float *)&ain3, AI3_P3 }, - { "ain3","ain3p4",_fip, 4, ain_print_p, ain_get_p4, ain_set_p4, (float *)&ain3, AI3_P4 }, - { "ain3","ain3p5",_fip, 4, ain_print_p, ain_get_p5, ain_set_p5, (float *)&ain3, AI3_P5 }, - { "ain3","ain3vv",_f0, 4, ain_print_value, ain_get_value, set_ro, (float *)&ain3, 0 }, - { "ain3","ain3rv",_f0, 2, ain_print_resistance, ain_get_resistance, set_ro, (float *)&ain3, 0 }, + { "ai3","ai3en",_fip, 0, ai_print_en, ai_get_en, ai_set_en, (float *)&ai3, AI3_ENABLED }, + { "ai3","ai3ty",_fip, 0, ai_print_type, ai_get_type, ai_set_type, (float *)&ai3, AI3_TYPE }, + { "ai3","ai3ct",_fip, 0, ai_print_circuit, ai_get_circuit, ai_set_circuit, (float *)&ai3, AI3_CIRCUIT }, + { "ai3","ai3p1",_fip, 4, ai_print_p, ai_get_p1, ai_set_p1, (float *)&ai3, AI3_P1 }, + { "ai3","ai3p2",_fip, 4, ai_print_p, ai_get_p2, ai_set_p2, (float *)&ai3, AI3_P2 }, + { "ai3","ai3p3",_fip, 4, ai_print_p, ai_get_p3, ai_set_p3, (float *)&ai3, AI3_P3 }, + { "ai3","ai3p4",_fip, 4, ai_print_p, ai_get_p4, ai_set_p4, (float *)&ai3, AI3_P4 }, + { "ai3","ai3p5",_fip, 4, ai_print_p, ai_get_p5, ai_set_p5, (float *)&ai3, AI3_P5 }, #endif #if (A_IN_CHANNELS >= 4) - { "ain4","ain4ty",_fip, 0, ain_print_type, ain_get_type, ain_set_type, (float *)&ain4, AI4_TYPE }, - { "ain4","ain4ct",_fip, 0, ain_print_circuit, ain_get_circuit, ain_set_circuit, (float *)&ain4, AI4_CIRCUIT }, - { "ain4","ain4p1",_fip, 4, ain_print_p, ain_get_p1, ain_set_p1, (float *)&ain4, AI4_P1 }, - { "ain4","ain4p2",_fip, 4, ain_print_p, ain_get_p2, ain_set_p2, (float *)&ain4, AI4_P2 }, - { "ain4","ain4p3",_fip, 4, ain_print_p, ain_get_p3, ain_set_p3, (float *)&ain4, AI4_P3 }, - { "ain4","ain4p4",_fip, 4, ain_print_p, ain_get_p4, ain_set_p4, (float *)&ain4, AI4_P4 }, - { "ain4","ain4p5",_fip, 4, ain_print_p, ain_get_p5, ain_set_p5, (float *)&ain4, AI4_P5 }, - { "ain4","ain4vv",_f0, 4, ain_print_value, ain_get_value, set_ro, (float *)&ain4, 0 }, - { "ain4","ain4rv",_f0, 2, ain_print_resistance, ain_get_resistance, set_ro, (float *)&ain4, 0 }, + { "ai4","ai4en",_fip, 0, ai_print_en, ai_get_en, ai_set_en, (float *)&ai4, AI4_ENABLED }, + { "ai4","ai4ty",_fip, 0, ai_print_type, ai_get_type, ai_set_type, (float *)&ai4, AI4_TYPE }, + { "ai4","ai4ct",_fip, 0, ai_print_circuit, ai_get_circuit, ai_set_circuit, (float *)&ai4, AI4_CIRCUIT }, + { "ai4","ai4p1",_fip, 4, ai_print_p, ai_get_p1, ai_set_p1, (float *)&ai4, AI4_P1 }, + { "ai4","ai4p2",_fip, 4, ai_print_p, ai_get_p2, ai_set_p2, (float *)&ai4, AI4_P2 }, + { "ai4","ai4p3",_fip, 4, ai_print_p, ai_get_p3, ai_set_p3, (float *)&ai4, AI4_P3 }, + { "ai4","ai4p4",_fip, 4, ai_print_p, ai_get_p4, ai_set_p4, (float *)&ai4, AI4_P4 }, + { "ai4","ai4p5",_fip, 4, ai_print_p, ai_get_p5, ai_set_p5, (float *)&ai4, AI4_P5 }, #endif + { "ain1","ain1vv",_f0, 4, ain_print_value, ain_get_value, set_ro, (float *)&ain1, 0 }, + { "ain1","ain1rv",_f0, 2, ain_print_resistance, ain_get_resistance, set_ro, (float *)&ain1, 0 }, + { "ain2","ain2vv",_f0, 4, ain_print_value, ain_get_value, set_ro, (float *)&ain2, 0 }, + { "ain2","ain2rv",_f0, 2, ain_print_resistance, ain_get_resistance, set_ro, (float *)&ain2, 0 }, + { "ain3","ain3vv",_f0, 4, ain_print_value, ain_get_value, set_ro, (float *)&ain3, 0 }, + { "ain3","ain3rv",_f0, 2, ain_print_resistance, ain_get_resistance, set_ro, (float *)&ain3, 0 }, + { "ain4","ain4vv",_f0, 4, ain_print_value, ain_get_value, set_ro, (float *)&ain4, 0 }, + { "ain4","ain4rv",_f0, 2, ain_print_resistance, ain_get_resistance, set_ro, (float *)&ain4, 0 }, + { "ain5","ain5vv",_f0, 4, ain_print_value, ain_get_value, set_ro, (float *)&ain5, 0 }, + { "ain5","ain5rv",_f0, 2, ain_print_resistance, ain_get_resistance, set_ro, (float *)&ain5, 0 }, + { "ain6","ain6vv",_f0, 4, ain_print_value, ain_get_value, set_ro, (float *)&ain6, 0 }, + { "ain6","ain6rv",_f0, 2, ain_print_resistance, ain_get_resistance, set_ro, (float *)&ain6, 0 }, + { "ain7","ain7vv",_f0, 4, ain_print_value, ain_get_value, set_ro, (float *)&ain7, 0 }, + { "ain7","ain7rv",_f0, 2, ain_print_resistance, ain_get_resistance, set_ro, (float *)&ain7, 0 }, + { "ain8","ain8vv",_f0, 4, ain_print_value, ain_get_value, set_ro, (float *)&ain8, 0 }, + { "ain8","ain8rv",_f0, 2, ain_print_resistance, ain_get_resistance, set_ro, (float *)&ain8, 0 }, + // PWM settings { "p1","p1frq",_fip, 0, pwm_print_p1frq, get_flt, pwm_set_pwm,(float *)&pwm.c[PWM_1].frequency, P1_PWM_FREQUENCY }, { "p1","p1csl",_fip, 0, pwm_print_p1csl, get_flt, pwm_set_pwm,(float *)&pwm.c[PWM_1].cw_speed_lo, P1_CW_SPEED_LO }, diff --git a/g2core/cycle_probing.cpp b/g2core/cycle_probing.cpp index 20464a01c..b19af1000 100644 --- a/g2core/cycle_probing.cpp +++ b/g2core/cycle_probing.cpp @@ -208,7 +208,7 @@ uint8_t cm_straight_probe(float target[], bool flags[], bool trip_sense, bool al } // initialize the probe input; error if no probe input specified - if ((pb.probe_input = gpio_get_probing_input()) == -1) { + if ((pb.probe_input = cm.probe_input) == -1) { return(cm_alarm(STAT_NO_PROBE_INPUT_CONFIGURED, "No probe input")); } diff --git a/g2core/device/max31865/max31865.h b/g2core/device/max31865/max31865.h index 4f89144c2..ab9bf6006 100644 --- a/g2core/device/max31865/max31865.h +++ b/g2core/device/max31865/max31865.h @@ -476,6 +476,7 @@ struct MAX31865 final { template struct gpioAnalogInputPin> : gpioAnalogInput { protected: // so we know if anyone tries to reach in + ioEnabled enabled; // -1=unavailable, 0=disabled, 1=enabled AnalogInputType_t type; uint8_t ext_pin_number; // the number used externally for this pin ("in" + ext_pin_number) @@ -488,8 +489,9 @@ struct gpioAnalogInputPin> : gpioAnalogInput { // In constructor, simply forward all values to the pin // To get a different behavior, override this object. template - gpioAnalogInputPin(const AnalogInputType_t _type, const uint8_t _ext_pin_number, T&&... additional_values) : + gpioAnalogInputPin(const ioEnabled _enabled, const AnalogInputType_t _type, const uint8_t _ext_pin_number, T&&... additional_values) : gpioAnalogInput{}, + enabled{_enabled}, type{_type}, ext_pin_number{_ext_pin_number}, pin{Motate::kNormal, [&](bool e){this->adc_has_new_value(e);}, additional_values...} @@ -499,16 +501,29 @@ struct gpioAnalogInputPin> : gpioAnalogInput { // functions for use by other parts of the code, and are overridden + ioEnabled getEnabled() override + { + return enabled; + }; + bool setEnabled(const ioEnabled m) override + { + if (enabled == IO_UNAVAILABLE) { + return false; + } + enabled = m; + return true; + }; + float getValue() override { - if (type == AIN_TYPE_DISABLED) { + if (enabled != IO_ENABLED) { return 0; } return pin.getVoltage(); }; float getResistance() override { - if (type == AIN_TYPE_DISABLED) { + if (enabled != IO_ENABLED) { return -1; } return pin.getResistance(); @@ -520,7 +535,7 @@ struct gpioAnalogInputPin> : gpioAnalogInput { }; bool setType(const AnalogInputType_t t) override { - // NOTE: Only AIN_TYPE_EXTERNAL and AIN_TYPE_DISABLED are handled here! + // NOTE: Allow setting type to AIN_TYPE_EXTERNAL if (t == AIN_TYPE_INTERNAL) { return false; } @@ -534,7 +549,10 @@ struct gpioAnalogInputPin> : gpioAnalogInput { }; bool setCircuit(const AnalogCircuit_t c) override { - // prevent setting circuit - it's always AIN_CIRCUIT_EXTERNAL + // prevent setting circuit to anything but AIN_CIRCUIT_EXTERNAL + if (c == AIN_CIRCUIT_EXTERNAL) { + return true; + } return false; }; diff --git a/g2core/gpio.cpp b/g2core/gpio.cpp index 1a146ea0b..e3fd08d0b 100644 --- a/g2core/gpio.cpp +++ b/g2core/gpio.cpp @@ -92,24 +92,17 @@ void gpio_reset(void) ********************************************/ /* - * gpio_set_homing_mode() - set/clear input to homing mode - * gpio_set_probing_mode() - set/clear input to probing mode - * gpio_get_probing_input() - get probing input * gpio_read_input() - read conditioned input * - * Note: input_num_ext means EXTERNAL input number -- 1-based - * TODO: lookup the external number to find the internal input, don't assume + * Note: input_num means the actual input number (1-based), not the exposed-as number */ -int8_t gpio_get_probing_input(void) -{ -} -bool gpio_read_input(const uint8_t input_num_ext) +bool gpio_read_input(const uint8_t input_num) { - if (input_num_ext == 0) { + if (input_num == 0) { return false; } - return (d_in[input_num_ext-1]->getState()); + return (d_in[input_num-1]->getState()); } @@ -132,6 +125,7 @@ gpioDigitalInputReader* _ir(const nvObj_t *nv) { return _io(nv); } gpioDigitalOutputWriter* _ow(const nvObj_t *nv) { return _io(nv); } gpioAnalogInput* _ai(const nvObj_t *nv) { return _io(nv); } +gpioAnalogInputReader* _air(const nvObj_t *nv) { return _io(nv); } gpioDigitalInputReader in1; gpioDigitalInputReader in2; @@ -169,11 +163,21 @@ gpioDigitalOutputWriter out14; gpioDigitalOutputWriter out15; gpioDigitalOutputWriter out16; -gpioDigitalOutputWriter* const out_w[14] = {&out1, &out2, &out3, &out4, &out5, &out6, &out7, &out8, &out9, &out10, &out11, &out12, &out13, &out14, &out15, &out16}; +gpioDigitalOutputWriter* const out_w[16] = {&out1, &out2, &out3, &out4, &out5, &out6, &out7, &out8, &out9, &out10, &out11, &out12, &out13, &out14, &out15, &out16}; // lists for the various inputAction events gpioDigitalInputHandlerList din_handlers[INPUT_ACTION_ACTUAL_MAX+1]; +gpioAnalogInputReader ain1; +gpioAnalogInputReader ain2; +gpioAnalogInputReader ain3; +gpioAnalogInputReader ain4; +gpioAnalogInputReader ain5; +gpioAnalogInputReader ain6; +gpioAnalogInputReader ain7; +gpioAnalogInputReader ain8; + +gpioAnalogInputReader* const ain_r[8] = {&ain1, &ain2, &ain3, &ain4, &ain5, &ain6, &ain7, &ain8}; /* * Get/set enabled @@ -288,57 +292,69 @@ stat_t dout_set_output(nvObj_t *nv) } +/* + * Get/set enabled + */ +stat_t ai_get_en(nvObj_t *nv) +{ + return _ai(nv)->getEnabled(nv); +} +stat_t ai_set_en(nvObj_t *nv) +{ + return _ai(nv)->setEnabled(nv); +} + /* * ain_get_value() - get the measured voltage level of the analog input */ stat_t ain_get_value(nvObj_t *nv) { - return _ai(nv)->getValue(nv); + return _air(nv)->getValue(nv); } // no ain_set_value /* - * ain_get_resistance() - get the measured resistance of the analog input + * ai_get_resistance() - get the measured resistance of the analog input * NOTE: Requires the circuit type to be configured and the relevant parameters set */ stat_t ain_get_resistance(nvObj_t *nv) { - return _ai(nv)->getResistance(nv); + return _air(nv)->getResistance(nv); } -// no ain_set_resistance +// no ai_set_resistance /* - * ain_get_type() - get the measured voltage level of the analog input + * ai_get_type() - get the measured voltage level of the analog input */ -stat_t ain_get_type(nvObj_t *nv) { +stat_t ai_get_type(nvObj_t *nv) { return _ai(nv)->getType(nv); } -stat_t ain_set_type(nvObj_t *nv) { +stat_t ai_set_type(nvObj_t *nv) { return _ai(nv)->setType(nv); } -stat_t ain_get_circuit(nvObj_t *nv) { +stat_t ai_get_circuit(nvObj_t *nv) { return _ai(nv)->getCircuit(nv); } -stat_t ain_set_circuit(nvObj_t *nv) { +stat_t ai_set_circuit(nvObj_t *nv) { return _ai(nv)->setCircuit(nv); } -stat_t ain_get_parameter(nvObj_t *nv, const uint8_t p) { +stat_t ai_get_parameter(nvObj_t *nv, const uint8_t p) { return _ai(nv)->getParameter(nv, p); } -stat_t ain_set_parameter(nvObj_t *nv, const uint8_t p) { +stat_t ai_set_parameter(nvObj_t *nv, const uint8_t p) { return _ai(nv)->setParameter(nv, p); } -stat_t ain_get_p1(nvObj_t *nv) { return ain_get_parameter(nv, 0); }; -stat_t ain_set_p1(nvObj_t *nv) { return ain_set_parameter(nv, 0); }; -stat_t ain_get_p2(nvObj_t *nv) { return ain_get_parameter(nv, 1); }; -stat_t ain_set_p2(nvObj_t *nv) { return ain_set_parameter(nv, 1); }; -stat_t ain_get_p3(nvObj_t *nv) { return ain_get_parameter(nv, 2); }; -stat_t ain_set_p3(nvObj_t *nv) { return ain_set_parameter(nv, 2); }; -stat_t ain_get_p4(nvObj_t *nv) { return ain_get_parameter(nv, 3); }; -stat_t ain_set_p4(nvObj_t *nv) { return ain_set_parameter(nv, 3); }; -stat_t ain_get_p5(nvObj_t *nv) { return ain_get_parameter(nv, 4); }; -stat_t ain_set_p5(nvObj_t *nv) { return ain_set_parameter(nv, 4); }; +stat_t ai_get_p1(nvObj_t *nv) { return ai_get_parameter(nv, 0); }; +stat_t ai_set_p1(nvObj_t *nv) { return ai_set_parameter(nv, 0); }; +stat_t ai_get_p2(nvObj_t *nv) { return ai_get_parameter(nv, 1); }; +stat_t ai_set_p2(nvObj_t *nv) { return ai_set_parameter(nv, 1); }; +stat_t ai_get_p3(nvObj_t *nv) { return ai_get_parameter(nv, 2); }; +stat_t ai_set_p3(nvObj_t *nv) { return ai_set_parameter(nv, 2); }; +stat_t ai_get_p4(nvObj_t *nv) { return ai_get_parameter(nv, 3); }; +stat_t ai_set_p4(nvObj_t *nv) { return ai_set_parameter(nv, 3); }; +stat_t ai_get_p5(nvObj_t *nv) { return ai_get_parameter(nv, 4); }; +stat_t ai_set_p5(nvObj_t *nv) { return ai_set_parameter(nv, 4); }; /*********************************************************************************** * TEXT MODE SUPPORT @@ -361,9 +377,10 @@ stat_t ain_set_p5(nvObj_t *nv) { return ain_set_parameter(nv, 4); }; static const char fmt_ain_value[] = "Analog input %s voltage: %5.2fV\n"; static const char fmt_ain_resistance[] = "Analog input %s resistance: %5.2fohm\n"; - static const char fmt_ain_type[] = "[%s] input type%17d [0=disabled,1=internal,2=external]\n"; - static const char fmt_ain_circuit[] = "[%s] analog circuit%13d [0=disabled,1=pull-up,2=external,3=inverted op-amp,4=constant current inverted op-amp]\n"; - static const char fmt_ain_parameter[] = "[%s] circuit parameter%6.4f [usage varies by circuit type]\n"; + static const char fmt_gpio_ai_en[] = "[%smo] analog input enabled%12d [-1=unavailable,0=disabled,1=enabled]\n"; + static const char fmt_ai_type[] = "[%s] input type%17d [0=disabled,1=internal,2=external]\n"; + static const char fmt_ai_circuit[] = "[%s] analog circuit%13d [0=disabled,1=pull-up,2=external,3=inverted op-amp,4=constant current inverted op-amp]\n"; + static const char fmt_ai_parameter[] = "[%s] circuit parameter%6.4f [usage varies by circuit type]\n"; static void _print_di(nvObj_t *nv, const char *format) { @@ -398,21 +415,22 @@ stat_t ain_set_p5(nvObj_t *nv) { return ain_set_parameter(nv, 4); }; sprintf(cs.out_buf, fmt_ain_resistance, nv->token, (float)nv->value); xio_writeline(cs.out_buf); } - void ain_print_type(nvObj_t *nv) + void ai_print_en(nvObj_t *nv) {_print_di(nv, fmt_gpio_ai_en);} + void ai_print_type(nvObj_t *nv) { - sprintf(cs.out_buf, fmt_ain_type, nv->token, (int)nv->value); + sprintf(cs.out_buf, fmt_ai_type, nv->token, (int)nv->value); xio_writeline(cs.out_buf); } - void ain_print_circuit(nvObj_t *nv) + void ai_print_circuit(nvObj_t *nv) { - sprintf(cs.out_buf, fmt_ain_circuit, nv->token, (int)nv->value); + sprintf(cs.out_buf, fmt_ai_circuit, nv->token, (int)nv->value); xio_writeline(cs.out_buf); } - void ain_print_p(nvObj_t *nv) + void ai_print_p(nvObj_t *nv) { - sprintf(cs.out_buf, fmt_ain_parameter, nv->token, (float)nv->value); + sprintf(cs.out_buf, fmt_ai_parameter, nv->token, (float)nv->value); xio_writeline(cs.out_buf); } diff --git a/g2core/gpio.h b/g2core/gpio.h index b2f080abe..15e28f6e9 100644 --- a/g2core/gpio.h +++ b/g2core/gpio.h @@ -100,7 +100,7 @@ typedef enum { // forward declare struct gpioDigitalInputReader; -extern gpioDigitalInputReader* const in_r[14]; +extern gpioDigitalInputReader* const in_r[16]; /* * gpioDigitalInputHandler - superclass of objects that wish to be informed of @@ -363,6 +363,8 @@ extern gpioDigitalInputReader in11; extern gpioDigitalInputReader in12; extern gpioDigitalInputReader in13; extern gpioDigitalInputReader in14; +extern gpioDigitalInputReader in15; +extern gpioDigitalInputReader in16; /* @@ -628,7 +630,8 @@ struct gpioDigitalOutput { }; stat_t setEnabled(nvObj_t *nv) { - if ((nv->value < IO_DISABLED) || (nv->value > IO_ENABLED)) { + int32_t value = nv->value; + if ((value != IO_DISABLED) && (value != IO_ENABLED)) { return (STAT_INPUT_VALUE_RANGE_ERROR); } if (!setEnabled((ioEnabled)nv->value)) { @@ -657,7 +660,7 @@ struct gpioDigitalOutput { stat_t getValue(nvObj_t *nv) { auto enabled = getEnabled(); - if (enabled <= IO_DISABLED) { + if (enabled != IO_ENABLED) { nv->value = 0; nv->valuetype = TYPE_NULL; // reports back as NULL } else { @@ -675,7 +678,7 @@ struct gpioDigitalOutput { stat_t setValue(nvObj_t *nv) { auto enabled = getEnabled(); - if (enabled <= IO_DISABLED) { + if (enabled != IO_ENABLED) { nv->valuetype = TYPE_NULL; // reports back as NULL } else { float value = nv->value; // read it as a float @@ -708,12 +711,11 @@ struct gpioDigitalOutput { } return (STAT_OK); }; - }; /* - * gpioDigitalOutputWriter - digital output reader class - the "out1" - "outX" objects + * gpioDigitalOutputWriter - digital output writer class - the "out1" - "outX" objects */ struct gpioDigitalOutputWriter final { @@ -776,6 +778,8 @@ extern gpioDigitalOutputWriter out11; extern gpioDigitalOutputWriter out12; extern gpioDigitalOutputWriter out13; extern gpioDigitalOutputWriter out14; +extern gpioDigitalOutputWriter out15; +extern gpioDigitalOutputWriter out16; /* @@ -879,15 +883,18 @@ struct gpioDigitalOutputPin final : gpioDigitalOutput { }; +// forward declare +struct gpioAnalogInputReader; +extern gpioAnalogInputReader* const ain_r[8]; + /* * gpioAnalogInput - analog (ADC) input base class */ struct gpioAnalogInput { // type of analog input source - read only - defined by the board enum AnalogInputType_t { - AIN_TYPE_DISABLED = 0, // the whole input is disabled - AIN_TYPE_INTERNAL = 1, // single-ended or differential - AIN_TYPE_EXTERNAL = 2, // for externally (SPI) connected inputs + AIN_TYPE_INTERNAL = 0, // single-ended or differential + AIN_TYPE_EXTERNAL = 1, // for externally (SPI) connected inputs }; // type of circuit connected - for use in determining the resistance @@ -914,11 +921,16 @@ struct gpioAnalogInput { }; static const auto AIN_CIRCUIT_MAX = AIN_CIRCUIT_CC_INV_OPAMP; + uint8_t proxy_pin_number; // the number used externally for this pin ("ain" + proxy_pin_number) + // this is the generic implementation for a "any"" analog input pin // see gpioAnalogInputPin for a real pin // functions for use by other parts of the code + virtual ioEnabled getEnabled(); + virtual bool setEnabled(const ioEnabled); + virtual float getValue(); virtual float getResistance(); @@ -931,13 +943,34 @@ struct gpioAnalogInput { virtual float getParameter(const uint8_t p); virtual bool setParameter(const uint8_t p, const float v); + virtual bool setExternalNumber(const uint8_t); + virtual const uint8_t getExternalNumber(); + virtual void startSampling(); // functions that take nvObj_t* and return stat_t, NOT overridden + stat_t getEnabled(nvObj_t *nv) + { + nv->value = getEnabled(); + nv->valuetype = TYPE_INT; + return (STAT_OK); + }; + stat_t setEnabled(nvObj_t *nv) + { + int32_t value = nv->value; + if ((value != IO_DISABLED) && (value != IO_ENABLED)) { + return (STAT_INPUT_VALUE_RANGE_ERROR); + } + if (!setEnabled((ioEnabled)nv->value)) { + return STAT_PARAMETER_IS_READ_ONLY; + } + return (STAT_OK); + }; + stat_t getValue(nvObj_t *nv) { - if (getType() == AIN_TYPE_DISABLED) { + if (getEnabled() != IO_ENABLED) { nv->valuetype = TYPE_NULL; return (STAT_OK); } @@ -949,7 +982,7 @@ struct gpioAnalogInput { stat_t getResistance(nvObj_t *nv) { - if (getType() == AIN_TYPE_DISABLED || getCircuit() == AIN_CIRCUIT_DISABLED) { + if (getEnabled() != IO_ENABLED || getCircuit() == AIN_CIRCUIT_DISABLED) { nv->valuetype = TYPE_NULL; return (STAT_OK); } @@ -967,7 +1000,7 @@ struct gpioAnalogInput { }; stat_t setType(nvObj_t *nv) { - if ((nv->value < AIN_TYPE_DISABLED) || (nv->value > AIN_TYPE_EXTERNAL)) { + if ((getEnabled() != IO_ENABLED) || (nv->value > AIN_TYPE_EXTERNAL)) { return (STAT_INPUT_VALUE_RANGE_ERROR); } if (!setType((AnalogInputType_t)nv->value)) { @@ -1006,8 +1039,86 @@ struct gpioAnalogInput { } return (STAT_OK); }; + + + stat_t getExternalNumber(nvObj_t *nv) + { + nv->value = getExternalNumber(); + nv->valuetype = TYPE_INT; + return (STAT_OK); + }; + stat_t setExternalNumber(nvObj_t *nv) + { + if ((nv->value < 0) || (nv->value > 14)) { + return (STAT_INPUT_VALUE_RANGE_ERROR); + } + if (!setExternalNumber(nv->value)) { + return STAT_PARAMETER_IS_READ_ONLY; + } + return (STAT_OK); + }; +}; + + + +/* + * gpioAnalogInputReader - analog input reader class - the "ain1" - "ainX" objects + */ + +struct gpioAnalogInputReader final { + gpioAnalogInput* pin; + + // functions for use by other parts of the code + + bool setPin(gpioAnalogInput* new_pin) { + new_pin = pin; // might be null + return true; + }; + + gpioAnalogInput* getPin() { + return pin; // might be null + }; + + float getValue() { + if (!pin) { return -1; } + return pin->getValue(); + }; + float getResistance() { + if (!pin) { return -1; } + return pin->getResistance(); + }; + + + // functions that take nvObj_t* and return stat_t, NOT overridden + + stat_t getValue(nvObj_t *nv) { + if (!pin) { + nv->value = 0; + nv->valuetype = TYPE_NULL; // reports back as NULL + return (STAT_OK); + } + return pin->getValue(nv); + }; + stat_t getResistance(nvObj_t *nv) { + if (!pin) { + nv->value = 0; + nv->valuetype = TYPE_NULL; // reports back as NULL + return (STAT_OK); + } + return pin->getResistance(nv); + }; }; +// setup the gpioDigitalInputReader objects as extern +extern gpioAnalogInputReader ain1; +extern gpioAnalogInputReader ain2; +extern gpioAnalogInputReader ain3; +extern gpioAnalogInputReader ain4; +extern gpioAnalogInputReader ain5; +extern gpioAnalogInputReader ain6; +extern gpioAnalogInputReader ain7; +extern gpioAnalogInputReader ain8; + // statistical sampling utility class template struct ValueHistory { @@ -1088,11 +1199,13 @@ struct ValueHistory { template struct gpioAnalogInputPin : gpioAnalogInput { protected: // so we know if anyone tries to reach in + ioEnabled enabled; // -1=unavailable, 0=disabled, 1=enabled AnalogInputType_t type; AnalogCircuit_t circuit; float parameters[6]; - uint8_t ext_pin_number; // the number used externally for this pin ("in" + ext_pin_number) + const uint8_t ext_pin_number; // the number used externally for this pin ("in" + ext_pin_number) + uint8_t proxy_pin_number; // the number used externally for this pin ("in" + proxy_pin_number) const float variance_max = 1.1; ValueHistory<40> history {variance_max}; @@ -1105,21 +1218,42 @@ struct gpioAnalogInputPin : gpioAnalogInput { // In constructor, simply forward all values to the pin // To get a different behavior, override this object. template - gpioAnalogInputPin(const AnalogInputType_t _type, const uint8_t _ext_pin_number, T&&... additional_values) : + gpioAnalogInputPin(const ioEnabled _enabled, const AnalogInputType_t _type, const uint8_t _ext_pin_number, const uint8_t _proxy_pin_number, T&&... additional_values) : gpioAnalogInput{}, + enabled{_enabled}, type{_type}, ext_pin_number{_ext_pin_number}, + proxy_pin_number{_proxy_pin_number}, pin{Motate::kNormal, [&]{this->adc_has_new_value();}, std::forward(additional_values)...} { - pin.setInterrupts(Motate::kPinInterruptOnChange|Motate::kInterruptPriorityLow); - pin.setVoltageRange(3.29, 0.0, 3.29, 100.0); + if (pin.isNull()) { + enabled = IO_UNAVAILABLE; + proxy_pin_number = 0; + } else { + pin.setInterrupts(Motate::kPinInterruptOnChange|Motate::kInterruptPriorityLow); + pin.setVoltageRange(3.29, 0.0, 3.29, 100.0); + setExternalNumber(proxy_pin_number); + } }; // functions for use by other parts of the code, and are overridden + ioEnabled getEnabled() override + { + return enabled; + }; + bool setEnabled(const ioEnabled m) override + { + if (enabled == IO_UNAVAILABLE) { + return false; + } + enabled = m; + return true; + }; + float getValue() override { - if (type == AIN_TYPE_DISABLED) { + if (enabled != IO_ENABLED) { return 0; } return history.value(); @@ -1128,7 +1262,7 @@ struct gpioAnalogInputPin : gpioAnalogInput { { // NOTE: AIN_CIRCUIT_EXTERNAL is NOT handled here! // That needs to be handled in a separate override! - if (type == AIN_TYPE_DISABLED || circuit == AIN_CIRCUIT_DISABLED) { + if (enabled != IO_ENABLED || circuit == AIN_CIRCUIT_DISABLED) { return -1; } const float v = history.value(); @@ -1228,6 +1362,26 @@ struct gpioAnalogInputPin : gpioAnalogInput { pin.startSampling(); }; + bool setExternalNumber(const uint8_t e) override + { + if (e == proxy_pin_number) { return true; } + if (proxy_pin_number > 0) { + // clear the old pin + ain_r[proxy_pin_number-1]->setPin(nullptr); + } + proxy_pin_number = e; + if (proxy_pin_number > 0) { + // set the new pin + ain_r[proxy_pin_number-1]->setPin(this); + } + return true; + }; + + const uint8_t getExternalNumber() override + { + return proxy_pin_number; + }; + // support function for pin value update interrupt handling void adc_has_new_value() { @@ -1246,7 +1400,6 @@ void inputs_reset(void); void outputs_reset(void); bool gpio_read_input(const uint8_t input_num); -int8_t gpio_get_probing_input(void); stat_t din_get_en(nvObj_t *nv); // enabled stat_t din_set_en(nvObj_t *nv); @@ -1271,22 +1424,24 @@ stat_t ain_get_value(nvObj_t *nv); // get the voltage level // no ain_set_value stat_t ain_get_resistance(nvObj_t *nv); // get the resistance in ohms // no ain_set_resistance -stat_t ain_get_type(nvObj_t *nv); // get the ADC type (or disabled) -stat_t ain_set_type(nvObj_t *nv); // set the type (used to disable/enable) -stat_t ain_get_circuit(nvObj_t *nv); // get the circuit type -stat_t ain_set_circuit(nvObj_t *nv); // set the circuit type -stat_t ain_get_parameter(nvObj_t *nv, const uint8_t p); // get the value of parameter p -stat_t ain_set_parameter(nvObj_t *nv, const uint8_t p); // set the value of parameter p -stat_t ain_get_p1(nvObj_t *nv); -stat_t ain_set_p1(nvObj_t *nv); -stat_t ain_get_p2(nvObj_t *nv); -stat_t ain_set_p2(nvObj_t *nv); -stat_t ain_get_p3(nvObj_t *nv); -stat_t ain_set_p3(nvObj_t *nv); -stat_t ain_get_p4(nvObj_t *nv); -stat_t ain_set_p4(nvObj_t *nv); -stat_t ain_get_p5(nvObj_t *nv); -stat_t ain_set_p5(nvObj_t *nv); +stat_t ai_get_en(nvObj_t *nv); // enabled +stat_t ai_set_en(nvObj_t *nv); // enabled +stat_t ai_get_type(nvObj_t *nv); // get the ADC type (or disabled) +stat_t ai_set_type(nvObj_t *nv); // set the type (used to disable/enable) +stat_t ai_get_circuit(nvObj_t *nv); // get the circuit type +stat_t ai_set_circuit(nvObj_t *nv); // set the circuit type +stat_t ai_get_parameter(nvObj_t *nv, const uint8_t p); // get the value of parameter p +stat_t ai_set_parameter(nvObj_t *nv, const uint8_t p); // set the value of parameter p +stat_t ai_get_p1(nvObj_t *nv); +stat_t ai_set_p1(nvObj_t *nv); +stat_t ai_get_p2(nvObj_t *nv); +stat_t ai_set_p2(nvObj_t *nv); +stat_t ai_get_p3(nvObj_t *nv); +stat_t ai_set_p3(nvObj_t *nv); +stat_t ai_get_p4(nvObj_t *nv); +stat_t ai_set_p4(nvObj_t *nv); +stat_t ai_get_p5(nvObj_t *nv); +stat_t ai_set_p5(nvObj_t *nv); #ifdef __TEXT_MODE void din_print_en(nvObj_t *nv); @@ -1302,9 +1457,10 @@ stat_t ain_set_p5(nvObj_t *nv); void ain_print_value(nvObj_t *nv); void ain_print_resistance(nvObj_t *nv); - void ain_print_type(nvObj_t *nv); - void ain_print_circuit(nvObj_t *nv); - void ain_print_p(nvObj_t *nv); + void ai_print_en(nvObj_t *nv); + void ai_print_type(nvObj_t *nv); + void ai_print_circuit(nvObj_t *nv); + void ai_print_p(nvObj_t *nv); #else #define din_print_en tx_print_stub #define din_print_po tx_print_stub @@ -1318,15 +1474,22 @@ stat_t ain_set_p5(nvObj_t *nv); #define ain_print_value tx_print_stub #define ain_print_resistance tx_print_stub - #define ain_print_type tx_print_stub - #define ain_print_circuit tx_print_stub - #define ain_print_p tx_print_stub + #define ai_print_en tx_print_stub + #define ai_print_type tx_print_stub + #define ai_print_circuit tx_print_stub + #define ai_print_p tx_print_stub #endif // __TEXT_MODE #include "board_gpio.h" +#ifndef AI1_ENABLED +#define AI1_ENABLED IO_DISABLED +#endif +#ifndef AI1_EXTERNAL_NUMBER +#define AI1_EXTERNAL_NUMBER 1 +#endif #ifndef AI1_TYPE -#define AI1_TYPE AIN_TYPE_DISABLED +#define AI1_TYPE AIN_TYPE_INTERNAL #endif #ifndef AI1_CIRCUIT #define AI1_CIRCUIT AIN_CIRCUIT_DISABLED @@ -1348,8 +1511,14 @@ stat_t ain_set_p5(nvObj_t *nv); #endif +#ifndef AI2_ENABLED +#define AI2_ENABLED IO_DISABLED +#endif +#ifndef AI2_EXTERNAL_NUMBER +#define AI2_EXTERNAL_NUMBER 2 +#endif #ifndef AI2_TYPE -#define AI2_TYPE AIN_TYPE_DISABLED +#define AI2_TYPE AIN_TYPE_INTERNAL #endif #ifndef AI2_CIRCUIT #define AI2_CIRCUIT AIN_CIRCUIT_DISABLED @@ -1370,8 +1539,14 @@ stat_t ain_set_p5(nvObj_t *nv); #define AI2_P5 0.0 #endif +#ifndef AI3_ENABLED +#define AI3_ENABLED IO_DISABLED +#endif +#ifndef AI3_EXTERNAL_NUMBER +#define AI3_EXTERNAL_NUMBER 3 +#endif #ifndef AI3_TYPE -#define AI3_TYPE AIN_TYPE_DISABLED +#define AI3_TYPE AIN_TYPE_INTERNAL #endif #ifndef AI3_CIRCUIT #define AI3_CIRCUIT AIN_CIRCUIT_DISABLED @@ -1392,8 +1567,14 @@ stat_t ain_set_p5(nvObj_t *nv); #define AI3_P5 0.0 #endif +#ifndef AI4_ENABLED +#define AI4_ENABLED IO_DISABLED +#endif +#ifndef AI4_EXTERNAL_NUMBER +#define AI4_EXTERNAL_NUMBER 4 +#endif #ifndef AI4_TYPE -#define AI4_TYPE AIN_TYPE_DISABLED +#define AI4_TYPE AIN_TYPE_INTERNAL #endif #ifndef AI4_CIRCUIT #define AI4_CIRCUIT AIN_CIRCUIT_DISABLED From 150e322f6e41e73b200b3b12245a2394b507288a Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Thu, 29 Mar 2018 11:11:51 -0500 Subject: [PATCH 190/193] Added `aiNain` to expose the analog pins on `ainM` --- g2core/config_app.cpp | 4 ++++ g2core/gpio.cpp | 18 ++++++++++++++++-- g2core/gpio.h | 4 ++++ 3 files changed, 24 insertions(+), 2 deletions(-) diff --git a/g2core/config_app.cpp b/g2core/config_app.cpp index 16ecc087d..aafa61931 100644 --- a/g2core/config_app.cpp +++ b/g2core/config_app.cpp @@ -672,6 +672,7 @@ const cfgItem_t cfgArray[] = { // Analog input configs #if (A_IN_CHANNELS >= 1) { "ai1","ai1en",_fip, 0, ai_print_en, ai_get_en, ai_set_en, (float *)&ai1, AI1_ENABLED }, + { "ai1","ai1ain",_fip,0, ai_print_ain, ai_get_ain, ai_set_ain, (float *)&ai1, AI1_EXTERNAL_NUMBER }, { "ai1","ai1ty",_fip, 0, ai_print_type, ai_get_type, ai_set_type, (float *)&ai1, AI1_TYPE }, { "ai1","ai1ct",_fip, 0, ai_print_circuit, ai_get_circuit, ai_set_circuit, (float *)&ai1, AI1_CIRCUIT }, { "ai1","ai1p1",_fip, 4, ai_print_p, ai_get_p1, ai_set_p1, (float *)&ai1, AI1_P1 }, @@ -682,6 +683,7 @@ const cfgItem_t cfgArray[] = { #endif #if (A_IN_CHANNELS >= 2) { "ai2","ai2en",_fip, 0, ai_print_en, ai_get_en, ai_set_en, (float *)&ai2, AI2_ENABLED }, + { "ai2","ai2ain",_fip,0, ai_print_ain, ai_get_ain, ai_set_ain, (float *)&ai2, AI2_EXTERNAL_NUMBER }, { "ai2","ai2ty",_fip, 0, ai_print_type, ai_get_type, ai_set_type, (float *)&ai2, AI2_TYPE }, { "ai2","ai2ct",_fip, 0, ai_print_circuit, ai_get_circuit, ai_set_circuit, (float *)&ai2, AI2_CIRCUIT }, { "ai2","ai2p1",_fip, 4, ai_print_p, ai_get_p1, ai_set_p1, (float *)&ai2, AI2_P1 }, @@ -692,6 +694,7 @@ const cfgItem_t cfgArray[] = { #endif #if (A_IN_CHANNELS >= 3) { "ai3","ai3en",_fip, 0, ai_print_en, ai_get_en, ai_set_en, (float *)&ai3, AI3_ENABLED }, + { "ai3","ai3ain",_fip,0, ai_print_ain, ai_get_ain, ai_set_ain, (float *)&ai3, AI3_EXTERNAL_NUMBER }, { "ai3","ai3ty",_fip, 0, ai_print_type, ai_get_type, ai_set_type, (float *)&ai3, AI3_TYPE }, { "ai3","ai3ct",_fip, 0, ai_print_circuit, ai_get_circuit, ai_set_circuit, (float *)&ai3, AI3_CIRCUIT }, { "ai3","ai3p1",_fip, 4, ai_print_p, ai_get_p1, ai_set_p1, (float *)&ai3, AI3_P1 }, @@ -702,6 +705,7 @@ const cfgItem_t cfgArray[] = { #endif #if (A_IN_CHANNELS >= 4) { "ai4","ai4en",_fip, 0, ai_print_en, ai_get_en, ai_set_en, (float *)&ai4, AI4_ENABLED }, + { "ai4","ai4ain",_fip,0, ai_print_ain, ai_get_ain, ai_set_ain, (float *)&ai4, AI4_EXTERNAL_NUMBER }, { "ai4","ai4ty",_fip, 0, ai_print_type, ai_get_type, ai_set_type, (float *)&ai4, AI4_TYPE }, { "ai4","ai4ct",_fip, 0, ai_print_circuit, ai_get_circuit, ai_set_circuit, (float *)&ai4, AI4_CIRCUIT }, { "ai4","ai4p1",_fip, 4, ai_print_p, ai_get_p1, ai_set_p1, (float *)&ai4, AI4_P1 }, diff --git a/g2core/gpio.cpp b/g2core/gpio.cpp index e3fd08d0b..3abe812b0 100644 --- a/g2core/gpio.cpp +++ b/g2core/gpio.cpp @@ -304,6 +304,18 @@ stat_t ai_set_en(nvObj_t *nv) return _ai(nv)->setEnabled(nv); } +/* + * Get/set output external number + */ +stat_t ai_get_ain(nvObj_t *nv) +{ + return _ai(nv)->getExternalNumber(nv); +} +stat_t ai_set_ain(nvObj_t *nv) +{ + return _ai(nv)->setExternalNumber(nv); +} + /* * ain_get_value() - get the measured voltage level of the analog input */ @@ -367,17 +379,18 @@ stat_t ai_set_p5(nvObj_t *nv) { return ai_set_parameter(nv, 4); }; static const char fmt_gpio_in_po[] = "[%smo] input polarity%13d [0=normal/active-high,1=inverted/active-low]\n"; static const char fmt_gpio_ac[] = "[%sac] input action%15d [0=none,1=stop,2=fast_stop,3=halt,4=alarm,5=shutdown,6=panic,7=reset]\n"; static const char fmt_gpio_fn[] = "[%sfn] input function%13d [0=none,1=limit,2=interlock,3=shutdown,4=probe]\n"; - static const char fmt_gpio_in[] = "[%sin] input external number%6d [0=none,1-12=inX shows the value of this din]\n"; + static const char fmt_gpio_in[] = "[%sin] input external number%6d [0=none,1-16=inX shows the value of this din]\n"; static const char fmt_gpio_state[] = "Input %s state: %5d\n"; static const char fmt_gpio_out_en[] = "[%smo] output enabled%12d [-1=unavailable,0=disabled,1=enabled]\n"; static const char fmt_gpio_out_po[] = "[%smo] output polarity%12d [0=normal/active-high,1=inverted/active-low]\n"; - static const char fmt_gpio_out_out[] = "[%sout] output external number%5d [0=none,1-14=outX shows the value of this dout]\n"; + static const char fmt_gpio_out_out[] = "[%sout] output external number%5d [0=none,1-16=outX shows the value of this dout]\n"; static const char fmt_gpio_out_state[] = "Output %s state: %5d\n"; static const char fmt_ain_value[] = "Analog input %s voltage: %5.2fV\n"; static const char fmt_ain_resistance[] = "Analog input %s resistance: %5.2fohm\n"; static const char fmt_gpio_ai_en[] = "[%smo] analog input enabled%12d [-1=unavailable,0=disabled,1=enabled]\n"; + static const char fmt_gpio_ai_ain[] = "[%sout] analog input external number%5d [0=none,1-8=ainX shows the value of this ai]\n"; static const char fmt_ai_type[] = "[%s] input type%17d [0=disabled,1=internal,2=external]\n"; static const char fmt_ai_circuit[] = "[%s] analog circuit%13d [0=disabled,1=pull-up,2=external,3=inverted op-amp,4=constant current inverted op-amp]\n"; static const char fmt_ai_parameter[] = "[%s] circuit parameter%6.4f [usage varies by circuit type]\n"; @@ -416,6 +429,7 @@ stat_t ai_set_p5(nvObj_t *nv) { return ai_set_parameter(nv, 4); }; xio_writeline(cs.out_buf); } void ai_print_en(nvObj_t *nv) {_print_di(nv, fmt_gpio_ai_en);} + void ai_print_ain(nvObj_t *nv) {_print_di(nv, fmt_gpio_ai_ain);} void ai_print_type(nvObj_t *nv) { sprintf(cs.out_buf, fmt_ai_type, nv->token, (int)nv->value); diff --git a/g2core/gpio.h b/g2core/gpio.h index 15e28f6e9..52b487b40 100644 --- a/g2core/gpio.h +++ b/g2core/gpio.h @@ -1426,6 +1426,8 @@ stat_t ain_get_resistance(nvObj_t *nv); // get the resistance in ohms // no ain_set_resistance stat_t ai_get_en(nvObj_t *nv); // enabled stat_t ai_set_en(nvObj_t *nv); // enabled +stat_t ai_get_ain(nvObj_t *nv); // external number +stat_t ai_set_ain(nvObj_t *nv); stat_t ai_get_type(nvObj_t *nv); // get the ADC type (or disabled) stat_t ai_set_type(nvObj_t *nv); // set the type (used to disable/enable) stat_t ai_get_circuit(nvObj_t *nv); // get the circuit type @@ -1457,6 +1459,7 @@ stat_t ai_set_p5(nvObj_t *nv); void ain_print_value(nvObj_t *nv); void ain_print_resistance(nvObj_t *nv); + void ai_print_ain(nvObj_t *nv); void ai_print_en(nvObj_t *nv); void ai_print_type(nvObj_t *nv); void ai_print_circuit(nvObj_t *nv); @@ -1475,6 +1478,7 @@ stat_t ai_set_p5(nvObj_t *nv); #define ain_print_value tx_print_stub #define ain_print_resistance tx_print_stub #define ai_print_en tx_print_stub + #define ai_print_ain tx_print_stub #define ai_print_type tx_print_stub #define ai_print_circuit tx_print_stub #define ai_print_p tx_print_stub From fed9c9e9451db801fa738371dc93e2211ba297ff Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Sun, 6 May 2018 10:46:00 -0500 Subject: [PATCH 191/193] Fixes for GPIO proxies --- g2core/gpio.h | 32 +++++++++++++++----------------- 1 file changed, 15 insertions(+), 17 deletions(-) diff --git a/g2core/gpio.h b/g2core/gpio.h index 52b487b40..cab712b90 100644 --- a/g2core/gpio.h +++ b/g2core/gpio.h @@ -321,8 +321,8 @@ struct gpioDigitalInputReader final { // functions for use by other parts of the code - bool setPin(gpioDigitalInput* new_pin) { - new_pin = pin; // might be null + bool setPin(gpioDigitalInput * const new_pin) { + pin = new_pin; // might be null return true; }; @@ -397,15 +397,15 @@ struct gpioDigitalInputPin final : gpioDigitalInput { gpioDigitalInput{}, enabled{_enabled}, polarity{_polarity}, - ext_pin_number{_ext_pin_number}, - proxy_pin_number{_proxy_pin_number}, + ext_pin_number{ _ext_pin_number }, + proxy_pin_number{ 0 }, pin{((polarity == IO_ACTIVE_LOW) ? kPullUp|kDebounce : kDebounce), [&]{this->pin_changed();}, std::forward(V)...} { if (pin.isNull()) { enabled = IO_UNAVAILABLE; proxy_pin_number = 0; } else { - setExternalNumber(proxy_pin_number); + setExternalNumber(_proxy_pin_number); } }; @@ -723,8 +723,8 @@ struct gpioDigitalOutputWriter final { // functions for use by other parts of the code - bool setPin(gpioDigitalOutput* new_pin) { - new_pin = pin; // might be null + bool setPin(gpioDigitalOutput * const new_pin) { + pin = new_pin; // might be null return true; }; @@ -798,14 +798,14 @@ struct gpioDigitalOutputPin final : gpioDigitalOutput { gpioDigitalOutput{}, enabled{ _enabled }, polarity{ _polarity }, - proxy_pin_number{ _proxy_pin_number }, + proxy_pin_number{ 0 }, pin{((polarity == IO_ACTIVE_LOW) ? kStartHigh|kPWMPinInverted : kStartLow), std::forward(V)...} { if (pin.isNull()) { enabled = IO_UNAVAILABLE; proxy_pin_number = 0; } else { - setExternalNumber(proxy_pin_number); + setExternalNumber(_proxy_pin_number); } }; @@ -921,8 +921,6 @@ struct gpioAnalogInput { }; static const auto AIN_CIRCUIT_MAX = AIN_CIRCUIT_CC_INV_OPAMP; - uint8_t proxy_pin_number; // the number used externally for this pin ("ain" + proxy_pin_number) - // this is the generic implementation for a "any"" analog input pin // see gpioAnalogInputPin for a real pin @@ -1070,8 +1068,8 @@ struct gpioAnalogInputReader final { // functions for use by other parts of the code - bool setPin(gpioAnalogInput* new_pin) { - new_pin = pin; // might be null + bool setPin(gpioAnalogInput * const new_pin) { + pin = new_pin; // might be null return true; }; @@ -1208,7 +1206,7 @@ struct gpioAnalogInputPin : gpioAnalogInput { uint8_t proxy_pin_number; // the number used externally for this pin ("in" + proxy_pin_number) const float variance_max = 1.1; - ValueHistory<40> history {variance_max}; + ValueHistory<20> history {variance_max}; float last_raw_value; @@ -1222,8 +1220,8 @@ struct gpioAnalogInputPin : gpioAnalogInput { gpioAnalogInput{}, enabled{_enabled}, type{_type}, - ext_pin_number{_ext_pin_number}, - proxy_pin_number{_proxy_pin_number}, + ext_pin_number{ _ext_pin_number }, + proxy_pin_number{ 0 }, pin{Motate::kNormal, [&]{this->adc_has_new_value();}, std::forward(additional_values)...} { if (pin.isNull()) { @@ -1232,7 +1230,7 @@ struct gpioAnalogInputPin : gpioAnalogInput { } else { pin.setInterrupts(Motate::kPinInterruptOnChange|Motate::kInterruptPriorityLow); pin.setVoltageRange(3.29, 0.0, 3.29, 100.0); - setExternalNumber(proxy_pin_number); + setExternalNumber(_proxy_pin_number); } }; From fbad7f5f17582588ee3cb27fdeeaada30b12a2db Mon Sep 17 00:00:00 2001 From: Rob Giseburt Date: Thu, 7 Jun 2018 14:10:47 -0500 Subject: [PATCH 192/193] Made svb300 compile --- g2core/board/sbv300/board_gpio.cpp | 63 ++++++++++++++++-------------- g2core/board/sbv300/board_gpio.h | 6 +++ g2core/board/sbv300/board_xio.h | 4 +- 3 files changed, 41 insertions(+), 32 deletions(-) diff --git a/g2core/board/sbv300/board_gpio.cpp b/g2core/board/sbv300/board_gpio.cpp index 4daf011d8..70f950b44 100644 --- a/g2core/board/sbv300/board_gpio.cpp +++ b/g2core/board/sbv300/board_gpio.cpp @@ -56,40 +56,43 @@ /**** Setup Actual Objects ****/ -gpioDigitalInputPin> din1 {DI1_MODE, 1}; -gpioDigitalInputPin> din2 {DI2_MODE, 2}; -gpioDigitalInputPin> din3 {DI3_MODE, 3}; -gpioDigitalInputPin> din4 {DI4_MODE, 4}; -gpioDigitalInputPin> din5 {DI5_MODE, 5}; -gpioDigitalInputPin> din6 {DI6_MODE, 6}; -gpioDigitalInputPin> din7 {DI7_MODE, 7}; -gpioDigitalInputPin> din8 {DI8_MODE, 8}; -gpioDigitalInputPin> din9 {DI9_MODE, 9}; -// gpioDigitalInputPin> din10 {DI10_MODE, 10}; -// gpioDigitalInputPin> din11 {DI11_MODE, 11}; -// gpioDigitalInputPin> din12 {DI12_MODE, 12}; - -gpioDigitalOutputPin> dout1 { DO1_MODE, (uint32_t)200000 }; -gpioDigitalOutputPin> dout2 { DO2_MODE, (uint32_t)200000 }; -gpioDigitalOutputPin> dout3 { DO3_MODE, (uint32_t)200000 }; -gpioDigitalOutputPin> dout4 { DO4_MODE, (uint32_t)200000 }; -gpioDigitalOutputPin> dout5 { DO5_MODE, (uint32_t)200000 }; -gpioDigitalOutputPin> dout6 { DO6_MODE, (uint32_t)200000 }; -gpioDigitalOutputPin> dout7 { DO7_MODE, (uint32_t)200000 }; -gpioDigitalOutputPin> dout8 { DO8_MODE, (uint32_t)200000 }; -gpioDigitalOutputPin> dout9 { DO9_MODE, (uint32_t)200000 }; -gpioDigitalOutputPin> dout10 { DO10_MODE, (uint32_t)200000 }; -gpioDigitalOutputPin> dout11 { DO11_MODE, (uint32_t)200000 }; -gpioDigitalOutputPin> dout12 { DO12_MODE, (uint32_t)200000 }; -gpioDigitalOutputPin> dout13 { DO13_MODE, (uint32_t)200000 }; - -/**** Setup Arrays - these are extern and MUST match the board_gpio.h ****/ +gpioDigitalInputPin> din1 {DI1_ENABLED, DI1_POLARITY, 1, DI1_EXTERNAL_NUMBER}; +gpioDigitalInputPin> din2 {DI2_ENABLED, DI2_POLARITY, 2, DI2_EXTERNAL_NUMBER}; +gpioDigitalInputPin> din3 {DI3_ENABLED, DI3_POLARITY, 3, DI3_EXTERNAL_NUMBER}; +gpioDigitalInputPin> din4 {DI4_ENABLED, DI4_POLARITY, 4, DI4_EXTERNAL_NUMBER}; +gpioDigitalInputPin> din5 {DI5_ENABLED, DI5_POLARITY, 5, DI5_EXTERNAL_NUMBER}; +gpioDigitalInputPin> din6 {DI6_ENABLED, DI6_POLARITY, 6, DI6_EXTERNAL_NUMBER}; +gpioDigitalInputPin> din7 {DI7_ENABLED, DI7_POLARITY, 7, DI7_EXTERNAL_NUMBER}; +gpioDigitalInputPin> din8 {DI8_ENABLED, DI8_POLARITY, 8, DI8_EXTERNAL_NUMBER}; +gpioDigitalInputPin> din9 {DI9_ENABLED, DI9_POLARITY, 9, DI9_EXTERNAL_NUMBER}; +// gpioDigitalInputPin> din10 {DI10ENABLEDE, DI10_POLARITY, 10, DI10_EXTERNAL_NUMBER}; +// gpioDigitalInputPin> din11 {DI11ENABLEDE, DI11_POLARITY, 11, DI11_EXTERNAL_NUMBER}; +// gpioDigitalInputPin> din12 {DI12ENABLEDE, DI12_POLARITY, 12, DI12_EXTERNAL_NUMBER}; gpioDigitalInput* const d_in[] = {&din1, &din2, &din3, &din4, &din5, &din6, &din7, &din8, &din9}; + + +gpioDigitalOutputPin> dout1 { DO1_ENABLED, DO1_POLARITY, DO1_EXTERNAL_NUMBER, (uint32_t)200000 }; +gpioDigitalOutputPin> dout2 { DO2_ENABLED, DO2_POLARITY, DO2_EXTERNAL_NUMBER, (uint32_t)200000 }; +gpioDigitalOutputPin> dout3 { DO3_ENABLED, DO3_POLARITY, DO3_EXTERNAL_NUMBER, (uint32_t)200000 }; +gpioDigitalOutputPin> dout4 { DO4_ENABLED, DO4_POLARITY, DO4_EXTERNAL_NUMBER, (uint32_t)200000 }; +gpioDigitalOutputPin> dout5 { DO5_ENABLED, DO5_POLARITY, DO5_EXTERNAL_NUMBER, (uint32_t)200000 }; +gpioDigitalOutputPin> dout6 { DO6_ENABLED, DO6_POLARITY, DO6_EXTERNAL_NUMBER, (uint32_t)200000 }; +gpioDigitalOutputPin> dout7 { DO7_ENABLED, DO7_POLARITY, DO7_EXTERNAL_NUMBER, (uint32_t)200000 }; +gpioDigitalOutputPin> dout8 { DO8_ENABLED, DO8_POLARITY, DO8_EXTERNAL_NUMBER, (uint32_t)200000 }; +gpioDigitalOutputPin> dout9 { DO9_ENABLED, DO9_POLARITY, DO9_EXTERNAL_NUMBER, (uint32_t)200000 }; +gpioDigitalOutputPin> dout10 { DO10_ENABLED, DO10_POLARITY, DO10_EXTERNAL_NUMBER, (uint32_t)200000 }; +gpioDigitalOutputPin> dout11 { DO11_ENABLED, DO11_POLARITY, DO11_EXTERNAL_NUMBER, (uint32_t)200000 }; +gpioDigitalOutputPin> dout12 { DO12_ENABLED, DO12_POLARITY, DO12_EXTERNAL_NUMBER, (uint32_t)200000 }; +gpioDigitalOutputPin> dout13 { DO13_ENABLED, DO13_POLARITY, DO13_EXTERNAL_NUMBER, (uint32_t)200000 }; + gpioDigitalOutput* const d_out[] = {&dout1, &dout2, &dout3, &dout4, &dout5, &dout6, &dout7, &dout8, &dout9, &dout10, &dout11, &dout12, &dout13}; + + +/**** Setup Arrays - these are extern and MUST match the board_gpio.h ****/ + // not yet used -// gpioAnalogInput* a_in[A_IN_CHANNELS]; -// gpioAnalogOutput* a_out[A_OUT_CHANNELS]; +gpioAnalogInput* const a_in[] = {}; /************************************************************************************ **** CODE ************************************************************************** diff --git a/g2core/board/sbv300/board_gpio.h b/g2core/board/sbv300/board_gpio.h index 25a1cddcd..9bffbfe35 100644 --- a/g2core/board/sbv300/board_gpio.h +++ b/g2core/board/sbv300/board_gpio.h @@ -72,6 +72,9 @@ extern gpioDigitalInputPin> din9; // extern gpioDigitalInputPin> din11; // extern gpioDigitalInputPin> din12; +extern gpioDigitalInput* const d_in[D_IN_CHANNELS]; + + extern gpioDigitalOutputPin> dout1; extern gpioDigitalOutputPin> dout2; extern gpioDigitalOutputPin> dout3; @@ -86,5 +89,8 @@ extern gpioDigitalOutputPin> dout12; extern gpioDigitalOutputPin> dout13; +extern gpioDigitalOutput* const d_out[D_OUT_CHANNELS]; + +extern gpioAnalogInput* const a_in[A_IN_CHANNELS]; #endif // End of include guard: BOARD_GPIO_H_ONCE diff --git a/g2core/board/sbv300/board_xio.h b/g2core/board/sbv300/board_xio.h index 04af83fd8..a6411948c 100755 --- a/g2core/board/sbv300/board_xio.h +++ b/g2core/board/sbv300/board_xio.h @@ -37,10 +37,10 @@ #include "MotateUSBCDC.h" #if USB_SERIAL_PORTS_EXPOSED == 1 -typedef Motate::USBDevice< USBDeviceHardware, , Motate::USBCDC > XIOUSBDevice_t; +typedef Motate::USBDevice< Motate::USBDeviceHardware, Motate::USBCDC > XIOUSBDevice_t; #endif #if USB_SERIAL_PORTS_EXPOSED == 2 -typedef Motate::USBDevice< USBDeviceHardware, Motate::USBCDC, Motate::USBCDC > XIOUSBDevice_t; +typedef Motate::USBDevice< Motate::USBDeviceHardware, Motate::USBCDC, Motate::USBCDC > XIOUSBDevice_t; #endif extern XIOUSBDevice_t usb; From 1cb13ba0550fbf82baf9181f1d820e21dcf2b840 Mon Sep 17 00:00:00 2001 From: Alden Hart Date: Mon, 18 Jun 2018 09:46:10 -0400 Subject: [PATCH 193/193] Changed AS7 project files to include some additional files --- g2core/g2core.cppproj | 32 ++++++++++++++++++++++++++++++++ 1 file changed, 32 insertions(+) diff --git a/g2core/g2core.cppproj b/g2core/g2core.cppproj index c37cda302..fd014253d 100644 --- a/g2core/g2core.cppproj +++ b/g2core/g2core.cppproj @@ -1824,6 +1824,9 @@ compile + + compile + compile @@ -1833,6 +1836,9 @@ compile + + compile + compile @@ -1851,6 +1857,18 @@ compile + + compile + + + compile + + + compile + + + compile + compile @@ -1866,6 +1884,9 @@ compile + + compile + compile @@ -2016,6 +2037,15 @@ compile + + compile + + + compile + + + compile + compile @@ -2067,6 +2097,8 @@ + +