From 1a397825f9eed334e809725ee5fb103bf39643c9 Mon Sep 17 00:00:00 2001 From: Martin Renold Date: Wed, 1 May 2013 08:18:45 +0200 Subject: [PATCH 01/18] fix DEFAULT_AXIS_STEPS_PER_UNIT minor Z rounding error --- Marlin/Configuration.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 9b07d14b6a..eed4abc81f 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -282,8 +282,8 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th // default settings -#define DEFAULT_AXIS_STEPS_PER_UNIT {78.7402,78.7402,200*8/3,760*1.1} // default steps per unit for ultimaker -#define DEFAULT_MAX_FEEDRATE {500, 500, 5, 25} // (mm/sec) +#define DEFAULT_AXIS_STEPS_PER_UNIT {78.7402,78.7402,200.0*8/3,760*1.1} // default steps per unit for ultimaker +#define DEFAULT_MAX_FEEDRATE {500, 500, 5, 25} // (mm/sec) #define DEFAULT_MAX_ACCELERATION {9000,9000,100,10000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for skeinforge 40+, for older versions raise them a lot. #define DEFAULT_ACCELERATION 3000 // X, Y, Z and E max acceleration in mm/s^2 for printing moves From fc4ab051571925e3d6668a66c3daaa8791cf1672 Mon Sep 17 00:00:00 2001 From: Arnoud Date: Fri, 3 May 2013 21:32:34 +0200 Subject: [PATCH 02/18] Solved minor bug in controllerFan() Extruder 2 was checked where extruder 1 should be checked. --- Marlin/Marlin_main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 04c3794fa8..233e2fa427 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -1974,7 +1974,7 @@ void controllerFan() || !READ(E2_ENABLE_PIN) #endif #if EXTRUDER > 1 - || !READ(E2_ENABLE_PIN) + || !READ(E1_ENABLE_PIN) #endif || !READ(E0_ENABLE_PIN)) //If any of the drivers are enabled... { From db2f157a222c0fbffb274a2f9c27f89858f51234 Mon Sep 17 00:00:00 2001 From: midopple Date: Sun, 5 May 2013 19:19:55 +0200 Subject: [PATCH 03/18] Replace the <= to < in the Command M907, M350 and M351. The for loop for Axis count over the Array. Add a break after M907 --- Marlin/Marlin_main.cpp | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 233e2fa427..9f2ba7be17 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -1708,11 +1708,12 @@ void process_commands() case 907: // M907 Set digital trimpot motor current using axis codes. { #if DIGIPOTSS_PIN > -1 - for(int i=0;i<=NUM_AXIS;i++) if(code_seen(axis_codes[i])) digipot_current(i,code_value()); + for(int i=0;i -1 @@ -1727,7 +1728,7 @@ void process_commands() { #if X_MS1_PIN > -1 if(code_seen('S')) for(int i=0;i<=4;i++) microstep_mode(i,code_value()); - for(int i=0;i<=NUM_AXIS;i++) if(code_seen(axis_codes[i])) microstep_mode(i,(uint8_t)code_value()); + for(int i=0;i Date: Sun, 5 May 2013 19:23:59 +0200 Subject: [PATCH 04/18] If CORE_XY is in use X and Y Axis had to be activated at the same time --- Marlin/planner.cpp | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/Marlin/planner.cpp b/Marlin/planner.cpp index e45c9d7ff9..854fd19eec 100644 --- a/Marlin/planner.cpp +++ b/Marlin/planner.cpp @@ -582,8 +582,16 @@ void plan_buffer_line(const float &x, const float &y, const float &z, const floa block->active_extruder = extruder; //enable active axes + #ifdef COREXY + if((block->steps_x != 0) || (block->steps_y != 0)) + { + enable_x(); + enable_y(); + } + #else if(block->steps_x != 0) enable_x(); if(block->steps_y != 0) enable_y(); + #endif #ifndef Z_LATE_ENABLE if(block->steps_z != 0) enable_z(); #endif From 6fb9573157bc95df20e7649e32f0d9d1edec5a9a Mon Sep 17 00:00:00 2001 From: gregor Date: Fri, 10 May 2013 21:57:17 +0200 Subject: [PATCH 05/18] added support for the reprapworld keypad --- Marlin/Configuration.h | 10 +++++++++ Marlin/pins.h | 24 +++++++++++++++++--- Marlin/ultralcd.cpp | 50 ++++++++++++++++++++++++++++++++++++++++++ Marlin/ultralcd.h | 18 +++++++++++++++ 4 files changed, 99 insertions(+), 3 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index eed4abc81f..693e66a716 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -338,6 +338,11 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th // ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib //#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER +// The RepRapWorld Keypad v1.1 +// http://reprapworld.com/?products_details&products_id=202&cPath=1591_1626 +//#define KEYPAD +//#define KEYPAD_MOVE_STEP 10.0 // how much should be moved when a key is pressed, eg 10.0 means 10mm per click + //automatic expansion #if defined (REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define DOGLCD @@ -350,6 +355,11 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th #define NEWPANEL #endif +#if defined(KEYPAD) + #define NEWPANEL + #define ULTIPANEL +#endif + // Preheat Constants #define PLA_PREHEAT_HOTEND_TEMP 180 #define PLA_PREHEAT_HPB_TEMP 70 diff --git a/Marlin/pins.h b/Marlin/pins.h index 2424010aa5..53932dc20f 100644 --- a/Marlin/pins.h +++ b/Marlin/pins.h @@ -416,9 +416,27 @@ #define BEEPER 33 // Beeper on AUX-4 //buttons are directly attached using AUX-2 - #define BTN_EN1 37 - #define BTN_EN2 35 - #define BTN_ENC 31 //the click + #ifdef KEYPAD + #define BTN_EN1 64 // encoder + #define BTN_EN2 59 // encoder + #define BTN_ENC 63 // enter button + #define SHIFT_OUT 40 // shift register + #define SHIFT_CLK 44 // shift register + #define SHIFT_LD 42 // shift register + // define register bit values, don't change it + #define BLEN_KEYPAD_F3 0 + #define BLEN_KEYPAD_F2 1 + #define BLEN_KEYPAD_F1 2 + #define BLEN_KEYPAD_UP 3 + #define BLEN_KEYPAD_RIGHT 4 + #define BLEN_KEYPAD_MIDDLE 5 + #define BLEN_KEYPAD_DOWN 6 + #define BLEN_KEYPAD_LEFT 7 + #else + #define BTN_EN1 37 + #define BTN_EN2 35 + #define BTN_ENC 31 //the click + #endif #ifdef G3D_PANEL #define SDCARDDETECT 49 diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index fe0619fb85..1d2a97e7da 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -113,6 +113,7 @@ static void menu_action_setting_edit_callback_long5(const char* pstr, unsigned l /** Used variables to keep track of the menu */ volatile uint8_t buttons;//Contains the bits of the currently pressed buttons. +volatile uint8_t buttons_keypad; // to store the keypad shiftregister values uint8_t currentMenuViewOffset; /* scroll offset in the current menu */ uint32_t blocking_enc; @@ -687,6 +688,25 @@ menu_edit_type(float, float51, ftostr51, 10) menu_edit_type(float, float52, ftostr52, 100) menu_edit_type(unsigned long, long5, ftostr5, 0.01) +#ifdef KEYPAD + static void keypad_move_y_down() { + SERIAL_ECHO("keypad_move_y_down"); + encoderPosition = 1; + move_menu_scale = KEYPAD_MOVE_STEP; + lcd_move_y(); + } + static void keypad_move_y_up() { + encoderPosition = -1; + move_menu_scale = KEYPAD_MOVE_STEP; + lcd_move_y(); + } + static void keypad_move_home() { + //enquecommand_P((PSTR("G28"))); // move all axis home + // TODO gregor: move all axis home, i have currently only one axis on my prusa i3 + enquecommand_P((PSTR("G28 Y"))); + } +#endif + /** End of menus **/ static void lcd_quick_feedback() @@ -750,6 +770,13 @@ void lcd_init() WRITE(BTN_EN1,HIGH); WRITE(BTN_EN2,HIGH); WRITE(BTN_ENC,HIGH); + #ifdef KEYPAD + pinMode(SHIFT_CLK,OUTPUT); + pinMode(SHIFT_LD,OUTPUT); + pinMode(SHIFT_OUT,INPUT); + WRITE(SHIFT_OUT,HIGH); + WRITE(SHIFT_LD,HIGH); + #endif #else pinMode(SHIFT_CLK,OUTPUT); pinMode(SHIFT_LD,OUTPUT); @@ -796,6 +823,17 @@ void lcd_update() if (lcd_next_update_millis < millis()) { #ifdef ULTIPANEL + #ifdef KEYPAD + if (KEYPAD_MOVE_Y_DOWN) { + keypad_move_y_down(); + } + if (KEYPAD_MOVE_Y_UP) { + keypad_move_y_up(); + } + if (KEYPAD_MOVE_HOME) { + keypad_move_home(); + } + #endif if (encoderDiff) { lcdDrawUpdate = 1; @@ -876,6 +914,18 @@ void lcd_buttons_update() if((blocking_enc>1; + if(READ(SHIFT_OUT)) + newbutton_keypad|=(1<<7); + WRITE(SHIFT_CLK,HIGH); + WRITE(SHIFT_CLK,LOW); + } + buttons_keypad=~newbutton_keypad; //invert it, because a pressed switch produces a logical 0 #else //read it from the shift register uint8_t newbutton=0; WRITE(SHIFT_LD,LOW); diff --git a/Marlin/ultralcd.h b/Marlin/ultralcd.h index 28de229726..1df3ed4b10 100644 --- a/Marlin/ultralcd.h +++ b/Marlin/ultralcd.h @@ -23,6 +23,9 @@ #ifdef ULTIPANEL void lcd_buttons_update(); extern volatile uint8_t buttons; //the last checked buttons in a bit array. + #ifdef KEYPAD + extern volatile uint8_t buttons_keypad; // to store the keypad shiftregister values + #endif #else FORCE_INLINE void lcd_buttons_update() {} #endif @@ -41,6 +44,21 @@ #define EN_A (1< Date: Fri, 10 May 2013 22:20:02 +0200 Subject: [PATCH 06/18] changes: - changed the variables from keypad to reprapworld_keypad - added a missing ifdef check --- Marlin/Configuration.h | 8 +++--- Marlin/pins.h | 18 ++++++------- Marlin/ultralcd.cpp | 57 +++++++++++++++++++++--------------------- Marlin/ultralcd.h | 32 ++++++++++++------------ 4 files changed, 58 insertions(+), 57 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 693e66a716..83944ab032 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -338,10 +338,10 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th // ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib //#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER -// The RepRapWorld Keypad v1.1 +// The RepRapWorld REPRAPWORLD_KEYPAD v1.1 // http://reprapworld.com/?products_details&products_id=202&cPath=1591_1626 -//#define KEYPAD -//#define KEYPAD_MOVE_STEP 10.0 // how much should be moved when a key is pressed, eg 10.0 means 10mm per click +//#define REPRAPWORLD_KEYPAD +//#define REPRAPWORLD_KEYPAD_MOVE_STEP 10.0 // how much should be moved when a key is pressed, eg 10.0 means 10mm per click //automatic expansion #if defined (REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) @@ -355,7 +355,7 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th #define NEWPANEL #endif -#if defined(KEYPAD) +#if defined(REPRAPWORLD_KEYPAD) #define NEWPANEL #define ULTIPANEL #endif diff --git a/Marlin/pins.h b/Marlin/pins.h index 53932dc20f..952fa7a9a3 100644 --- a/Marlin/pins.h +++ b/Marlin/pins.h @@ -416,7 +416,7 @@ #define BEEPER 33 // Beeper on AUX-4 //buttons are directly attached using AUX-2 - #ifdef KEYPAD + #ifdef REPRAPWORLD_KEYPAD #define BTN_EN1 64 // encoder #define BTN_EN2 59 // encoder #define BTN_ENC 63 // enter button @@ -424,14 +424,14 @@ #define SHIFT_CLK 44 // shift register #define SHIFT_LD 42 // shift register // define register bit values, don't change it - #define BLEN_KEYPAD_F3 0 - #define BLEN_KEYPAD_F2 1 - #define BLEN_KEYPAD_F1 2 - #define BLEN_KEYPAD_UP 3 - #define BLEN_KEYPAD_RIGHT 4 - #define BLEN_KEYPAD_MIDDLE 5 - #define BLEN_KEYPAD_DOWN 6 - #define BLEN_KEYPAD_LEFT 7 + #define BLEN_REPRAPWORLD_KEYPAD_F3 0 + #define BLEN_REPRAPWORLD_KEYPAD_F2 1 + #define BLEN_REPRAPWORLD_KEYPAD_F1 2 + #define BLEN_REPRAPWORLD_KEYPAD_UP 3 + #define BLEN_REPRAPWORLD_KEYPAD_RIGHT 4 + #define BLEN_REPRAPWORLD_KEYPAD_MIDDLE 5 + #define BLEN_REPRAPWORLD_KEYPAD_DOWN 6 + #define BLEN_REPRAPWORLD_KEYPAD_LEFT 7 #else #define BTN_EN1 37 #define BTN_EN2 35 diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 1d2a97e7da..3f74e2743b 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -113,7 +113,7 @@ static void menu_action_setting_edit_callback_long5(const char* pstr, unsigned l /** Used variables to keep track of the menu */ volatile uint8_t buttons;//Contains the bits of the currently pressed buttons. -volatile uint8_t buttons_keypad; // to store the keypad shiftregister values +volatile uint8_t buttons_reprapworld_keypad; // to store the reprapworld_keypad shiftregister values uint8_t currentMenuViewOffset; /* scroll offset in the current menu */ uint32_t blocking_enc; @@ -688,19 +688,18 @@ menu_edit_type(float, float51, ftostr51, 10) menu_edit_type(float, float52, ftostr52, 100) menu_edit_type(unsigned long, long5, ftostr5, 0.01) -#ifdef KEYPAD - static void keypad_move_y_down() { - SERIAL_ECHO("keypad_move_y_down"); +#ifdef REPRAPWORLD_KEYPAD + static void reprapworld_keypad_move_y_down() { encoderPosition = 1; - move_menu_scale = KEYPAD_MOVE_STEP; + move_menu_scale = REPRAPWORLD_KEYPAD_MOVE_STEP; lcd_move_y(); } - static void keypad_move_y_up() { + static void reprapworld_keypad_move_y_up() { encoderPosition = -1; - move_menu_scale = KEYPAD_MOVE_STEP; + move_menu_scale = REPRAPWORLD_KEYPAD_MOVE_STEP; lcd_move_y(); } - static void keypad_move_home() { + static void reprapworld_keypad_move_home() { //enquecommand_P((PSTR("G28"))); // move all axis home // TODO gregor: move all axis home, i have currently only one axis on my prusa i3 enquecommand_P((PSTR("G28 Y"))); @@ -770,7 +769,7 @@ void lcd_init() WRITE(BTN_EN1,HIGH); WRITE(BTN_EN2,HIGH); WRITE(BTN_ENC,HIGH); - #ifdef KEYPAD + #ifdef REPRAPWORLD_KEYPAD pinMode(SHIFT_CLK,OUTPUT); pinMode(SHIFT_LD,OUTPUT); pinMode(SHIFT_OUT,INPUT); @@ -823,15 +822,15 @@ void lcd_update() if (lcd_next_update_millis < millis()) { #ifdef ULTIPANEL - #ifdef KEYPAD - if (KEYPAD_MOVE_Y_DOWN) { - keypad_move_y_down(); + #ifdef REPRAPWORLD_KEYPAD + if (REPRAPWORLD_KEYPAD_MOVE_Y_DOWN) { + reprapworld_keypad_move_y_down(); } - if (KEYPAD_MOVE_Y_UP) { - keypad_move_y_up(); + if (REPRAPWORLD_KEYPAD_MOVE_Y_UP) { + reprapworld_keypad_move_y_up(); } - if (KEYPAD_MOVE_HOME) { - keypad_move_home(); + if (REPRAPWORLD_KEYPAD_MOVE_HOME) { + reprapworld_keypad_move_home(); } #endif if (encoderDiff) @@ -914,18 +913,20 @@ void lcd_buttons_update() if((blocking_enc>1; - if(READ(SHIFT_OUT)) - newbutton_keypad|=(1<<7); - WRITE(SHIFT_CLK,HIGH); - WRITE(SHIFT_CLK,LOW); - } - buttons_keypad=~newbutton_keypad; //invert it, because a pressed switch produces a logical 0 + #ifdef REPRAPWORLD_KEYPAD + // for the reprapworld_keypad + uint8_t newbutton_reprapworld_keypad=0; + WRITE(SHIFT_LD,LOW); + WRITE(SHIFT_LD,HIGH); + for(int8_t i=0;i<8;i++) { + newbutton_reprapworld_keypad = newbutton_reprapworld_keypad>>1; + if(READ(SHIFT_OUT)) + newbutton_reprapworld_keypad|=(1<<7); + WRITE(SHIFT_CLK,HIGH); + WRITE(SHIFT_CLK,LOW); + } + buttons_reprapworld_keypad=~newbutton_reprapworld_keypad; //invert it, because a pressed switch produces a logical 0 + #endif #else //read it from the shift register uint8_t newbutton=0; WRITE(SHIFT_LD,LOW); diff --git a/Marlin/ultralcd.h b/Marlin/ultralcd.h index 1df3ed4b10..03f2fe1862 100644 --- a/Marlin/ultralcd.h +++ b/Marlin/ultralcd.h @@ -23,8 +23,8 @@ #ifdef ULTIPANEL void lcd_buttons_update(); extern volatile uint8_t buttons; //the last checked buttons in a bit array. - #ifdef KEYPAD - extern volatile uint8_t buttons_keypad; // to store the keypad shiftregister values + #ifdef REPRAPWORLD_KEYPAD + extern volatile uint8_t buttons_reprapworld_keypad; // to store the keypad shiftregister values #endif #else FORCE_INLINE void lcd_buttons_update() {} @@ -44,21 +44,21 @@ #define EN_A (1< Date: Tue, 14 May 2013 16:56:19 +0200 Subject: [PATCH 07/18] Fixed "Cooldown" Selection not reseting bed temp - enquecommand with multiple lines "\n" doesn't work -> M140 S0 didn't get processed. So I wrote a new func for the cooldown which uses setTargetHotend. In addition this does return to status page after selection. - Added setWatch() to preheat-functions (Temperatur sanity check would never have worked when preheating from the lcd panel) --- Marlin/ultralcd.cpp | 13 ++++++++++++- 1 file changed, 12 insertions(+), 1 deletion(-) diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 3f74e2743b..4d4f1ce65d 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -252,6 +252,7 @@ void lcd_preheat_pla() setTargetBed(plaPreheatHPBTemp); fanSpeed = plaPreheatFanSpeed; lcd_return_to_status(); + setWatch(); // heater sanity check timer } void lcd_preheat_abs() @@ -262,6 +263,16 @@ void lcd_preheat_abs() setTargetBed(absPreheatHPBTemp); fanSpeed = absPreheatFanSpeed; lcd_return_to_status(); + setWatch(); // heater sanity check timer +} + +static void lcd_cooldown() +{ + setTargetHotend0(0); + setTargetHotend1(0); + setTargetHotend2(0); + setTargetBed(0); + lcd_return_to_status(); } static void lcd_tune_menu() @@ -299,7 +310,7 @@ static void lcd_prepare_menu() //MENU_ITEM(gcode, MSG_SET_ORIGIN, PSTR("G92 X0 Y0 Z0")); MENU_ITEM(function, MSG_PREHEAT_PLA, lcd_preheat_pla); MENU_ITEM(function, MSG_PREHEAT_ABS, lcd_preheat_abs); - MENU_ITEM(gcode, MSG_COOLDOWN, PSTR("M104 S0\nM140 S0")); + MENU_ITEM(function, MSG_COOLDOWN, lcd_cooldown); MENU_ITEM(submenu, MSG_MOVE_AXIS, lcd_move_menu); END_MENU(); } From fbd899a37d2ec36a37119bcbbd3fdde4b3e4b649 Mon Sep 17 00:00:00 2001 From: Jordan Miller Date: Tue, 14 May 2013 16:25:53 -0400 Subject: [PATCH 08/18] Support for BariCUDA Paste Extruder derived from MakerBot Frostruder. Using Ultimachine RAMBo board. M126/M127 and M128/M129. --- Marlin/Marlin.h | 2 ++ Marlin/Marlin_main.cpp | 37 +++++++++++++++++++++++++++++++++++++ Marlin/pins.h | 2 +- Marlin/planner.cpp | 19 +++++++++++++++++++ Marlin/planner.h | 2 ++ 5 files changed, 61 insertions(+), 1 deletion(-) diff --git a/Marlin/Marlin.h b/Marlin/Marlin.h index 25c5aca636..af3f517c86 100644 --- a/Marlin/Marlin.h +++ b/Marlin/Marlin.h @@ -186,6 +186,8 @@ extern float add_homeing[3]; extern float min_pos[3]; extern float max_pos[3]; extern int fanSpeed; +extern int ValvePressure; +extern int EtoPPressure; #ifdef FWRETRACT extern bool autoretract_enabled; diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 9f2ba7be17..3d966bf1d7 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -101,6 +101,10 @@ // M115 - Capabilities string // M117 - display message // M119 - Output Endstop status to serial port +// M126 - Solenoid Air Valve Open (BariCUDA support by jmil) +// M127 - Solenoid Air Valve Closed (BariCUDA vent to atmospheric pressure by jmil) +// M128 - EtoP Open (BariCUDA EtoP = electricity to air pressure transducer by jmil) +// M129 - EtoP Closed (BariCUDA EtoP = electricity to air pressure transducer by jmil) // M140 - Set bed target temp // M190 - Wait for bed current temp to reach target temp. // M200 - Set filament diameter @@ -168,6 +172,8 @@ float extruder_offset[2][EXTRUDERS] = { #endif uint8_t active_extruder = 0; int fanSpeed=0; +int ValvePressure=0; +int EtoPPressure=0; #ifdef FWRETRACT bool autoretract_enabled=true; @@ -1169,6 +1175,37 @@ void process_commands() break; #endif //FAN_PIN + // PWM for HEATER_1_PIN + #if HEATER_1_PIN > -1 + case 126: //M126 valve open + if (code_seen('S')){ + ValvePressure=constrain(code_value(),0,255); + } + else { + ValvePressure=255; + } + break; + case 127: //M127 valve closed + ValvePressure = 0; + break; + #endif //HEATER_1_PIN + + // PWM for HEATER_2_PIN + #if HEATER_2_PIN > -1 + case 128: //M128 valve open + if (code_seen('S')){ + EtoPPressure=constrain(code_value(),0,255); + } + else { + EtoPPressure=255; + } + break; + case 129: //M129 valve closed + EtoPPressure = 0; + break; + #endif //HEATER_2_PIN + + #if (PS_ON_PIN > -1) case 80: // M80 - ATX Power On SET_OUTPUT(PS_ON_PIN); //GND diff --git a/Marlin/pins.h b/Marlin/pins.h index 952fa7a9a3..ac25dea4cf 100644 --- a/Marlin/pins.h +++ b/Marlin/pins.h @@ -1474,7 +1474,7 @@ #define HEATER_1_PIN 7 #define TEMP_1_PIN 1 -#define HEATER_2_PIN -1 +#define HEATER_2_PIN 6 #define TEMP_2_PIN -1 #define E0_STEP_PIN 34 diff --git a/Marlin/planner.cpp b/Marlin/planner.cpp index 854fd19eec..f7473c6023 100644 --- a/Marlin/planner.cpp +++ b/Marlin/planner.cpp @@ -439,12 +439,18 @@ void check_axes_activity() unsigned char z_active = 0; unsigned char e_active = 0; unsigned char tail_fan_speed = fanSpeed; + unsigned char valve_pressure = 0; + unsigned char e_to_p_pressure = 0; + unsigned char tail_valve_pressure = 0; + unsigned char tail_e_to_p_pressure = 0; block_t *block; if(block_buffer_tail != block_buffer_head) { uint8_t block_index = block_buffer_tail; tail_fan_speed = block_buffer[block_index].fan_speed; + tail_valve_pressure = block_buffer[block_index].valve_pressure; + tail_e_to_p_pressure = block_buffer[block_index].e_to_p_pressure; while(block_index != block_buffer_head) { block = &block_buffer[block_index]; @@ -486,6 +492,17 @@ void check_axes_activity() #ifdef AUTOTEMP getHighESpeed(); #endif + +#if HEATER_1_PIN > -1 + if (ValvePressure != 0){ + analogWrite(HEATER_1_PIN,ValvePressure); // If buffer is empty use current fan speed + } +#endif +#if HEATER_2_PIN > -1 + if (EtoPPressure != 0){ + analogWrite(HEATER_2_PIN,EtoPPressure); // If buffer is empty use current fan speed + } +#endif } @@ -559,6 +576,8 @@ void plan_buffer_line(const float &x, const float &y, const float &z, const floa } block->fan_speed = fanSpeed; + block->valve_pressure = ValvePressure; + block->e_to_p_pressure = EtoPPressure; // Compute direction bits for this block block->direction_bits = 0; diff --git a/Marlin/planner.h b/Marlin/planner.h index 9a904e5776..4af72a475e 100644 --- a/Marlin/planner.h +++ b/Marlin/planner.h @@ -60,6 +60,8 @@ typedef struct { unsigned long final_rate; // The minimal rate at exit unsigned long acceleration_st; // acceleration steps/sec^2 unsigned long fan_speed; + unsigned long valve_pressure; + unsigned long e_to_p_pressure; volatile char busy; } block_t; From 37f3199df3ad8607caf5cb71158092e28cfce594 Mon Sep 17 00:00:00 2001 From: Jordan Miller Date: Tue, 14 May 2013 17:16:10 -0400 Subject: [PATCH 09/18] fixed problems in planner with solenoids for BariCUDA when set to 0 --- Marlin/planner.cpp | 21 +++++++++++++++++++-- 1 file changed, 19 insertions(+), 2 deletions(-) diff --git a/Marlin/planner.cpp b/Marlin/planner.cpp index f7473c6023..0bf59593e1 100644 --- a/Marlin/planner.cpp +++ b/Marlin/planner.cpp @@ -495,12 +495,29 @@ void check_axes_activity() #if HEATER_1_PIN > -1 if (ValvePressure != 0){ - analogWrite(HEATER_1_PIN,ValvePressure); // If buffer is empty use current fan speed + analogWrite(HEATER_1_PIN,ValvePressure); // If buffer is empty use current valve pressure + } + + if((ValvePressure == 0) && (valve_pressure ==0)) { + analogWrite(HEATER_1_PIN, 0); + } + + if (ValvePressure != 0 && tail_valve_pressure !=0) { + analogWrite(HEATER_1_PIN,tail_valve_pressure); } #endif + #if HEATER_2_PIN > -1 if (EtoPPressure != 0){ - analogWrite(HEATER_2_PIN,EtoPPressure); // If buffer is empty use current fan speed + analogWrite(HEATER_2_PIN,EtoPPressure); // If buffer is empty use current EtoP pressure + } + + if((EtoPPressure == 0) && (e_to_p_pressure ==0)) { + analogWrite(HEATER_2_PIN, 0); + } + + if (EtoPPressure != 0 && tail_e_to_p_pressure !=0) { + analogWrite(HEATER_2_PIN,tail_e_to_p_pressure); } #endif } From bd2cd4903e5daedcfebc06b90e7c0e2cf05e5eaa Mon Sep 17 00:00:00 2001 From: Erik van der Zalm Date: Tue, 14 May 2013 23:56:32 +0200 Subject: [PATCH 10/18] Added #ifdef BARICUDA around the BariCUDA changes --- Marlin/Configuration.h | 3 +++ Marlin/Marlin.h | 2 ++ Marlin/Marlin_main.cpp | 60 ++++++++++++++++++++++-------------------- Marlin/pins.h | 4 +++ Marlin/planner.cpp | 14 +++++++--- Marlin/planner.h | 2 ++ 6 files changed, 53 insertions(+), 32 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 83944ab032..3405dfbffe 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -403,6 +403,9 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th // SF send wrong arc g-codes when using Arc Point as fillet procedure //#define SF_ARC_FIX +// Support for the BariCUDA Paste Extruder. +//#define BARICUDA + #include "Configuration_adv.h" #include "thermistortables.h" diff --git a/Marlin/Marlin.h b/Marlin/Marlin.h index af3f517c86..551a553907 100644 --- a/Marlin/Marlin.h +++ b/Marlin/Marlin.h @@ -186,8 +186,10 @@ extern float add_homeing[3]; extern float min_pos[3]; extern float max_pos[3]; extern int fanSpeed; +#ifdef BARICUDA extern int ValvePressure; extern int EtoPPressure; +#endif #ifdef FWRETRACT extern bool autoretract_enabled; diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 3d966bf1d7..0a528ea058 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -172,8 +172,10 @@ float extruder_offset[2][EXTRUDERS] = { #endif uint8_t active_extruder = 0; int fanSpeed=0; +#ifdef BARICUDA int ValvePressure=0; int EtoPPressure=0; +#endif #ifdef FWRETRACT bool autoretract_enabled=true; @@ -1174,37 +1176,37 @@ void process_commands() fanSpeed = 0; break; #endif //FAN_PIN - + #ifdef BARICUDA // PWM for HEATER_1_PIN - #if HEATER_1_PIN > -1 - case 126: //M126 valve open - if (code_seen('S')){ - ValvePressure=constrain(code_value(),0,255); - } - else { - ValvePressure=255; - } - break; - case 127: //M127 valve closed - ValvePressure = 0; - break; - #endif //HEATER_1_PIN - - // PWM for HEATER_2_PIN - #if HEATER_2_PIN > -1 - case 128: //M128 valve open - if (code_seen('S')){ - EtoPPressure=constrain(code_value(),0,255); - } - else { - EtoPPressure=255; - } - break; - case 129: //M129 valve closed - EtoPPressure = 0; - break; - #endif //HEATER_2_PIN + #if HEATER_1_PIN > -1 + case 126: //M126 valve open + if (code_seen('S')){ + ValvePressure=constrain(code_value(),0,255); + } + else { + ValvePressure=255; + } + break; + case 127: //M127 valve closed + ValvePressure = 0; + break; + #endif //HEATER_1_PIN + // PWM for HEATER_2_PIN + #if HEATER_2_PIN > -1 + case 128: //M128 valve open + if (code_seen('S')){ + EtoPPressure=constrain(code_value(),0,255); + } + else { + EtoPPressure=255; + } + break; + case 129: //M129 valve closed + EtoPPressure = 0; + break; + #endif //HEATER_2_PIN + #endif #if (PS_ON_PIN > -1) case 80: // M80 - ATX Power On diff --git a/Marlin/pins.h b/Marlin/pins.h index ac25dea4cf..a13c522f71 100644 --- a/Marlin/pins.h +++ b/Marlin/pins.h @@ -1474,7 +1474,11 @@ #define HEATER_1_PIN 7 #define TEMP_1_PIN 1 +#ifdef BARICUDA #define HEATER_2_PIN 6 +#else +#define HEATER_2_PIN -1 +#endif #define TEMP_2_PIN -1 #define E0_STEP_PIN 34 diff --git a/Marlin/planner.cpp b/Marlin/planner.cpp index 0bf59593e1..1a37cecb47 100644 --- a/Marlin/planner.cpp +++ b/Marlin/planner.cpp @@ -439,18 +439,22 @@ void check_axes_activity() unsigned char z_active = 0; unsigned char e_active = 0; unsigned char tail_fan_speed = fanSpeed; + #ifdef BARICUDA unsigned char valve_pressure = 0; unsigned char e_to_p_pressure = 0; unsigned char tail_valve_pressure = 0; unsigned char tail_e_to_p_pressure = 0; + #endif block_t *block; if(block_buffer_tail != block_buffer_head) { uint8_t block_index = block_buffer_tail; tail_fan_speed = block_buffer[block_index].fan_speed; + #ifdef BARICUDA tail_valve_pressure = block_buffer[block_index].valve_pressure; tail_e_to_p_pressure = block_buffer[block_index].e_to_p_pressure; + #endif while(block_index != block_buffer_head) { block = &block_buffer[block_index]; @@ -493,7 +497,8 @@ void check_axes_activity() getHighESpeed(); #endif -#if HEATER_1_PIN > -1 +#ifdef BARICUDA + #if HEATER_1_PIN > -1 if (ValvePressure != 0){ analogWrite(HEATER_1_PIN,ValvePressure); // If buffer is empty use current valve pressure } @@ -505,9 +510,9 @@ void check_axes_activity() if (ValvePressure != 0 && tail_valve_pressure !=0) { analogWrite(HEATER_1_PIN,tail_valve_pressure); } -#endif + #endif -#if HEATER_2_PIN > -1 + #if HEATER_2_PIN > -1 if (EtoPPressure != 0){ analogWrite(HEATER_2_PIN,EtoPPressure); // If buffer is empty use current EtoP pressure } @@ -519,6 +524,7 @@ void check_axes_activity() if (EtoPPressure != 0 && tail_e_to_p_pressure !=0) { analogWrite(HEATER_2_PIN,tail_e_to_p_pressure); } + #endif #endif } @@ -593,8 +599,10 @@ void plan_buffer_line(const float &x, const float &y, const float &z, const floa } block->fan_speed = fanSpeed; + #ifdef BARICUDA block->valve_pressure = ValvePressure; block->e_to_p_pressure = EtoPPressure; + #endif // Compute direction bits for this block block->direction_bits = 0; diff --git a/Marlin/planner.h b/Marlin/planner.h index 4af72a475e..703646eb13 100644 --- a/Marlin/planner.h +++ b/Marlin/planner.h @@ -60,8 +60,10 @@ typedef struct { unsigned long final_rate; // The minimal rate at exit unsigned long acceleration_st; // acceleration steps/sec^2 unsigned long fan_speed; + #ifdef BARICUDA unsigned long valve_pressure; unsigned long e_to_p_pressure; + #endif volatile char busy; } block_t; From 9cc15876be8e2a584fd5ceeee48a751bbda25657 Mon Sep 17 00:00:00 2001 From: MaikStohn Date: Thu, 16 May 2013 01:16:08 +0200 Subject: [PATCH 11/18] Add support for RUMBA thermocouple add on --- Marlin/pins.h | 59 ++++++++++++++++++++++++++++++++++++++++++--------- 1 file changed, 49 insertions(+), 10 deletions(-) diff --git a/Marlin/pins.h b/Marlin/pins.h index a13c522f71..ad88338e87 100644 --- a/Marlin/pins.h +++ b/Marlin/pins.h @@ -1053,17 +1053,56 @@ #define PS_ON_PIN 45 #define KILL_PIN 46 -#define HEATER_0_PIN 2 // EXTRUDER 1 -#define HEATER_1_PIN 3 // EXTRUDER 2 -#define HEATER_2_PIN 6 // EXTRUDER 3 -//optional FAN1 can be used as 4th heater output: #define HEATER_3_PIN 8 // EXTRUDER 4 -#define HEATER_BED_PIN 9 // BED +#if (TEMP_SENSOR_0==0) + #define TEMP_0_PIN -1 + #define HEATER_0_PIN -1 +#else + #define HEATER_0_PIN 2 // EXTRUDER 1 + #if (TEMP_SENSOR_0==-1) + #define TEMP_0_PIN 6 // ANALOG NUMBERING - connector *K1* on RUMBA thermocouple ADD ON is used + #else + #define TEMP_0_PIN 15 // ANALOG NUMBERING - default connector for thermistor *T0* on rumba board is used + #endif +#endif -#define TEMP_0_PIN 15 // ANALOG NUMBERING -#define TEMP_1_PIN 14 // ANALOG NUMBERING -#define TEMP_2_PIN 13 // ANALOG NUMBERING -//optional for extruder 4 or chamber: #define TEMP_2_PIN 12 // ANALOG NUMBERING -#define TEMP_BED_PIN 11 // ANALOG NUMBERING +#if (TEMP_SENSOR_1==0) + #define TEMP_1_PIN -1 + #define HEATER_1_PIN -1 +#else + #define HEATER_1_PIN 3 // EXTRUDER 2 + #if (TEMP_SENSOR_1==-1) + #define TEMP_1_PIN 5 // ANALOG NUMBERING - connector *K2* on RUMBA thermocouple ADD ON is used + #else + #define TEMP_1_PIN 14 // ANALOG NUMBERING - default connector for thermistor *T1* on rumba board is used + #endif +#endif + +#if (TEMP_SENSOR_2==0) + #define TEMP_2_PIN -1 + #define HEATER_2_PIN -1 +#else + #define HEATER_2_PIN 6 // EXTRUDER 3 + #if (TEMP_SENSOR_2==-1) + #define TEMP_2_PIN 7 // ANALOG NUMBERING - connector *K3* on RUMBA thermocouple ADD ON is used <-- this can not be used when TEMP_SENSOR_BED is defined as thermocouple + #else + #define TEMP_2_PIN 13 // ANALOG NUMBERING - default connector for thermistor *T2* on rumba board is used + #endif +#endif + +//optional for extruder 4 or chamber: #define TEMP_X_PIN 12 // ANALOG NUMBERING - default connector for thermistor *T3* on rumba board is used +//optional FAN1 can be used as 4th heater output: #define HEATER_3_PIN 8 // EXTRUDER 4 + +#if (TEMP_SENSOR_BED==0) + #define TEMP_BED_PIN -1 + #define HEATER_BED_PIN -1 +#else + #define HEATER_BED_PIN 9 // BED + #if (TEMP_SENSOR_BED==-1) + #define TEMP_BED_PIN 7 // ANALOG NUMBERING - connector *K3* on RUMBA thermocouple ADD ON is used <-- this can not be used when TEMP_SENSOR_2 is defined as thermocouple + #else + #define TEMP_BED_PIN 11 // ANALOG NUMBERING - default connector for thermistor *THB* on rumba board is used + #endif +#endif #define SDPOWER -1 #define SDSS 53 From 61a48cc6626e3b49a56f379ffbb7980adc7e710b Mon Sep 17 00:00:00 2001 From: MaikStohn Date: Thu, 16 May 2013 01:16:33 +0200 Subject: [PATCH 12/18] Add support for RUMBA thermocouple add on --- Marlin/temperature.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/Marlin/temperature.cpp b/Marlin/temperature.cpp index 85017750be..665cbe391f 100644 --- a/Marlin/temperature.cpp +++ b/Marlin/temperature.cpp @@ -571,6 +571,12 @@ static void updateTemperaturesFromRawValues() void tp_init() { +#if (MOTHERBOARD == 80) && ((TEMP_SENSOR_0==-1)||(TEMP_SENSOR_1==-1)||(TEMP_SENSOR_2==-1)||(TEMP_SENSOR_BED==-1)) + //disable RUMBA JTAG in case the thermocouple extension is plugged on top of JTAG connector + MCUCR=(1< Date: Thu, 16 May 2013 01:17:08 +0200 Subject: [PATCH 13/18] fixed wrong pin initialization when using temperature 2 pin input --- Marlin/temperature.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/temperature.cpp b/Marlin/temperature.cpp index 665cbe391f..6fced65670 100644 --- a/Marlin/temperature.cpp +++ b/Marlin/temperature.cpp @@ -653,7 +653,7 @@ void tp_init() #if TEMP_2_PIN < 8 DIDR0 |= 1 << TEMP_2_PIN; #else - DIDR2 = 1<<(TEMP_2_PIN - 8); + DIDR2 |= 1<<(TEMP_2_PIN - 8); #endif #endif #if (TEMP_BED_PIN > -1) From 95dff34b734d3b43857ab6b3feaa95a8e5b97fea Mon Sep 17 00:00:00 2001 From: MaikStohn Date: Thu, 16 May 2013 01:17:38 +0200 Subject: [PATCH 14/18] fixed wrong compare for min temp check of heater 1 and heater 2 --- Marlin/temperature.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/temperature.cpp b/Marlin/temperature.cpp index 6fced65670..18cdec65fc 100644 --- a/Marlin/temperature.cpp +++ b/Marlin/temperature.cpp @@ -695,7 +695,7 @@ void tp_init() #if (EXTRUDERS > 1) && defined(HEATER_1_MINTEMP) minttemp[1] = HEATER_1_MINTEMP; - while(analog2temp(minttemp_raw[1], 1) > HEATER_1_MINTEMP) { + while(analog2temp(minttemp_raw[1], 1) < HEATER_1_MINTEMP) { #if HEATER_1_RAW_LO_TEMP < HEATER_1_RAW_HI_TEMP minttemp_raw[1] += OVERSAMPLENR; #else @@ -716,7 +716,7 @@ void tp_init() #if (EXTRUDERS > 2) && defined(HEATER_2_MINTEMP) minttemp[2] = HEATER_2_MINTEMP; - while(analog2temp(minttemp_raw[2], 2) > HEATER_2_MINTEMP) { + while(analog2temp(minttemp_raw[2], 2) < HEATER_2_MINTEMP) { #if HEATER_2_RAW_LO_TEMP < HEATER_2_RAW_HI_TEMP minttemp_raw[2] += OVERSAMPLENR; #else From b668cb051693758a9b1919fbb162ef298bb3d704 Mon Sep 17 00:00:00 2001 From: Gord Christmas Date: Thu, 16 May 2013 06:47:42 -0700 Subject: [PATCH 15/18] Adding in clean copies of Servo library from Arduino 1.0.4 --- Marlin/Servo.cpp | 337 +++++++++++++++++++++++++++++++++++++++++++++++ Marlin/Servo.h | 126 ++++++++++++++++++ 2 files changed, 463 insertions(+) create mode 100644 Marlin/Servo.cpp create mode 100644 Marlin/Servo.h diff --git a/Marlin/Servo.cpp b/Marlin/Servo.cpp new file mode 100644 index 0000000000..02138b5825 --- /dev/null +++ b/Marlin/Servo.cpp @@ -0,0 +1,337 @@ +/* + Servo.cpp - Interrupt driven Servo library for Arduino using 16 bit timers- Version 2 + Copyright (c) 2009 Michael Margolis. All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA + */ + +/* + + A servo is activated by creating an instance of the Servo class passing the desired pin to the attach() method. + The servos are pulsed in the background using the value most recently written using the write() method + + Note that analogWrite of PWM on pins associated with the timer are disabled when the first servo is attached. + Timers are seized as needed in groups of 12 servos - 24 servos use two timers, 48 servos will use four. + + The methods are: + + Servo - Class for manipulating servo motors connected to Arduino pins. + + attach(pin ) - Attaches a servo motor to an i/o pin. + attach(pin, min, max ) - Attaches to a pin setting min and max values in microseconds + default min is 544, max is 2400 + + write() - Sets the servo angle in degrees. (invalid angle that is valid as pulse in microseconds is treated as microseconds) + writeMicroseconds() - Sets the servo pulse width in microseconds + read() - Gets the last written servo pulse width as an angle between 0 and 180. + readMicroseconds() - Gets the last written servo pulse width in microseconds. (was read_us() in first release) + attached() - Returns true if there is a servo attached. + detach() - Stops an attached servos from pulsing its i/o pin. + +*/ + +#include +#include + +#include "Servo.h" + +#define usToTicks(_us) (( clockCyclesPerMicrosecond()* _us) / 8) // converts microseconds to tick (assumes prescale of 8) // 12 Aug 2009 +#define ticksToUs(_ticks) (( (unsigned)_ticks * 8)/ clockCyclesPerMicrosecond() ) // converts from ticks back to microseconds + + +#define TRIM_DURATION 2 // compensation ticks to trim adjust for digitalWrite delays // 12 August 2009 + +//#define NBR_TIMERS (MAX_SERVOS / SERVOS_PER_TIMER) + +static servo_t servos[MAX_SERVOS]; // static array of servo structures +static volatile int8_t Channel[_Nbr_16timers ]; // counter for the servo being pulsed for each timer (or -1 if refresh interval) + +uint8_t ServoCount = 0; // the total number of attached servos + + +// convenience macros +#define SERVO_INDEX_TO_TIMER(_servo_nbr) ((timer16_Sequence_t)(_servo_nbr / SERVOS_PER_TIMER)) // returns the timer controlling this servo +#define SERVO_INDEX_TO_CHANNEL(_servo_nbr) (_servo_nbr % SERVOS_PER_TIMER) // returns the index of the servo on this timer +#define SERVO_INDEX(_timer,_channel) ((_timer*SERVOS_PER_TIMER) + _channel) // macro to access servo index by timer and channel +#define SERVO(_timer,_channel) (servos[SERVO_INDEX(_timer,_channel)]) // macro to access servo class by timer and channel + +#define SERVO_MIN() (MIN_PULSE_WIDTH - this->min * 4) // minimum value in uS for this servo +#define SERVO_MAX() (MAX_PULSE_WIDTH - this->max * 4) // maximum value in uS for this servo + +/************ static functions common to all instances ***********************/ + +static inline void handle_interrupts(timer16_Sequence_t timer, volatile uint16_t *TCNTn, volatile uint16_t* OCRnA) +{ + if( Channel[timer] < 0 ) + *TCNTn = 0; // channel set to -1 indicated that refresh interval completed so reset the timer + else{ + if( SERVO_INDEX(timer,Channel[timer]) < ServoCount && SERVO(timer,Channel[timer]).Pin.isActive == true ) + digitalWrite( SERVO(timer,Channel[timer]).Pin.nbr,LOW); // pulse this channel low if activated + } + + Channel[timer]++; // increment to the next channel + if( SERVO_INDEX(timer,Channel[timer]) < ServoCount && Channel[timer] < SERVOS_PER_TIMER) { + *OCRnA = *TCNTn + SERVO(timer,Channel[timer]).ticks; + if(SERVO(timer,Channel[timer]).Pin.isActive == true) // check if activated + digitalWrite( SERVO(timer,Channel[timer]).Pin.nbr,HIGH); // its an active channel so pulse it high + } + else { + // finished all channels so wait for the refresh period to expire before starting over + if( ((unsigned)*TCNTn) + 4 < usToTicks(REFRESH_INTERVAL) ) // allow a few ticks to ensure the next OCR1A not missed + *OCRnA = (unsigned int)usToTicks(REFRESH_INTERVAL); + else + *OCRnA = *TCNTn + 4; // at least REFRESH_INTERVAL has elapsed + Channel[timer] = -1; // this will get incremented at the end of the refresh period to start again at the first channel + } +} + +#ifndef WIRING // Wiring pre-defines signal handlers so don't define any if compiling for the Wiring platform +// Interrupt handlers for Arduino +#if defined(_useTimer1) +SIGNAL (TIMER1_COMPA_vect) +{ + handle_interrupts(_timer1, &TCNT1, &OCR1A); +} +#endif + +#if defined(_useTimer3) +SIGNAL (TIMER3_COMPA_vect) +{ + handle_interrupts(_timer3, &TCNT3, &OCR3A); +} +#endif + +#if defined(_useTimer4) +SIGNAL (TIMER4_COMPA_vect) +{ + handle_interrupts(_timer4, &TCNT4, &OCR4A); +} +#endif + +#if defined(_useTimer5) +SIGNAL (TIMER5_COMPA_vect) +{ + handle_interrupts(_timer5, &TCNT5, &OCR5A); +} +#endif + +#elif defined WIRING +// Interrupt handlers for Wiring +#if defined(_useTimer1) +void Timer1Service() +{ + handle_interrupts(_timer1, &TCNT1, &OCR1A); +} +#endif +#if defined(_useTimer3) +void Timer3Service() +{ + handle_interrupts(_timer3, &TCNT3, &OCR3A); +} +#endif +#endif + + +static void initISR(timer16_Sequence_t timer) +{ +#if defined (_useTimer1) + if(timer == _timer1) { + TCCR1A = 0; // normal counting mode + TCCR1B = _BV(CS11); // set prescaler of 8 + TCNT1 = 0; // clear the timer count +#if defined(__AVR_ATmega8__)|| defined(__AVR_ATmega128__) + TIFR |= _BV(OCF1A); // clear any pending interrupts; + TIMSK |= _BV(OCIE1A) ; // enable the output compare interrupt +#else + // here if not ATmega8 or ATmega128 + TIFR1 |= _BV(OCF1A); // clear any pending interrupts; + TIMSK1 |= _BV(OCIE1A) ; // enable the output compare interrupt +#endif +#if defined(WIRING) + timerAttach(TIMER1OUTCOMPAREA_INT, Timer1Service); +#endif + } +#endif + +#if defined (_useTimer3) + if(timer == _timer3) { + TCCR3A = 0; // normal counting mode + TCCR3B = _BV(CS31); // set prescaler of 8 + TCNT3 = 0; // clear the timer count +#if defined(__AVR_ATmega128__) + TIFR |= _BV(OCF3A); // clear any pending interrupts; + ETIMSK |= _BV(OCIE3A); // enable the output compare interrupt +#else + TIFR3 = _BV(OCF3A); // clear any pending interrupts; + TIMSK3 = _BV(OCIE3A) ; // enable the output compare interrupt +#endif +#if defined(WIRING) + timerAttach(TIMER3OUTCOMPAREA_INT, Timer3Service); // for Wiring platform only +#endif + } +#endif + +#if defined (_useTimer4) + if(timer == _timer4) { + TCCR4A = 0; // normal counting mode + TCCR4B = _BV(CS41); // set prescaler of 8 + TCNT4 = 0; // clear the timer count + TIFR4 = _BV(OCF4A); // clear any pending interrupts; + TIMSK4 = _BV(OCIE4A) ; // enable the output compare interrupt + } +#endif + +#if defined (_useTimer5) + if(timer == _timer5) { + TCCR5A = 0; // normal counting mode + TCCR5B = _BV(CS51); // set prescaler of 8 + TCNT5 = 0; // clear the timer count + TIFR5 = _BV(OCF5A); // clear any pending interrupts; + TIMSK5 = _BV(OCIE5A) ; // enable the output compare interrupt + } +#endif +} + +static void finISR(timer16_Sequence_t timer) +{ + //disable use of the given timer +#if defined WIRING // Wiring + if(timer == _timer1) { + #if defined(__AVR_ATmega1281__)||defined(__AVR_ATmega2561__) + TIMSK1 &= ~_BV(OCIE1A) ; // disable timer 1 output compare interrupt + #else + TIMSK &= ~_BV(OCIE1A) ; // disable timer 1 output compare interrupt + #endif + timerDetach(TIMER1OUTCOMPAREA_INT); + } + else if(timer == _timer3) { + #if defined(__AVR_ATmega1281__)||defined(__AVR_ATmega2561__) + TIMSK3 &= ~_BV(OCIE3A); // disable the timer3 output compare A interrupt + #else + ETIMSK &= ~_BV(OCIE3A); // disable the timer3 output compare A interrupt + #endif + timerDetach(TIMER3OUTCOMPAREA_INT); + } +#else + //For arduino - in future: call here to a currently undefined function to reset the timer +#endif +} + +static boolean isTimerActive(timer16_Sequence_t timer) +{ + // returns true if any servo is active on this timer + for(uint8_t channel=0; channel < SERVOS_PER_TIMER; channel++) { + if(SERVO(timer,channel).Pin.isActive == true) + return true; + } + return false; +} + + +/****************** end of static functions ******************************/ + +Servo::Servo() +{ + if( ServoCount < MAX_SERVOS) { + this->servoIndex = ServoCount++; // assign a servo index to this instance + servos[this->servoIndex].ticks = usToTicks(DEFAULT_PULSE_WIDTH); // store default values - 12 Aug 2009 + } + else + this->servoIndex = INVALID_SERVO ; // too many servos +} + +uint8_t Servo::attach(int pin) +{ + return this->attach(pin, MIN_PULSE_WIDTH, MAX_PULSE_WIDTH); +} + +uint8_t Servo::attach(int pin, int min, int max) +{ + if(this->servoIndex < MAX_SERVOS ) { + pinMode( pin, OUTPUT) ; // set servo pin to output + servos[this->servoIndex].Pin.nbr = pin; + // todo min/max check: abs(min - MIN_PULSE_WIDTH) /4 < 128 + this->min = (MIN_PULSE_WIDTH - min)/4; //resolution of min/max is 4 uS + this->max = (MAX_PULSE_WIDTH - max)/4; + // initialize the timer if it has not already been initialized + timer16_Sequence_t timer = SERVO_INDEX_TO_TIMER(servoIndex); + if(isTimerActive(timer) == false) + initISR(timer); + servos[this->servoIndex].Pin.isActive = true; // this must be set after the check for isTimerActive + } + return this->servoIndex ; +} + +void Servo::detach() +{ + servos[this->servoIndex].Pin.isActive = false; + timer16_Sequence_t timer = SERVO_INDEX_TO_TIMER(servoIndex); + if(isTimerActive(timer) == false) { + finISR(timer); + } +} + +void Servo::write(int value) +{ + if(value < MIN_PULSE_WIDTH) + { // treat values less than 544 as angles in degrees (valid values in microseconds are handled as microseconds) + if(value < 0) value = 0; + if(value > 180) value = 180; + value = map(value, 0, 180, SERVO_MIN(), SERVO_MAX()); + } + this->writeMicroseconds(value); +} + +void Servo::writeMicroseconds(int value) +{ + // calculate and store the values for the given channel + byte channel = this->servoIndex; + if( (channel < MAX_SERVOS) ) // ensure channel is valid + { + if( value < SERVO_MIN() ) // ensure pulse width is valid + value = SERVO_MIN(); + else if( value > SERVO_MAX() ) + value = SERVO_MAX(); + + value = value - TRIM_DURATION; + value = usToTicks(value); // convert to ticks after compensating for interrupt overhead - 12 Aug 2009 + + uint8_t oldSREG = SREG; + cli(); + servos[channel].ticks = value; + SREG = oldSREG; + } +} + +int Servo::read() // return the value as degrees +{ + return map( this->readMicroseconds()+1, SERVO_MIN(), SERVO_MAX(), 0, 180); +} + +int Servo::readMicroseconds() +{ + unsigned int pulsewidth; + if( this->servoIndex != INVALID_SERVO ) + pulsewidth = ticksToUs(servos[this->servoIndex].ticks) + TRIM_DURATION ; // 12 aug 2009 + else + pulsewidth = 0; + + return pulsewidth; +} + +bool Servo::attached() +{ + return servos[this->servoIndex].Pin.isActive ; +} diff --git a/Marlin/Servo.h b/Marlin/Servo.h new file mode 100644 index 0000000000..a76954a06f --- /dev/null +++ b/Marlin/Servo.h @@ -0,0 +1,126 @@ +/* + Servo.h - Interrupt driven Servo library for Arduino using 16 bit timers- Version 2 + Copyright (c) 2009 Michael Margolis. All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +/* + + A servo is activated by creating an instance of the Servo class passing the desired pin to the attach() method. + The servos are pulsed in the background using the value most recently written using the write() method + + Note that analogWrite of PWM on pins associated with the timer are disabled when the first servo is attached. + Timers are seized as needed in groups of 12 servos - 24 servos use two timers, 48 servos will use four. + The sequence used to sieze timers is defined in timers.h + + The methods are: + + Servo - Class for manipulating servo motors connected to Arduino pins. + + attach(pin ) - Attaches a servo motor to an i/o pin. + attach(pin, min, max ) - Attaches to a pin setting min and max values in microseconds + default min is 544, max is 2400 + + write() - Sets the servo angle in degrees. (invalid angle that is valid as pulse in microseconds is treated as microseconds) + writeMicroseconds() - Sets the servo pulse width in microseconds + read() - Gets the last written servo pulse width as an angle between 0 and 180. + readMicroseconds() - Gets the last written servo pulse width in microseconds. (was read_us() in first release) + attached() - Returns true if there is a servo attached. + detach() - Stops an attached servos from pulsing its i/o pin. + */ + +#ifndef Servo_h +#define Servo_h + +#include + +/* + * Defines for 16 bit timers used with Servo library + * + * If _useTimerX is defined then TimerX is a 16 bit timer on the curent board + * timer16_Sequence_t enumerates the sequence that the timers should be allocated + * _Nbr_16timers indicates how many 16 bit timers are available. + * + */ + +// Say which 16 bit timers can be used and in what order +#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) +#define _useTimer5 +#define _useTimer1 +#define _useTimer3 +#define _useTimer4 +typedef enum { _timer5, _timer1, _timer3, _timer4, _Nbr_16timers } timer16_Sequence_t ; + +#elif defined(__AVR_ATmega32U4__) +#define _useTimer1 +typedef enum { _timer1, _Nbr_16timers } timer16_Sequence_t ; + +#elif defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB1286__) +#define _useTimer3 +#define _useTimer1 +typedef enum { _timer3, _timer1, _Nbr_16timers } timer16_Sequence_t ; + +#elif defined(__AVR_ATmega128__) ||defined(__AVR_ATmega1281__)||defined(__AVR_ATmega2561__) +#define _useTimer3 +#define _useTimer1 +typedef enum { _timer3, _timer1, _Nbr_16timers } timer16_Sequence_t ; + +#else // everything else +#define _useTimer1 +typedef enum { _timer1, _Nbr_16timers } timer16_Sequence_t ; +#endif + +#define Servo_VERSION 2 // software version of this library + +#define MIN_PULSE_WIDTH 544 // the shortest pulse sent to a servo +#define MAX_PULSE_WIDTH 2400 // the longest pulse sent to a servo +#define DEFAULT_PULSE_WIDTH 1500 // default pulse width when servo is attached +#define REFRESH_INTERVAL 20000 // minumim time to refresh servos in microseconds + +#define SERVOS_PER_TIMER 12 // the maximum number of servos controlled by one timer +#define MAX_SERVOS (_Nbr_16timers * SERVOS_PER_TIMER) + +#define INVALID_SERVO 255 // flag indicating an invalid servo index + +typedef struct { + uint8_t nbr :6 ; // a pin number from 0 to 63 + uint8_t isActive :1 ; // true if this channel is enabled, pin not pulsed if false +} ServoPin_t ; + +typedef struct { + ServoPin_t Pin; + unsigned int ticks; +} servo_t; + +class Servo +{ +public: + Servo(); + uint8_t attach(int pin); // attach the given pin to the next free channel, sets pinMode, returns channel number or 0 if failure + uint8_t attach(int pin, int min, int max); // as above but also sets min and max values for writes. + void detach(); + void write(int value); // if value is < 200 its treated as an angle, otherwise as pulse width in microseconds + void writeMicroseconds(int value); // Write pulse width in microseconds + int read(); // returns current pulse width as an angle between 0 and 180 degrees + int readMicroseconds(); // returns current pulse width in microseconds for this servo (was read_us() in first release) + bool attached(); // return true if this servo is attached, otherwise false +private: + uint8_t servoIndex; // index into the channel data for this servo + int8_t min; // minimum is this value times 4 added to MIN_PULSE_WIDTH + int8_t max; // maximum is this value times 4 added to MAX_PULSE_WIDTH +}; + +#endif From dc59f07d240119f3031dc905b21232f581f3e11b Mon Sep 17 00:00:00 2001 From: Gord Christmas Date: Thu, 16 May 2013 07:03:01 -0700 Subject: [PATCH 16/18] First attempt at refactoring of original servo code. Only adding servo support as a start to keep things simple. --- Marlin/Configuration.h | 61 ++++-- Marlin/Marlin_main.cpp | 446 +++++++++++++++++++++++------------------ Marlin/Servo.h | 26 ++- Marlin/pins.h | 171 ++++++++-------- 4 files changed, 396 insertions(+), 308 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 3405dfbffe..e22c83cae0 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -2,7 +2,7 @@ #define CONFIGURATION_H // This configurtion file contains the basic settings. -// Advanced settings can be found in Configuration_adv.h +// Advanced settings can be found in Configuration_adv.h // BASIC SETTINGS: select your board type, temperature sensor type, axis scaling, and endstop configuration //User specified version info of this build to display in [Pronterface, etc] terminal window during startup. @@ -78,7 +78,7 @@ // 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup) // 10 is 100k RS thermistor 198-961 (4.7k pullup) // -// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k +// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k // (but gives greater accuracy and more stable PID) // 51 is 100k thermistor - EPCOS (1k pullup) // 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup) @@ -95,7 +95,7 @@ #define TEMP_WINDOW 1 // (degC) Window around target to start the recidency timer x degC early. // The minimal temperature defines the temperature below which the heater will not be enabled It is used -// to check that the wiring to the thermistor is not broken. +// to check that the wiring to the thermistor is not broken. // Otherwise this would lead to the heater being powered on all the time. #define HEATER_0_MINTEMP 5 #define HEATER_1_MINTEMP 5 @@ -121,7 +121,7 @@ #define BANG_MAX 256 // limits current to nozzle while in bang-bang mode; 256=full current #define PID_MAX 256 // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 256=full current #ifdef PIDTEMP - //#define PID_DEBUG // Sends debug data to the serial port. + //#define PID_DEBUG // Sends debug data to the serial port. //#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX #define PID_FUNCTIONAL_RANGE 10 // If the temperature difference between the target temperature and the actual temperature // is more then PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max. @@ -132,15 +132,15 @@ // If you are using a preconfigured hotend then you can use one of the value sets by uncommenting it // Ultimaker #define DEFAULT_Kp 22.2 - #define DEFAULT_Ki 1.08 - #define DEFAULT_Kd 114 + #define DEFAULT_Ki 1.08 + #define DEFAULT_Kd 114 // Makergear // #define DEFAULT_Kp 7.0 -// #define DEFAULT_Ki 0.1 -// #define DEFAULT_Kd 12 +// #define DEFAULT_Ki 0.1 +// #define DEFAULT_Kd 12 -// Mendel Parts V9 on 12V +// Mendel Parts V9 on 12V // #define DEFAULT_Kp 63.0 // #define DEFAULT_Ki 2.25 // #define DEFAULT_Kd 440 @@ -149,11 +149,11 @@ // Bed Temperature Control // Select PID or bang-bang with PIDTEMPBED. If bang-bang, BED_LIMIT_SWITCHING will enable hysteresis // -// uncomment this to enable PID on the bed. It uses the same ferquency PWM as the extruder. +// uncomment this to enable PID on the bed. It uses the same ferquency PWM as the extruder. // If your PID_dT above is the default, and correct for your hardware/configuration, that means 7.689Hz, // which is fine for driving a square wave into a resistive load and does not significantly impact you FET heating. -// This also works fine on a Fotek SSR-10DA Solid State Relay into a 250W heater. -// If your configuration is significantly different than this and you don't understand the issues involved, you proabaly +// This also works fine on a Fotek SSR-10DA Solid State Relay into a 250W heater. +// If your configuration is significantly different than this and you don't understand the issues involved, you proabaly // shouldn't use bed PID until someone else verifies your hardware works. // If this is enabled, find your own PID constants below. //#define PIDTEMPBED @@ -223,9 +223,9 @@ #endif // The pullups are needed if you directly connect a mechanical endswitch between the signal and ground pins. -const bool X_ENDSTOPS_INVERTING = true; // set to true to invert the logic of the endstops. -const bool Y_ENDSTOPS_INVERTING = true; // set to true to invert the logic of the endstops. -const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of the endstops. +const bool X_ENDSTOPS_INVERTING = true; // set to true to invert the logic of the endstops. +const bool Y_ENDSTOPS_INVERTING = true; // set to true to invert the logic of the endstops. +const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of the endstops. //#define DISABLE_MAX_ENDSTOPS // For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1 @@ -280,13 +280,13 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th #define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E #define HOMING_FEEDRATE {50*60, 50*60, 4*60, 0} // set the homing speeds (mm/min) -// default settings +// default settings #define DEFAULT_AXIS_STEPS_PER_UNIT {78.7402,78.7402,200.0*8/3,760*1.1} // default steps per unit for ultimaker #define DEFAULT_MAX_FEEDRATE {500, 500, 5, 25} // (mm/sec) #define DEFAULT_MAX_ACCELERATION {9000,9000,100,10000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for skeinforge 40+, for older versions raise them a lot. -#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E max acceleration in mm/s^2 for printing moves +#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E max acceleration in mm/s^2 for printing moves #define DEFAULT_RETRACT_ACCELERATION 3000 // X, Y, Z and E max acceleration in mm/s^2 for r retracts // Offset of the extruders (uncomment if using more than one and relying on firmware to position when changing). @@ -307,7 +307,7 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th // EEPROM // the microcontroller can store settings in the EEPROM, e.g. max velocity... // M500 - stores paramters in EEPROM -// M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily). +// M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily). // M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to. //define this to enable eeprom support //#define EEPROM_SETTINGS @@ -353,7 +353,7 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th #if defined(ULTIMAKERCONTROLLER) || defined(REPRAP_DISCOUNT_SMART_CONTROLLER) || defined(G3D_PANEL) #define ULTIPANEL #define NEWPANEL -#endif +#endif #if defined(REPRAPWORLD_KEYPAD) #define NEWPANEL @@ -361,7 +361,7 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th #endif // Preheat Constants -#define PLA_PREHEAT_HOTEND_TEMP 180 +#define PLA_PREHEAT_HOTEND_TEMP 180 #define PLA_PREHEAT_HPB_TEMP 70 #define PLA_PREHEAT_FAN_SPEED 255 // Insert Value between 0 and 255 @@ -381,7 +381,7 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th #define LCD_WIDTH 20 #define LCD_HEIGHT 4 #endif -#else //no panel but just lcd +#else //no panel but just lcd #ifdef ULTRA_LCD #ifdef DOGLCD // Change number of lines to match the 128x64 graphics display #define LCD_WIDTH 20 @@ -389,7 +389,7 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th #else #define LCD_WIDTH 16 #define LCD_HEIGHT 2 - #endif + #endif #endif #endif @@ -406,6 +406,23 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th // Support for the BariCUDA Paste Extruder. //#define BARICUDA +/*********************************************************************\ +* +* R/C SERVO support +* +* Sponsored by TrinityLabs, Reworked by codexmas +* +**********************************************************************/ + +// Number of servos +// +// If you select a configuration below, this will receive a default value and does not need to be set manually +// set it manually if you have more servos than extruders and wish to manually control some +// leaving it undefined or defining as 0 will disable the servo subsystem +// If unsure, leave commented / disabled +// +// #define NUM_SERVOS 3 + #include "Configuration_adv.h" #include "thermistortables.h" diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 0a528ea058..0ff34605c3 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -3,17 +3,17 @@ /* Reprap firmware based on Sprinter and grbl. Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm - + This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version. - + This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details. - + You should have received a copy of the GNU General Public License along with this program. If not, see . */ @@ -22,8 +22,8 @@ This firmware is a mashup between Sprinter and grbl. (https://github.com/kliment/Sprinter) (https://github.com/simen/grbl/tree) - - It has preliminary support for Matthew Roberts advance algorithm + + It has preliminary support for Matthew Roberts advance algorithm http://reprap.org/pipermail/reprap-dev/2011-May/003323.html */ @@ -40,6 +40,10 @@ #include "language.h" #include "pins_arduino.h" +#if (defined NUM_SERVOS) && (NUM_SERVOS > 0) +#include "Servo.h" +#endif + #if DIGIPOTSS_PIN > -1 #include #endif @@ -93,11 +97,11 @@ // M81 - Turn off Power Supply // M82 - Set E codes absolute (default) // M83 - Set E codes relative while in Absolute Coordinates (G90) mode -// M84 - Disable steppers until next move, +// M84 - Disable steppers until next move, // or use S to specify an inactivity timeout, after which the steppers will be disabled. S0 to disable the timeout. // M85 - Set inactivity shutdown timer with parameter S. To disable set zero (default) // M92 - Set axis_steps_per_unit - same syntax as G92 -// M114 - Output current position to serial port +// M114 - Output current position to serial port // M115 - Capabilities string // M117 - display message // M119 - Output Endstop status to serial port @@ -121,6 +125,7 @@ // M220 S- set speed factor override percentage // M221 S- set extrude factor override percentage // M240 - Trigger a camera to take a photograph +// M280 - set servo position absolute. P: servo index, S: angle or microseconds // M300 - Play beepsound S P // M301 - Set PID parameters P I and D // M302 - Allow cold extrudes @@ -128,7 +133,7 @@ // M304 - Set bed PID parameters P I and D // M400 - Finish all moves // M500 - stores paramters in EEPROM -// M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily). +// M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily). // M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to. // M503 - print the current settings (from memory not from eeprom) // M540 - Use S[0|1] to enable or disable the stop SD card print on endstop hit (requires ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED) @@ -164,11 +169,11 @@ float min_pos[3] = { X_MIN_POS, Y_MIN_POS, Z_MIN_POS }; float max_pos[3] = { X_MAX_POS, Y_MAX_POS, Z_MAX_POS }; // Extruder offset, only in XY plane #if EXTRUDERS > 1 -float extruder_offset[2][EXTRUDERS] = { +float extruder_offset[2][EXTRUDERS] = { #if defined(EXTRUDER_OFFSET_X) && defined(EXTRUDER_OFFSET_Y) - EXTRUDER_OFFSET_X, EXTRUDER_OFFSET_Y + EXTRUDER_OFFSET_X, EXTRUDER_OFFSET_Y #endif -}; +}; #endif uint8_t active_extruder = 0; int fanSpeed=0; @@ -225,6 +230,10 @@ static uint8_t tmp_extruder; bool Stopped=false; +#if (defined NUM_SERVOS) && (NUM_SERVOS > 0) + Servo servos[NUM_SERVOS]; +#endif + //=========================================================================== //=============================ROUTINES============================= //=========================================================================== @@ -296,7 +305,7 @@ void setup_killpin() WRITE(KILL_PIN,HIGH); #endif } - + void setup_photpin() { #ifdef PHOTOGRAPH_PIN @@ -304,7 +313,7 @@ void setup_photpin() SET_OUTPUT(PHOTOGRAPH_PIN); WRITE(PHOTOGRAPH_PIN, LOW); #endif - #endif + #endif } void setup_powerhold() @@ -324,16 +333,35 @@ void setup_powerhold() void suicide() { #ifdef SUICIDE_PIN - #if (SUICIDE_PIN> -1) + #if (SUICIDE_PIN> -1) SET_OUTPUT(SUICIDE_PIN); WRITE(SUICIDE_PIN, LOW); #endif #endif } +void servo_init() +{ + #if (NUM_SERVOS >= 1) && defined (SERVO0_PIN) && (SERVO0_PIN > -1) + servos[0].attach(SERVO0_PIN); + #endif + #if (NUM_SERVOS >= 2) && defined (SERVO1_PIN) && (SERVO1_PIN > -1) + servos[1].attach(SERVO1_PIN); + #endif + #if (NUM_SERVOS >= 3) && defined (SERVO2_PIN) && (SERVO2_PIN > -1) + servos[2].attach(SERVO2_PIN); + #endif + #if (NUM_SERVOS >= 4) && defined (SERVO3_PIN) && (SERVO3_PIN > -1) + servos[3].attach(SERVO3_PIN); + #endif + #if (NUM_SERVOS >= 5) + #error "TODO: enter initalisation code for more servos" + #endif +} + void setup() { - setup_killpin(); + setup_killpin(); setup_powerhold(); MYSERIAL.begin(BAUDRATE); SERIAL_PROTOCOLLNPGM("start"); @@ -370,22 +398,23 @@ void setup() { fromsd[i] = false; } - - // loads data from EEPROM if available else uses defaults (and resets step acceleration rate) - Config_RetrieveSettings(); - tp_init(); // Initialize temperature loop + // loads data from EEPROM if available else uses defaults (and resets step acceleration rate) + Config_RetrieveSettings(); + + tp_init(); // Initialize temperature loop plan_init(); // Initialize planner; watchdog_init(); st_init(); // Initialize stepper, this enables interrupts! setup_photpin(); - + servo_init(); + lcd_init(); - + #ifdef CONTROLLERFAN_PIN SET_OUTPUT(CONTROLLERFAN_PIN); //Set pin used for driver cooling fan #endif - + #ifdef EXTRUDERFAN_PIN SET_OUTPUT(EXTRUDERFAN_PIN); //Set pin used for extruder cooling fan #endif @@ -439,14 +468,14 @@ void loop() lcd_update(); } -void get_command() -{ +void get_command() +{ while( MYSERIAL.available() > 0 && buflen < BUFSIZE) { serial_char = MYSERIAL.read(); - if(serial_char == '\n' || - serial_char == '\r' || - (serial_char == ':' && comment_mode == false) || - serial_count >= (MAX_CMD_SIZE - 1) ) + if(serial_char == '\n' || + serial_char == '\r' || + (serial_char == ':' && comment_mode == false) || + serial_count >= (MAX_CMD_SIZE - 1) ) { if(!serial_count) { //if empty line comment_mode = false; //for new command @@ -487,7 +516,7 @@ void get_command() } //if no errors, continue parsing } - else + else { SERIAL_ERROR_START; SERIAL_ERRORPGM(MSG_ERR_NO_CHECKSUM); @@ -523,7 +552,7 @@ void get_command() if(card.saving) break; #endif //SDSUPPORT - SERIAL_PROTOCOLLNPGM(MSG_OK); + SERIAL_PROTOCOLLNPGM(MSG_OK); } else { SERIAL_ERRORLNPGM(MSG_ERR_STOPPED); @@ -553,10 +582,10 @@ void get_command() while( !card.eof() && buflen < BUFSIZE) { int16_t n=card.get(); serial_char = (char)n; - if(serial_char == '\n' || - serial_char == '\r' || - (serial_char == ':' && comment_mode == false) || - serial_count >= (MAX_CMD_SIZE - 1)||n==-1) + if(serial_char == '\n' || + serial_char == '\r' || + (serial_char == ':' && comment_mode == false) || + serial_count >= (MAX_CMD_SIZE - 1)||n==-1) { if(card.eof()){ SERIAL_PROTOCOLLNPGM(MSG_FILE_PRINTED); @@ -572,7 +601,7 @@ void get_command() lcd_setstatus(time); card.printingHasFinished(); card.checkautostart(true); - + } if(!serial_count) { @@ -584,7 +613,7 @@ void get_command() fromsd[bufindw] = true; buflen += 1; bufindw = (bufindw + 1)%BUFSIZE; -// } +// } comment_mode = false; //for new command serial_count = 0; //clear buffer } @@ -594,20 +623,20 @@ void get_command() if(!comment_mode) cmdbuffer[bufindw][serial_count++] = serial_char; } } - + #endif //SDSUPPORT } -float code_value() -{ - return (strtod(&cmdbuffer[bufindr][strchr_pointer - cmdbuffer[bufindr] + 1], NULL)); +float code_value() +{ + return (strtod(&cmdbuffer[bufindr][strchr_pointer - cmdbuffer[bufindr] + 1], NULL)); } -long code_value_long() -{ - return (strtol(&cmdbuffer[bufindr][strchr_pointer - cmdbuffer[bufindr] + 1], NULL, 10)); +long code_value_long() +{ + return (strtol(&cmdbuffer[bufindr][strchr_pointer - cmdbuffer[bufindr] + 1], NULL, 10)); } bool code_seen(char code) @@ -656,19 +685,19 @@ static void homeaxis(int axis) { feedrate = homing_feedrate[axis]; plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder); st_synchronize(); - + current_position[axis] = 0; plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]); destination[axis] = -home_retract_mm(axis) * home_dir(axis); plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder); st_synchronize(); - + destination[axis] = 2*home_retract_mm(axis) * home_dir(axis); - feedrate = homing_feedrate[axis]/2 ; + feedrate = homing_feedrate[axis]/2 ; plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder); st_synchronize(); - - axis_is_at_home(axis); + + axis_is_at_home(axis); destination[axis] = current_position[axis]; feedrate = 0.0; endstops_hit_on_purpose(); @@ -711,7 +740,7 @@ void process_commands() codenum = 0; if(code_seen('P')) codenum = code_value(); // milliseconds to wait if(code_seen('S')) codenum = code_value() * 1000; // seconds to wait - + st_synchronize(); codenum += millis(); // keep track of when we started waiting previous_millis_cmd = millis(); @@ -721,30 +750,30 @@ void process_commands() lcd_update(); } break; - #ifdef FWRETRACT + #ifdef FWRETRACT case 10: // G10 retract - if(!retracted) + if(!retracted) { destination[X_AXIS]=current_position[X_AXIS]; destination[Y_AXIS]=current_position[Y_AXIS]; - destination[Z_AXIS]=current_position[Z_AXIS]; + destination[Z_AXIS]=current_position[Z_AXIS]; current_position[Z_AXIS]+=-retract_zlift; - destination[E_AXIS]=current_position[E_AXIS]-retract_length; + destination[E_AXIS]=current_position[E_AXIS]-retract_length; feedrate=retract_feedrate; retracted=true; prepare_move(); } - + break; case 11: // G10 retract_recover - if(!retracted) + if(!retracted) { destination[X_AXIS]=current_position[X_AXIS]; destination[Y_AXIS]=current_position[Y_AXIS]; - destination[Z_AXIS]=current_position[Z_AXIS]; - + destination[Z_AXIS]=current_position[Z_AXIS]; + current_position[Z_AXIS]+=retract_zlift; - current_position[E_AXIS]+=-retract_recover_length; + current_position[E_AXIS]+=-retract_recover_length; feedrate=retract_recover_feedrate; retracted=false; prepare_move(); @@ -756,34 +785,34 @@ void process_commands() saved_feedmultiply = feedmultiply; feedmultiply = 100; previous_millis_cmd = millis(); - + enable_endstops(true); - + for(int8_t i=0; i < NUM_AXIS; i++) { destination[i] = current_position[i]; } feedrate = 0.0; home_all_axis = !((code_seen(axis_codes[0])) || (code_seen(axis_codes[1])) || (code_seen(axis_codes[2]))); - + #if Z_HOME_DIR > 0 // If homing away from BED do Z first if((home_all_axis) || (code_seen(axis_codes[Z_AXIS]))) { HOMEAXIS(Z); } #endif - + #ifdef QUICK_HOME if((home_all_axis)||( code_seen(axis_codes[X_AXIS]) && code_seen(axis_codes[Y_AXIS])) ) //first diagonal move { - current_position[X_AXIS] = 0;current_position[Y_AXIS] = 0; + current_position[X_AXIS] = 0;current_position[Y_AXIS] = 0; - plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]); - destination[X_AXIS] = 1.5 * X_MAX_LENGTH * X_HOME_DIR;destination[Y_AXIS] = 1.5 * Y_MAX_LENGTH * Y_HOME_DIR; - feedrate = homing_feedrate[X_AXIS]; + plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]); + destination[X_AXIS] = 1.5 * X_MAX_LENGTH * X_HOME_DIR;destination[Y_AXIS] = 1.5 * Y_MAX_LENGTH * Y_HOME_DIR; + feedrate = homing_feedrate[X_AXIS]; if(homing_feedrate[Y_AXIS] 0){ @@ -900,12 +929,12 @@ void process_commands() #endif case 17: LCD_MESSAGEPGM(MSG_NO_MOVE); - enable_x(); - enable_y(); - enable_z(); - enable_e0(); - enable_e1(); - enable_e2(); + enable_x(); + enable_y(); + enable_z(); + enable_e0(); + enable_e1(); + enable_e2(); break; #ifdef SDSUPPORT @@ -915,9 +944,9 @@ void process_commands() SERIAL_PROTOCOLLNPGM(MSG_END_FILE_LIST); break; case 21: // M21 - init SD card - + card.initsd(); - + break; case 22: //M22 - release SD card card.release(); @@ -957,7 +986,7 @@ void process_commands() //processed in write to file routine above //card,saving = false; break; - case 30: //M30 Delete File + case 30: //M30 Delete File if (card.cardOK){ card.closefile(); starpos = (strchr(strchr_pointer + 4,'*')); @@ -978,7 +1007,7 @@ void process_commands() } card.openLogFile(strchr_pointer+5); break; - + #endif //SDSUPPORT case 31: //M31 take time since the start of the SD print or an M109 command @@ -1035,11 +1064,11 @@ void process_commands() } #if (TEMP_0_PIN > -1) SERIAL_PROTOCOLPGM("ok T:"); - SERIAL_PROTOCOL_F(degHotend(tmp_extruder),1); + SERIAL_PROTOCOL_F(degHotend(tmp_extruder),1); SERIAL_PROTOCOLPGM(" /"); - SERIAL_PROTOCOL_F(degTargetHotend(tmp_extruder),1); + SERIAL_PROTOCOL_F(degTargetHotend(tmp_extruder),1); #if TEMP_BED_PIN > -1 - SERIAL_PROTOCOLPGM(" B:"); + SERIAL_PROTOCOLPGM(" B:"); SERIAL_PROTOCOL_F(degBed(),1); SERIAL_PROTOCOLPGM(" /"); SERIAL_PROTOCOL_F(degTargetBed(),1); @@ -1050,20 +1079,20 @@ void process_commands() #endif SERIAL_PROTOCOLPGM(" @:"); - SERIAL_PROTOCOL(getHeaterPower(tmp_extruder)); + SERIAL_PROTOCOL(getHeaterPower(tmp_extruder)); SERIAL_PROTOCOLPGM(" B@:"); - SERIAL_PROTOCOL(getHeaterPower(-1)); + SERIAL_PROTOCOL(getHeaterPower(-1)); SERIAL_PROTOCOLLN(""); return; break; - case 109: + case 109: {// M109 - Wait for extruder heater to reach target. if(setTargetedHotend(109)){ break; } - LCD_MESSAGEPGM(MSG_HEATING); + LCD_MESSAGEPGM(MSG_HEATING); #ifdef AUTOTEMP autotemp_enabled=false; #endif @@ -1071,15 +1100,15 @@ void process_commands() #ifdef AUTOTEMP if (code_seen('S')) autotemp_min=code_value(); if (code_seen('B')) autotemp_max=code_value(); - if (code_seen('F')) + if (code_seen('F')) { autotemp_factor=code_value(); autotemp_enabled=true; } #endif - + setWatch(); - codenum = millis(); + codenum = millis(); /* See if we are heating up or cooling down */ bool target_direction = isHeatingHotend(tmp_extruder); // true if heating, false if cooling @@ -1087,7 +1116,7 @@ void process_commands() #ifdef TEMP_RESIDENCY_TIME long residencyStart; residencyStart = -1; - /* continue to loop until we have reached the target temp + /* continue to loop until we have reached the target temp _and_ until TEMP_RESIDENCY_TIME hasn't passed since we reached it */ while((residencyStart == -1) || (residencyStart >= 0 && (((unsigned int) (millis() - residencyStart)) < (TEMP_RESIDENCY_TIME * 1000UL))) ) { @@ -1097,9 +1126,9 @@ void process_commands() if( (millis() - codenum) > 1000UL ) { //Print Temp Reading and remaining time every 1 second while heating up/cooling down SERIAL_PROTOCOLPGM("T:"); - SERIAL_PROTOCOL_F(degHotend(tmp_extruder),1); + SERIAL_PROTOCOL_F(degHotend(tmp_extruder),1); SERIAL_PROTOCOLPGM(" E:"); - SERIAL_PROTOCOL((int)tmp_extruder); + SERIAL_PROTOCOL((int)tmp_extruder); #ifdef TEMP_RESIDENCY_TIME SERIAL_PROTOCOLPGM(" W:"); if(residencyStart > -1) @@ -1107,7 +1136,7 @@ void process_commands() codenum = ((TEMP_RESIDENCY_TIME * 1000UL) - (millis() - residencyStart)) / 1000UL; SERIAL_PROTOCOLLN( codenum ); } - else + else { SERIAL_PROTOCOLLN( "?" ); } @@ -1124,7 +1153,7 @@ void process_commands() or when current temp falls outside the hysteresis after target temp was reached */ if ((residencyStart == -1 && target_direction && (degHotend(tmp_extruder) >= (degTargetHotend(tmp_extruder)-TEMP_WINDOW))) || (residencyStart == -1 && !target_direction && (degHotend(tmp_extruder) <= (degTargetHotend(tmp_extruder)+TEMP_WINDOW))) || - (residencyStart > -1 && labs(degHotend(tmp_extruder) - degTargetHotend(tmp_extruder)) > TEMP_HYSTERESIS) ) + (residencyStart > -1 && labs(degHotend(tmp_extruder) - degTargetHotend(tmp_extruder)) > TEMP_HYSTERESIS) ) { residencyStart = millis(); } @@ -1139,8 +1168,8 @@ void process_commands() #if TEMP_BED_PIN > -1 LCD_MESSAGEPGM(MSG_BED_HEATING); if (code_seen('S')) setTargetBed(code_value()); - codenum = millis(); - while(isHeatingBed()) + codenum = millis(); + while(isHeatingBed()) { if(( millis() - codenum) > 1000 ) //Print Temp Reading every 1 second while heating up. { @@ -1148,11 +1177,11 @@ void process_commands() SERIAL_PROTOCOLPGM("T:"); SERIAL_PROTOCOL(tt); SERIAL_PROTOCOLPGM(" E:"); - SERIAL_PROTOCOL((int)active_extruder); + SERIAL_PROTOCOL((int)active_extruder); SERIAL_PROTOCOLPGM(" B:"); - SERIAL_PROTOCOL_F(degBed(),1); - SERIAL_PROTOCOLLN(""); - codenum = millis(); + SERIAL_PROTOCOL_F(degBed(),1); + SERIAL_PROTOCOLLN(""); + codenum = millis(); } manage_heater(); manage_inactivity(); @@ -1169,7 +1198,7 @@ void process_commands() fanSpeed=constrain(code_value(),0,255); } else { - fanSpeed=255; + fanSpeed=255; } break; case 107: //M107 Fan Off @@ -1184,7 +1213,7 @@ void process_commands() ValvePressure=constrain(code_value(),0,255); } else { - ValvePressure=255; + ValvePressure=255; } break; case 127: //M127 valve closed @@ -1199,7 +1228,7 @@ void process_commands() EtoPPressure=constrain(code_value(),0,255); } else { - EtoPPressure=255; + EtoPPressure=255; } break; case 129: //M129 valve closed @@ -1214,18 +1243,18 @@ void process_commands() WRITE(PS_ON_PIN, PS_ON_AWAKE); break; #endif - + case 81: // M81 - ATX Power Off - + #if defined SUICIDE_PIN && SUICIDE_PIN > -1 st_synchronize(); suicide(); #elif (PS_ON_PIN > -1) - SET_OUTPUT(PS_ON_PIN); + SET_OUTPUT(PS_ON_PIN); WRITE(PS_ON_PIN, PS_ON_ASLEEP); #endif break; - + case 82: axis_relative_modes[3] = false; break; @@ -1234,11 +1263,11 @@ void process_commands() break; case 18: //compatibility case 84: // M84 - if(code_seen('S')){ - stepper_inactive_time = code_value() * 1000; + if(code_seen('S')){ + stepper_inactive_time = code_value() * 1000; } else - { + { bool all_axis = !((code_seen(axis_codes[0])) || (code_seen(axis_codes[1])) || (code_seen(axis_codes[2]))|| (code_seen(axis_codes[3]))); if(all_axis) { @@ -1260,18 +1289,18 @@ void process_commands() disable_e1(); disable_e2(); } - #endif + #endif } } break; case 85: // M85 code_seen('S'); - max_inactive_time = code_value() * 1000; + max_inactive_time = code_value() * 1000; break; case 92: // M92 - for(int8_t i=0; i < NUM_AXIS; i++) + for(int8_t i=0; i < NUM_AXIS; i++) { - if(code_seen(axis_codes[i])) + if(code_seen(axis_codes[i])) { if(i == 3) { // E float value = code_value(); @@ -1305,16 +1334,16 @@ void process_commands() SERIAL_PROTOCOL(current_position[Y_AXIS]); SERIAL_PROTOCOLPGM("Z:"); SERIAL_PROTOCOL(current_position[Z_AXIS]); - SERIAL_PROTOCOLPGM("E:"); + SERIAL_PROTOCOLPGM("E:"); SERIAL_PROTOCOL(current_position[E_AXIS]); - + SERIAL_PROTOCOLPGM(MSG_COUNT_X); SERIAL_PROTOCOL(float(st_get_position(X_AXIS))/axis_steps_per_unit[X_AXIS]); SERIAL_PROTOCOLPGM("Y:"); SERIAL_PROTOCOL(float(st_get_position(Y_AXIS))/axis_steps_per_unit[Y_AXIS]); SERIAL_PROTOCOLPGM("Z:"); SERIAL_PROTOCOL(float(st_get_position(Z_AXIS))/axis_steps_per_unit[Z_AXIS]); - + SERIAL_PROTOCOLLN(""); break; case 120: // M120 @@ -1352,7 +1381,7 @@ void process_commands() break; //TODO: update for all axis, use for loop case 201: // M201 - for(int8_t i=0; i < NUM_AXIS; i++) + for(int8_t i=0; i < NUM_AXIS; i++) { if(code_seen(axis_codes[i])) { @@ -1391,7 +1420,7 @@ void process_commands() } break; case 206: // M206 additional homeing offset - for(int8_t i=0; i < 3; i++) + for(int8_t i=0; i < 3; i++) { if(code_seen(axis_codes[i])) add_homeing[i] = code_value(); } @@ -1399,47 +1428,47 @@ void process_commands() #ifdef FWRETRACT case 207: //M207 - set retract length S[positive mm] F[feedrate mm/sec] Z[additional zlift/hop] { - if(code_seen('S')) + if(code_seen('S')) { retract_length = code_value() ; } - if(code_seen('F')) + if(code_seen('F')) { retract_feedrate = code_value() ; } - if(code_seen('Z')) + if(code_seen('Z')) { retract_zlift = code_value() ; } }break; case 208: // M208 - set retract recover length S[positive mm surplus to the M207 S*] F[feedrate mm/sec] { - if(code_seen('S')) + if(code_seen('S')) { retract_recover_length = code_value() ; } - if(code_seen('F')) + if(code_seen('F')) { retract_recover_feedrate = code_value() ; } }break; case 209: // M209 - S<1=true/0=false> enable automatic retract detect if the slicer did not support G10/11: every normal extrude-only move will be classified as retract depending on the direction. { - if(code_seen('S')) + if(code_seen('S')) { int t= code_value() ; switch(t) { case 0: autoretract_enabled=false;retracted=false;break; case 1: autoretract_enabled=true;retracted=false;break; - default: + default: SERIAL_ECHO_START; SERIAL_ECHOPGM(MSG_UNKNOWN_COMMAND); SERIAL_ECHO(cmdbuffer[bufindr]); SERIAL_ECHOLNPGM("\""); } } - + }break; #endif // FWRETRACT #if EXTRUDERS > 1 @@ -1448,7 +1477,7 @@ void process_commands() if(setTargetedHotend(218)){ break; } - if(code_seen('X')) + if(code_seen('X')) { extruder_offset[X_AXIS][tmp_extruder] = code_value(); } @@ -1458,7 +1487,7 @@ void process_commands() } SERIAL_ECHO_START; SERIAL_ECHOPGM(MSG_HOTEND_OFFSET); - for(tmp_extruder = 0; tmp_extruder < EXTRUDERS; tmp_extruder++) + for(tmp_extruder = 0; tmp_extruder < EXTRUDERS; tmp_extruder++) { SERIAL_ECHO(" "); SERIAL_ECHO(extruder_offset[X_AXIS][tmp_extruder]); @@ -1470,7 +1499,7 @@ void process_commands() #endif case 220: // M220 S- set speed factor override percentage { - if(code_seen('S')) + if(code_seen('S')) { feedmultiply = code_value() ; } @@ -1478,13 +1507,44 @@ void process_commands() break; case 221: // M221 S- set extrude factor override percentage { - if(code_seen('S')) + if(code_seen('S')) { extrudemultiply = code_value() ; } } break; - + + #if (defined NUM_SERVOS) && (NUM_SERVOS > 0) + case 280: // M280 - set servo position absolute. P: servo index, S: angle or microseconds + { + int servo_index = -1; + int servo_position = 0; + if (code_seen('P')) + servo_index = code_value(); + if (code_seen('S')) { + servo_position = code_value(); + if ((servo_index >= 0) && (servo_index < NUM_SERVOS)) { + servos[servo_index].write(servo_position); + } + else { + SERIAL_ECHO_START; + SERIAL_ECHO("Servo "); + SERIAL_ECHO(servo_index); + SERIAL_ECHOLN(" out of range"); + } + } + else if (servo_index >= 0) { + SERIAL_PROTOCOL(MSG_OK); + SERIAL_PROTOCOL(" Servo "); + SERIAL_PROTOCOL(servo_index); + SERIAL_PROTOCOL(": "); + SERIAL_PROTOCOL(servos[servo_index].read()); + SERIAL_PROTOCOLLN(""); + } + } + break; + #endif // NUM_SERVOS > 0 + #if defined(LARGE_FLASH) && LARGE_FLASH == true && defined(BEEPER) && BEEPER > -1 case 300: // M300 { @@ -1509,7 +1569,7 @@ void process_commands() #ifdef PID_ADD_EXTRUSION_RATE if(code_seen('C')) Kc = code_value(); #endif - + updatePID(); SERIAL_PROTOCOL(MSG_OK); SERIAL_PROTOCOL(" p:"); @@ -1569,7 +1629,7 @@ void process_commands() #endif } break; - + case 302: // allow cold extrudes { allow_cold_extrudes(true); @@ -1634,7 +1694,7 @@ void process_commands() lastpos[Z_AXIS]=current_position[Z_AXIS]; lastpos[E_AXIS]=current_position[E_AXIS]; //retract by E - if(code_seen('E')) + if(code_seen('E')) { target[E_AXIS]+= code_value(); } @@ -1645,9 +1705,9 @@ void process_commands() #endif } plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], feedrate/60, active_extruder); - + //lift Z - if(code_seen('Z')) + if(code_seen('Z')) { target[Z_AXIS]+= code_value(); } @@ -1658,9 +1718,9 @@ void process_commands() #endif } plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], feedrate/60, active_extruder); - + //move xy - if(code_seen('X')) + if(code_seen('X')) { target[X_AXIS]+= code_value(); } @@ -1670,7 +1730,7 @@ void process_commands() target[X_AXIS]= FILAMENTCHANGE_XPOS ; #endif } - if(code_seen('Y')) + if(code_seen('Y')) { target[Y_AXIS]= code_value(); } @@ -1680,9 +1740,9 @@ void process_commands() target[Y_AXIS]= FILAMENTCHANGE_YPOS ; #endif } - + plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], feedrate/60, active_extruder); - + if(code_seen('L')) { target[E_AXIS]+= code_value(); @@ -1693,9 +1753,9 @@ void process_commands() target[E_AXIS]+= FILAMENTCHANGE_FINALRETRACT ; #endif } - + plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], feedrate/60, active_extruder); - + //finish moves st_synchronize(); //disable extruder steppers so filament can be removed @@ -1710,12 +1770,12 @@ void process_commands() manage_heater(); manage_inactivity(); lcd_update(); - + #if BEEPER > -1 if(cnt==0) { SET_OUTPUT(BEEPER); - + WRITE(BEEPER,HIGH); delay(3); WRITE(BEEPER,LOW); @@ -1723,9 +1783,9 @@ void process_commands() } #endif } - + //return to normal - if(code_seen('L')) + if(code_seen('L')) { target[E_AXIS]+= -code_value(); } @@ -1743,7 +1803,7 @@ void process_commands() plan_buffer_line(lastpos[X_AXIS], lastpos[Y_AXIS], lastpos[Z_AXIS], lastpos[E_AXIS], feedrate/60, active_extruder); //final untretract } break; - #endif //FILAMENTCHANGEENABLE + #endif //FILAMENTCHANGEENABLE case 907: // M907 Set digital trimpot motor current using axis codes. { #if DIGIPOTSS_PIN > -1 @@ -1766,7 +1826,7 @@ void process_commands() case 350: // M350 Set microstepping mode. Warning: Steps per unit remains unchanged. S code sets stepping mode for all drivers. { #if X_MS1_PIN > -1 - if(code_seen('S')) for(int i=0;i<=4;i++) microstep_mode(i,code_value()); + if(code_seen('S')) for(int i=0;i<=4;i++) microstep_mode(i,code_value()); for(int i=0;i= EXTRUDERS) { @@ -1825,7 +1885,7 @@ void process_commands() // Offset extruder (only by XY) int i; for(i = 0; i < 2; i++) { - current_position[i] = current_position[i] - + current_position[i] = current_position[i] - extruder_offset[i][active_extruder] + extruder_offset[i][tmp_extruder]; } @@ -1871,14 +1931,14 @@ void ClearToSend() if(fromsd[bufindr]) return; #endif //SDSUPPORT - SERIAL_PROTOCOLLNPGM(MSG_OK); + SERIAL_PROTOCOLLNPGM(MSG_OK); } void get_coordinates() { bool seen[4]={false,false,false,false}; for(int8_t i=0; i < NUM_AXIS; i++) { - if(code_seen(axis_codes[i])) + if(code_seen(axis_codes[i])) { destination[i] = (float)code_value() + (axis_relative_modes[i] || relative_mode)*current_position[i]; seen[i]=true; @@ -1896,23 +1956,23 @@ void get_coordinates() float echange=destination[E_AXIS]-current_position[E_AXIS]; if(echange<-MIN_RETRACT) //retract { - if(!retracted) + if(!retracted) { - + destination[Z_AXIS]+=retract_zlift; //not sure why chaninging current_position negatively does not work. //if slicer retracted by echange=-1mm and you want to retract 3mm, corrrectede=-2mm additionally float correctede=-echange-retract_length; //to generate the additional steps, not the destination is changed, but inversely the current position - current_position[E_AXIS]+=-correctede; + current_position[E_AXIS]+=-correctede; feedrate=retract_feedrate; retracted=true; } - + } - else + else if(echange>MIN_RETRACT) //retract_recover { - if(retracted) + if(retracted) { //current_position[Z_AXIS]+=-retract_zlift; //if slicer retracted_recovered by echange=+1mm and you want to retract_recover 3mm, corrrectede=2mm additionally @@ -1922,7 +1982,7 @@ void get_coordinates() retracted=false; } } - + } #endif //FWRETRACT } @@ -1940,7 +2000,7 @@ void get_arc_coordinates() if(code_seen('I')) { offset[0] = code_value(); - } + } else { offset[0] = 0.0; } @@ -1971,7 +2031,7 @@ void prepare_move() { clamp_to_software_endstops(destination); - previous_millis_cmd = millis(); + previous_millis_cmd = millis(); // Do not use feedmultiply for E or Z only moves if( (current_position[X_AXIS] == destination [X_AXIS]) && (current_position[Y_AXIS] == destination [Y_AXIS])) { plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder); @@ -1989,7 +2049,7 @@ void prepare_arc_move(char isclockwise) { // Trace the arc mc_arc(current_position, destination, offset, X_AXIS, Y_AXIS, Z_AXIS, feedrate*feedmultiply/60/100.0, r, isclockwise, active_extruder); - + // As far as the parser is concerned, the position is now == target. In reality the // motion control system might still be processing the action and the real tool position // in any intermediate location. @@ -2008,7 +2068,7 @@ void controllerFan() if ((millis() - lastMotorCheck) >= 2500) //Not a time critical function, so we only check every 2500ms { lastMotorCheck = millis(); - + if(!READ(X_ENABLE_PIN) || !READ(Y_ENABLE_PIN) || !READ(Z_ENABLE_PIN) #if EXTRUDERS > 2 || !READ(E2_ENABLE_PIN) @@ -2016,12 +2076,12 @@ void controllerFan() #if EXTRUDER > 1 || !READ(E1_ENABLE_PIN) #endif - || !READ(E0_ENABLE_PIN)) //If any of the drivers are enabled... + || !READ(E0_ENABLE_PIN)) //If any of the drivers are enabled... { lastMotor = millis(); //... set time to NOW so the fan will turn on } - - if ((millis() - lastMotor) >= (CONTROLLERFAN_SEC*1000UL) || lastMotor == 0) //If the last time any driver was enabled, is longer since than CONTROLLERSEC... + + if ((millis() - lastMotor) >= (CONTROLLERFAN_SEC*1000UL) || lastMotor == 0) //If the last time any driver was enabled, is longer since than CONTROLLERSEC... { WRITE(CONTROLLERFAN_PIN, LOW); //... turn the fan off } @@ -2041,7 +2101,7 @@ void extruderFan() if ((millis() - lastExtruderCheck) >= 2500) //Not a time critical function, so we only check every 2500ms { lastExtruderCheck = millis(); - + if (degHotend(active_extruder) < EXTRUDERFAN_DEC) { WRITE(EXTRUDERFAN_PIN, LOW); //... turn the fan off @@ -2054,13 +2114,13 @@ void extruderFan() } #endif -void manage_inactivity() -{ - if( (millis() - previous_millis_cmd) > max_inactive_time ) - if(max_inactive_time) - kill(); +void manage_inactivity() +{ + if( (millis() - previous_millis_cmd) > max_inactive_time ) + if(max_inactive_time) + kill(); if(stepper_inactive_time) { - if( (millis() - previous_millis_cmd) > stepper_inactive_time ) + if( (millis() - previous_millis_cmd) > stepper_inactive_time ) { if(blocks_queued() == false) { disable_x(); @@ -2080,15 +2140,15 @@ void manage_inactivity() controllerFan(); //Check if fan should be turned on to cool stepper drivers down #endif #ifdef EXTRUDER_RUNOUT_PREVENT - if( (millis() - previous_millis_cmd) > EXTRUDER_RUNOUT_SECONDS*1000 ) + if( (millis() - previous_millis_cmd) > EXTRUDER_RUNOUT_SECONDS*1000 ) if(degHotend(active_extruder)>EXTRUDER_RUNOUT_MINTEMP) { bool oldstatus=READ(E0_ENABLE_PIN); enable_e0(); float oldepos=current_position[E_AXIS]; float oldedes=destination[E_AXIS]; - plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], - current_position[E_AXIS]+EXTRUDER_RUNOUT_EXTRUDE*EXTRUDER_RUNOUT_ESTEPS/axis_steps_per_unit[E_AXIS], + plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], + current_position[E_AXIS]+EXTRUDER_RUNOUT_EXTRUDE*EXTRUDER_RUNOUT_ESTEPS/axis_steps_per_unit[E_AXIS], EXTRUDER_RUNOUT_SPEED/60.*EXTRUDER_RUNOUT_ESTEPS/axis_steps_per_unit[E_AXIS], active_extruder); current_position[E_AXIS]=oldepos; destination[E_AXIS]=oldedes; @@ -2112,7 +2172,7 @@ void kill() disable_e0(); disable_e1(); disable_e2(); - + if(PS_ON_PIN > -1) pinMode(PS_ON_PIN,INPUT); SERIAL_ERROR_START; SERIAL_ERRORLNPGM(MSG_ERR_KILLED); @@ -2141,7 +2201,7 @@ void setPwmFrequency(uint8_t pin, int val) val &= 0x07; switch(digitalPinToTimer(pin)) { - + #if defined(TCCR0A) case TIMER0A: case TIMER0B: @@ -2183,7 +2243,7 @@ void setPwmFrequency(uint8_t pin, int val) break; #endif - #if defined(TCCR4A) + #if defined(TCCR4A) case TIMER4A: case TIMER4B: case TIMER4C: @@ -2192,7 +2252,7 @@ void setPwmFrequency(uint8_t pin, int val) break; #endif - #if defined(TCCR5A) + #if defined(TCCR5A) case TIMER5A: case TIMER5B: case TIMER5C: diff --git a/Marlin/Servo.h b/Marlin/Servo.h index a76954a06f..17c99f7974 100644 --- a/Marlin/Servo.h +++ b/Marlin/Servo.h @@ -59,28 +59,34 @@ // Say which 16 bit timers can be used and in what order #if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) #define _useTimer5 -#define _useTimer1 +//#define _useTimer1 #define _useTimer3 #define _useTimer4 -typedef enum { _timer5, _timer1, _timer3, _timer4, _Nbr_16timers } timer16_Sequence_t ; +//typedef enum { _timer5, _timer1, _timer3, _timer4, _Nbr_16timers } timer16_Sequence_t ; +typedef enum { _timer5, _timer3, _timer4, _Nbr_16timers } timer16_Sequence_t ; #elif defined(__AVR_ATmega32U4__) -#define _useTimer1 -typedef enum { _timer1, _Nbr_16timers } timer16_Sequence_t ; +//#define _useTimer1 +#define _useTimer3 +//typedef enum { _timer1, _Nbr_16timers } timer16_Sequence_t ; +typedef enum { _timer3, _Nbr_16timers } timer16_Sequence_t ; #elif defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB1286__) #define _useTimer3 -#define _useTimer1 -typedef enum { _timer3, _timer1, _Nbr_16timers } timer16_Sequence_t ; +//#define _useTimer1 +//typedef enum { _timer3, _timer1, _Nbr_16timers } timer16_Sequence_t ; +typedef enum { _timer3, _Nbr_16timers } timer16_Sequence_t ; #elif defined(__AVR_ATmega128__) ||defined(__AVR_ATmega1281__)||defined(__AVR_ATmega2561__) #define _useTimer3 -#define _useTimer1 -typedef enum { _timer3, _timer1, _Nbr_16timers } timer16_Sequence_t ; +//#define _useTimer1 +//typedef enum { _timer3, _timer1, _Nbr_16timers } timer16_Sequence_t ; +typedef enum { _timer3, _Nbr_16timers } timer16_Sequence_t ; #else // everything else -#define _useTimer1 -typedef enum { _timer1, _Nbr_16timers } timer16_Sequence_t ; +//#define _useTimer1 +//typedef enum { _timer1, _Nbr_16timers } timer16_Sequence_t ; +typedef enum { _Nbr_16timers } timer16_Sequence_t ; #endif #define Servo_VERSION 2 // software version of this library diff --git a/Marlin/pins.h b/Marlin/pins.h index a13c522f71..52310f100e 100644 --- a/Marlin/pins.h +++ b/Marlin/pins.h @@ -248,14 +248,14 @@ #define E0_STEP_PIN 28 #define E0_DIR_PIN 27 #define E0_ENABLE_PIN 24 - + #define TEMP_0_PIN 2 #define TEMP_1_PIN -1 #define TEMP_2_PIN -1 #define TEMP_BED_PIN 1 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! (pin 34 bed) - + #define HEATER_0_PIN 4 - #define HEATER_1_PIN -1 + #define HEATER_1_PIN -1 #define HEATER_2_PIN -1 #define HEATER_BED_PIN 3 // (bed) @@ -272,25 +272,25 @@ //our RS485 pins //#define TX_ENABLE_PIN 12 //#define RX_ENABLE_PIN 13 - - #define BEEPER -1 - #define SDCARDDETECT -1 + + #define BEEPER -1 + #define SDCARDDETECT -1 #define SUICIDE_PIN -1 //has to be defined; otherwise Power_off doesn't work - + #define KILL_PIN -1 - //Pins for 4bit LCD Support - #define LCD_PINS_RS 18 + //Pins for 4bit LCD Support + #define LCD_PINS_RS 18 #define LCD_PINS_ENABLE 17 #define LCD_PINS_D4 16 - #define LCD_PINS_D5 15 + #define LCD_PINS_D5 15 #define LCD_PINS_D6 13 #define LCD_PINS_D7 14 - + //buttons are directly attached #define BTN_EN1 11 #define BTN_EN2 10 #define BTN_ENC 12 //the click - + #define BLEN_C 2 #define BLEN_B 1 #define BLEN_A 0 @@ -376,13 +376,18 @@ #else #define HEATER_1_PIN 9 // EXTRUDER 2 (FAN On Sprinter) #endif -#define HEATER_2_PIN -1 +#define HEATER_2_PIN -1 #define TEMP_0_PIN 13 // ANALOG NUMBERING #define TEMP_1_PIN 15 // ANALOG NUMBERING #define TEMP_2_PIN -1 // ANALOG NUMBERING #define HEATER_BED_PIN 8 // BED #define TEMP_BED_PIN 14 // ANALOG NUMBERING +#define SERVO0_PIN 11 +#define SERVO1_PIN 6 +#define SERVO2_PIN 5 +#define SERVO3_PIN 4 + #ifdef ULTRA_LCD #ifdef NEWPANEL @@ -396,13 +401,13 @@ #define BLEN_B 1 #define BLEN_C 2 - #define LCD_PINS_RS 16 + #define LCD_PINS_RS 16 #define LCD_PINS_ENABLE 17 #define LCD_PINS_D4 23 - #define LCD_PINS_D5 25 + #define LCD_PINS_D5 25 #define LCD_PINS_D6 27 #define LCD_PINS_D7 29 - + #ifdef REPRAP_DISCOUNT_SMART_CONTROLLER #define BEEPER 37 @@ -455,21 +460,21 @@ //#define SHIFT_LD 42 //#define SHIFT_OUT 40 //#define SHIFT_EN 17 - - #define LCD_PINS_RS 16 + + #define LCD_PINS_RS 16 #define LCD_PINS_ENABLE 17 #define LCD_PINS_D4 23 - #define LCD_PINS_D5 25 + #define LCD_PINS_D5 25 #define LCD_PINS_D6 27 #define LCD_PINS_D7 29 - + //encoder rotation values #define encrot0 0 #define encrot1 2 #define encrot2 3 #define encrot3 1 - + //bits in the shift register that carry the buttons for: // left up center down right red #define BL_LE 7 @@ -481,7 +486,7 @@ #define BLEN_B 1 #define BLEN_A 0 - #endif + #endif #endif //ULTRA_LCD #else // RAMPS_V_1_1 or RAMPS_V_1_2 as default (MOTHERBOARD == 3) @@ -526,15 +531,15 @@ #define HEATER_1_PIN -1 #define HEATER_2_PIN -1 #define TEMP_0_PIN 2 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! -#define TEMP_1_PIN -1 -#define TEMP_2_PIN -1 +#define TEMP_1_PIN -1 +#define TEMP_2_PIN -1 #define TEMP_BED_PIN 1 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! #endif// MOTHERBOARD == 33 || MOTHERBOARD == 34 -// SPI for Max6675 Thermocouple +// SPI for Max6675 Thermocouple #ifndef SDSUPPORT -// these pins are defined in the SD library if building with SD support +// these pins are defined in the SD library if building with SD support #define MAX_SCK_PIN 52 #define MAX_MISO_PIN 50 #define MAX_MOSI_PIN 51 @@ -586,8 +591,8 @@ #define HEATER_1_PIN -1 #define HEATER_2_PIN -1 #define TEMP_0_PIN 0 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! -#define TEMP_1_PIN -1 -#define TEMP_2_PIN -1 +#define TEMP_1_PIN -1 +#define TEMP_2_PIN -1 #define HEATER_BED_PIN -1 #define TEMP_BED_PIN -1 @@ -650,14 +655,14 @@ #define PS_ON_PIN -1 //changed @ rkoeppl 20110410 #define KILL_PIN -1 //changed @ drakelive 20120830 //our pin for debugging. - + #define DEBUG_PIN 0 - + //our RS485 pins #define TX_ENABLE_PIN 12 #define RX_ENABLE_PIN 13 - + #endif /**************************************************************************************** @@ -673,7 +678,7 @@ #if MOTHERBOARD == 62 || MOTHERBOARD == 63 || MOTHERBOARD == 64 #undef MOTHERBOARD #define MOTHERBOARD 6 -#define SANGUINOLOLU_V_1_2 +#define SANGUINOLOLU_V_1_2 #endif #if MOTHERBOARD == 6 #define KNOWN_BOARD 1 @@ -700,7 +705,7 @@ #define LED_PIN -1 -#define FAN_PIN -1 +#define FAN_PIN -1 #if FAN_PIN == 12 || FAN_PIN ==13 #define FAN_SOFT_PWM #endif @@ -779,21 +784,21 @@ #define BTN_ENC 16 //the switch //not connected to a pin #define SDCARDDETECT -1 - + //from the same bit in the RAMPS Newpanel define //encoder rotation values #define encrot0 0 #define encrot1 2 #define encrot2 3 #define encrot3 1 - + #define BLEN_C 2 #define BLEN_B 1 #define BLEN_A 0 - + #endif //Newpanel #endif //Ultipanel - + #endif @@ -823,17 +828,17 @@ #define Y_MAX_PIN 28 #define Y_ENABLE_PIN 29 -#define Z_STEP_PIN 37 +#define Z_STEP_PIN 37 #define Z_DIR_PIN 39 #define Z_MIN_PIN 30 #define Z_MAX_PIN 32 #define Z_ENABLE_PIN 35 -#define HEATER_BED_PIN 4 -#define TEMP_BED_PIN 10 +#define HEATER_BED_PIN 4 +#define TEMP_BED_PIN 10 #define HEATER_0_PIN 2 -#define TEMP_0_PIN 8 +#define TEMP_0_PIN 8 #define HEATER_1_PIN 3 #define TEMP_1_PIN 9 @@ -863,24 +868,24 @@ //arduino pin witch triggers an piezzo beeper #define BEEPER 18 - #define LCD_PINS_RS 20 + #define LCD_PINS_RS 20 #define LCD_PINS_ENABLE 17 #define LCD_PINS_D4 16 - #define LCD_PINS_D5 21 + #define LCD_PINS_D5 21 #define LCD_PINS_D6 5 #define LCD_PINS_D7 6 - + //buttons are directly attached #define BTN_EN1 40 #define BTN_EN2 42 #define BTN_ENC 19 //the click - + #define BLEN_C 2 #define BLEN_B 1 #define BLEN_A 0 - + #define SDCARDDETECT 38 - + //encoder rotation values #define encrot0 0 #define encrot1 2 @@ -895,14 +900,14 @@ #define SHIFT_LD 42 #define SHIFT_OUT 40 #define SHIFT_EN 17 - - #define LCD_PINS_RS 16 + + #define LCD_PINS_RS 16 #define LCD_PINS_ENABLE 5 #define LCD_PINS_D4 6 - #define LCD_PINS_D5 21 + #define LCD_PINS_D5 21 #define LCD_PINS_D6 20 #define LCD_PINS_D7 19 - + //encoder rotation values #ifndef ULTIMAKERCONTROLLER #define encrot0 0 @@ -929,7 +934,7 @@ #define BLEN_B 1 #define BLEN_A 0 - #endif + #endif #endif //ULTRA_LCD #endif @@ -960,17 +965,17 @@ #define Y_MAX_PIN 16 #define Y_ENABLE_PIN 29 -#define Z_STEP_PIN 37 +#define Z_STEP_PIN 37 #define Z_DIR_PIN 39 #define Z_MIN_PIN 19 #define Z_MAX_PIN 18 #define Z_ENABLE_PIN 35 -#define HEATER_BED_PIN -1 -#define TEMP_BED_PIN -1 +#define HEATER_BED_PIN -1 +#define TEMP_BED_PIN -1 #define HEATER_0_PIN 2 -#define TEMP_0_PIN 8 +#define TEMP_0_PIN 8 #define HEATER_1_PIN 1 #define TEMP_1_PIN 1 @@ -994,10 +999,10 @@ #define KILL_PIN -1 #define SUICIDE_PIN -1 //PIN that has to be turned on right after start, to keep power flowing. -#define LCD_PINS_RS 24 +#define LCD_PINS_RS 24 #define LCD_PINS_ENABLE 22 #define LCD_PINS_D4 36 -#define LCD_PINS_D5 34 +#define LCD_PINS_D5 34 #define LCD_PINS_D6 32 #define LCD_PINS_D7 30 @@ -1019,17 +1024,17 @@ #define X_DIR_PIN 16 #define X_ENABLE_PIN 48 #define X_MIN_PIN 37 -#define X_MAX_PIN 36 +#define X_MAX_PIN 36 #define Y_STEP_PIN 54 -#define Y_DIR_PIN 47 +#define Y_DIR_PIN 47 #define Y_ENABLE_PIN 55 #define Y_MIN_PIN 35 -#define Y_MAX_PIN 34 +#define Y_MAX_PIN 34 -#define Z_STEP_PIN 57 +#define Z_STEP_PIN 57 #define Z_DIR_PIN 56 -#define Z_ENABLE_PIN 62 +#define Z_ENABLE_PIN 62 #define Z_MIN_PIN 33 #define Z_MAX_PIN 32 @@ -1047,7 +1052,7 @@ #define LED_PIN 13 -#define FAN_PIN 7 +#define FAN_PIN 7 //additional FAN1 PIN (e.g. useful for electronics fan or light on/off) on PIN 8 #define PS_ON_PIN 45 @@ -1069,10 +1074,10 @@ #define SDSS 53 #define SDCARDDETECT 49 #define BEEPER 44 -#define LCD_PINS_RS 19 +#define LCD_PINS_RS 19 #define LCD_PINS_ENABLE 42 #define LCD_PINS_D4 18 -#define LCD_PINS_D5 38 +#define LCD_PINS_D5 38 #define LCD_PINS_D6 41 #define LCD_PINS_D7 40 #define BTN_EN1 11 @@ -1256,7 +1261,7 @@ #define LED_PIN -1 -#define FAN_PIN -1 +#define FAN_PIN -1 #define PS_ON_PIN 14 #define KILL_PIN -1 @@ -1295,7 +1300,7 @@ * MISO (D 6) PB6 7| |34 PA6 (AI 6 / D25) * SCK (D 7) PB7 8| |33 PA7 (AI 7 / D24) * RST 9| |32 AREF -* VCC 10| |31 GND +* VCC 10| |31 GND * GND 11| |30 AVCC * XTAL2 12| |29 PC7 (D 23) * XTAL1 13| |28 PC6 (D 22) @@ -1352,7 +1357,7 @@ #define KILL_PIN -1 #define HEATER_0_PIN 4 -#define HEATER_1_PIN -1 // 12 +#define HEATER_1_PIN -1 // 12 #define HEATER_2_PIN -1 // 13 #define TEMP_0_PIN 0 //D27 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! #define TEMP_1_PIN -1 // 1 @@ -1414,11 +1419,11 @@ #define KILL_PIN -1 #define HEATER_0_PIN 3 /*DONE PWM on RIGHT connector */ -#define HEATER_1_PIN -1 +#define HEATER_1_PIN -1 #define HEATER_2_PIN -1 -#define HEATER_1_PIN -1 +#define HEATER_1_PIN -1 #define HEATER_2_PIN -1 -#define TEMP_0_PIN 0 // ANALOG INPUT NUMBERING +#define TEMP_0_PIN 0 // ANALOG INPUT NUMBERING #define TEMP_1_PIN 1 // ANALOG #define TEMP_2_PIN -1 // 2 #define HEATER_BED_PIN 4 @@ -1466,7 +1471,7 @@ #define Z_MS2_PIN 67 #define HEATER_BED_PIN 3 -#define TEMP_BED_PIN 2 +#define TEMP_BED_PIN 2 #define HEATER_0_PIN 9 #define TEMP_0_PIN 0 @@ -1559,9 +1564,9 @@ #define HEATER_0_PIN 9 // EXTRUDER 1 #define HEATER_1_PIN 8 // EXTRUDER 2 (FAN On Sprinter) -#define HEATER_2_PIN -1 +#define HEATER_2_PIN -1 -#if TEMP_SENSOR_0 == -1 +#if TEMP_SENSOR_0 == -1 #define TEMP_0_PIN 8 // ANALOG NUMBERING #else #define TEMP_0_PIN 13 // ANALOG NUMBERING @@ -1580,25 +1585,25 @@ #ifdef NEWPANEL //arduino pin which triggers an piezzo beeper - - #define LCD_PINS_RS 16 + + #define LCD_PINS_RS 16 #define LCD_PINS_ENABLE 17 #define LCD_PINS_D4 23 - #define LCD_PINS_D5 25 + #define LCD_PINS_D5 25 #define LCD_PINS_D6 27 #define LCD_PINS_D7 29 - + //buttons are directly attached using AUX-2 #define BTN_EN1 59 #define BTN_EN2 64 #define BTN_ENC 43 //the click - + #define BLEN_C 2 #define BLEN_B 1 #define BLEN_A 0 - + #define SDCARDDETECT -1 // Ramps does not use this port - + //encoder rotation values #define encrot0 0 #define encrot1 2 @@ -1614,7 +1619,7 @@ #endif //List of pins which to ignore when asked to change by gcode, 0 and 1 are RX and TX, do not mess with those! -#define _E0_PINS E0_STEP_PIN, E0_DIR_PIN, E0_ENABLE_PIN, HEATER_0_PIN, +#define _E0_PINS E0_STEP_PIN, E0_DIR_PIN, E0_ENABLE_PIN, HEATER_0_PIN, #if EXTRUDERS > 1 #define _E1_PINS E1_STEP_PIN, E1_DIR_PIN, E1_ENABLE_PIN, HEATER_1_PIN, #else From 96624f0f3174363fc740a125480f6f72042cc963 Mon Sep 17 00:00:00 2001 From: Gord Christmas Date: Thu, 16 May 2013 08:25:20 -0700 Subject: [PATCH 17/18] Forgot to include reference to Servo in makefile --- Marlin/Makefile | 20 ++++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/Marlin/Makefile b/Marlin/Makefile index e09d15f067..c231735255 100644 --- a/Marlin/Makefile +++ b/Marlin/Makefile @@ -1,12 +1,12 @@ # Sprinter Arduino Project Makefile -# +# # Makefile Based on: # Arduino 0011 Makefile # Arduino adaptation by mellis, eighthave, oli.keller # Marlin adaption by Daid # # This has been tested with Arduino 0022. -# +# # This makefile allows you to build sketches from the command line # without the Arduino environment (or Java). # @@ -21,7 +21,7 @@ # (e.g. UPLOAD_PORT = /dev/tty.USB0). If the exact name of this file # changes, you can use * as a wildcard (e.g. UPLOAD_PORT = /dev/tty.usb*). # -# 3. Set the line containing "MCU" to match your board's processor. +# 3. Set the line containing "MCU" to match your board's processor. # Older one's are atmega8 based, newer ones like Arduino Mini, Bluetooth # or Diecimila have the atmega168. If you're using a LilyPad Arduino, # change F_CPU to 8000000. If you are using Gen7 electronics, you @@ -44,7 +44,7 @@ ARDUINO_INSTALL_DIR ?= ../../arduino-0022 ARDUINO_VERSION ?= 22 # You can optionally set a path to the avr-gcc tools. Requires a trailing slash. (ex: /usr/local/avr-gcc/bin) -AVR_TOOLS_PATH ?= +AVR_TOOLS_PATH ?= #Programmer configuration UPLOAD_RATE ?= 115200 @@ -213,7 +213,7 @@ CXXSRC = WMath.cpp WString.cpp Print.cpp Marlin_main.cpp \ SdFile.cpp SdVolume.cpp motion_control.cpp planner.cpp \ stepper.cpp temperature.cpp cardreader.cpp ConfigurationStore.cpp \ watchdog.cpp -CXXSRC += LiquidCrystal.cpp ultralcd.cpp SPI.cpp +CXXSRC += LiquidCrystal.cpp ultralcd.cpp SPI.cpp Servo.cpp #Check for Arduino 1.0.0 or higher and use the correct sourcefiles for that version ifeq ($(shell [ $(ARDUINO_VERSION) -ge 100 ] && echo true), true) @@ -317,19 +317,19 @@ endif # Default target. all: sizeafter -build: $(BUILD_DIR) elf hex +build: $(BUILD_DIR) elf hex # Creates the object directory -$(BUILD_DIR): +$(BUILD_DIR): $P mkdir -p $(BUILD_DIR) elf: $(BUILD_DIR)/$(TARGET).elf hex: $(BUILD_DIR)/$(TARGET).hex eep: $(BUILD_DIR)/$(TARGET).eep -lss: $(BUILD_DIR)/$(TARGET).lss +lss: $(BUILD_DIR)/$(TARGET).lss sym: $(BUILD_DIR)/$(TARGET).sym -# Program the device. +# Program the device. # Do not try to reset an arduino if it's not one upload: $(BUILD_DIR)/$(TARGET).hex ifeq (${AVRDUDE_PROGRAMMER}, arduino) @@ -356,7 +356,7 @@ COFFCONVERT=$(OBJCOPY) --debugging \ --change-section-address .data-0x800000 \ --change-section-address .bss-0x800000 \ --change-section-address .noinit-0x800000 \ - --change-section-address .eeprom-0x810000 + --change-section-address .eeprom-0x810000 coff: $(BUILD_DIR)/$(TARGET).elf From 6c45c3f4e70d3d9e71d03bba73bb85136238415f Mon Sep 17 00:00:00 2001 From: Erik van der Zalm Date: Thu, 16 May 2013 19:00:57 +0200 Subject: [PATCH 18/18] BariCUDA changes --- Marlin/planner.cpp | 26 ++------------------------ 1 file changed, 2 insertions(+), 24 deletions(-) diff --git a/Marlin/planner.cpp b/Marlin/planner.cpp index 1a37cecb47..35bda428f7 100644 --- a/Marlin/planner.cpp +++ b/Marlin/planner.cpp @@ -440,10 +440,8 @@ void check_axes_activity() unsigned char e_active = 0; unsigned char tail_fan_speed = fanSpeed; #ifdef BARICUDA - unsigned char valve_pressure = 0; - unsigned char e_to_p_pressure = 0; - unsigned char tail_valve_pressure = 0; - unsigned char tail_e_to_p_pressure = 0; + unsigned char tail_valve_pressure = ValvePressure; + unsigned char tail_e_to_p_pressure = EtoPPressure; #endif block_t *block; @@ -499,31 +497,11 @@ void check_axes_activity() #ifdef BARICUDA #if HEATER_1_PIN > -1 - if (ValvePressure != 0){ - analogWrite(HEATER_1_PIN,ValvePressure); // If buffer is empty use current valve pressure - } - - if((ValvePressure == 0) && (valve_pressure ==0)) { - analogWrite(HEATER_1_PIN, 0); - } - - if (ValvePressure != 0 && tail_valve_pressure !=0) { analogWrite(HEATER_1_PIN,tail_valve_pressure); - } #endif #if HEATER_2_PIN > -1 - if (EtoPPressure != 0){ - analogWrite(HEATER_2_PIN,EtoPPressure); // If buffer is empty use current EtoP pressure - } - - if((EtoPPressure == 0) && (e_to_p_pressure ==0)) { - analogWrite(HEATER_2_PIN, 0); - } - - if (EtoPPressure != 0 && tail_e_to_p_pressure !=0) { analogWrite(HEATER_2_PIN,tail_e_to_p_pressure); - } #endif #endif }