Merge remote-tracking branch 'upstream/Marlin_v1' into Marlin_v1
This commit is contained in:
commit
dfa549f268
|
@ -282,7 +282,7 @@ 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_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.
|
||||
|
||||
|
@ -347,6 +347,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 REPRAPWORLD_KEYPAD v1.1
|
||||
// http://reprapworld.com/?products_details&products_id=202&cPath=1591_1626
|
||||
//#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)
|
||||
#define DOGLCD
|
||||
|
@ -359,6 +364,11 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th
|
|||
#define NEWPANEL
|
||||
#endif
|
||||
|
||||
#if defined(REPRAPWORLD_KEYPAD)
|
||||
#define NEWPANEL
|
||||
#define ULTIPANEL
|
||||
#endif
|
||||
|
||||
//I2C PANELS
|
||||
|
||||
//#define LCD_I2C_SAINSMART_YWROBOT
|
||||
|
@ -433,6 +443,26 @@ 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
|
||||
|
||||
/*********************************************************************\
|
||||
*
|
||||
* 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"
|
||||
|
||||
|
|
|
@ -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)
|
||||
|
|
|
@ -186,6 +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;
|
||||
|
|
|
@ -40,7 +40,11 @@
|
|||
#include "language.h"
|
||||
#include "pins_arduino.h"
|
||||
|
||||
#if DIGIPOTSS_PIN > -1
|
||||
#if NUM_SERVOS > 0
|
||||
#include "Servo.h"
|
||||
#endif
|
||||
|
||||
#if DIGIPOTSS_PIN > 0
|
||||
#include <SPI.h>
|
||||
#endif
|
||||
|
||||
|
@ -101,6 +105,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
|
||||
|
@ -117,6 +125,7 @@
|
|||
// M220 S<factor in percent>- set speed factor override percentage
|
||||
// M221 S<factor in percent>- 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<frequency Hz> P<duration ms>
|
||||
// M301 - Set PID parameters P I and D
|
||||
// M302 - Allow cold extrudes
|
||||
|
@ -168,6 +177,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;
|
||||
|
@ -217,6 +230,10 @@ static uint8_t tmp_extruder;
|
|||
|
||||
bool Stopped=false;
|
||||
|
||||
#if NUM_SERVOS > 0
|
||||
Servo servos[NUM_SERVOS];
|
||||
#endif
|
||||
|
||||
//===========================================================================
|
||||
//=============================ROUTINES=============================
|
||||
//===========================================================================
|
||||
|
@ -292,7 +309,7 @@ void setup_killpin()
|
|||
void setup_photpin()
|
||||
{
|
||||
#ifdef PHOTOGRAPH_PIN
|
||||
#if (PHOTOGRAPH_PIN > -1)
|
||||
#if (PHOTOGRAPH_PIN > 0)
|
||||
SET_OUTPUT(PHOTOGRAPH_PIN);
|
||||
WRITE(PHOTOGRAPH_PIN, LOW);
|
||||
#endif
|
||||
|
@ -307,7 +324,7 @@ void setup_powerhold()
|
|||
WRITE(SUICIDE_PIN, HIGH);
|
||||
#endif
|
||||
#endif
|
||||
#if (PS_ON_PIN > -1)
|
||||
#if (PS_ON_PIN > 0)
|
||||
SET_OUTPUT(PS_ON_PIN);
|
||||
WRITE(PS_ON_PIN, PS_ON_AWAKE);
|
||||
#endif
|
||||
|
@ -316,13 +333,32 @@ void setup_powerhold()
|
|||
void suicide()
|
||||
{
|
||||
#ifdef SUICIDE_PIN
|
||||
#if (SUICIDE_PIN> -1)
|
||||
#if (SUICIDE_PIN > 0)
|
||||
SET_OUTPUT(SUICIDE_PIN);
|
||||
WRITE(SUICIDE_PIN, LOW);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
void servo_init()
|
||||
{
|
||||
#if (NUM_SERVOS >= 1) && (SERVO0_PIN > 0)
|
||||
servos[0].attach(SERVO0_PIN);
|
||||
#endif
|
||||
#if (NUM_SERVOS >= 2) && (SERVO1_PIN > 0)
|
||||
servos[1].attach(SERVO1_PIN);
|
||||
#endif
|
||||
#if (NUM_SERVOS >= 3) && (SERVO2_PIN > 0)
|
||||
servos[2].attach(SERVO2_PIN);
|
||||
#endif
|
||||
#if (NUM_SERVOS >= 4) && (SERVO3_PIN > 0)
|
||||
servos[3].attach(SERVO3_PIN);
|
||||
#endif
|
||||
#if (NUM_SERVOS >= 5)
|
||||
#error "TODO: enter initalisation code for more servos"
|
||||
#endif
|
||||
}
|
||||
|
||||
void setup()
|
||||
{
|
||||
setup_killpin();
|
||||
|
@ -371,6 +407,7 @@ void setup()
|
|||
watchdog_init();
|
||||
st_init(); // Initialize stepper, this enables interrupts!
|
||||
setup_photpin();
|
||||
servo_init();
|
||||
|
||||
lcd_init();
|
||||
|
||||
|
@ -636,7 +673,7 @@ static void axis_is_at_home(int axis) {
|
|||
|
||||
static void homeaxis(int axis) {
|
||||
#define HOMEAXIS_DO(LETTER) \
|
||||
((LETTER##_MIN_PIN > -1 && LETTER##_HOME_DIR==-1) || (LETTER##_MAX_PIN > -1 && LETTER##_HOME_DIR==1))
|
||||
((LETTER##_MIN_PIN > 0 && LETTER##_HOME_DIR==-1) || (LETTER##_MAX_PIN > 0 && LETTER##_HOME_DIR==1))
|
||||
|
||||
if (axis==X_AXIS ? HOMEAXIS_DO(X) :
|
||||
axis==Y_AXIS ? HOMEAXIS_DO(Y) :
|
||||
|
@ -1025,12 +1062,12 @@ void process_commands()
|
|||
if(setTargetedHotend(105)){
|
||||
break;
|
||||
}
|
||||
#if (TEMP_0_PIN > -1)
|
||||
#if (TEMP_0_PIN > 0)
|
||||
SERIAL_PROTOCOLPGM("ok T:");
|
||||
SERIAL_PROTOCOL_F(degHotend(tmp_extruder),1);
|
||||
SERIAL_PROTOCOLPGM(" /");
|
||||
SERIAL_PROTOCOL_F(degTargetHotend(tmp_extruder),1);
|
||||
#if TEMP_BED_PIN > -1
|
||||
#if TEMP_BED_PIN > 0
|
||||
SERIAL_PROTOCOLPGM(" B:");
|
||||
SERIAL_PROTOCOL_F(degBed(),1);
|
||||
SERIAL_PROTOCOLPGM(" /");
|
||||
|
@ -1128,7 +1165,7 @@ void process_commands()
|
|||
}
|
||||
break;
|
||||
case 190: // M190 - Wait for bed heater to reach target.
|
||||
#if TEMP_BED_PIN > -1
|
||||
#if TEMP_BED_PIN > 0
|
||||
LCD_MESSAGEPGM(MSG_BED_HEATING);
|
||||
if (code_seen('S')) setTargetBed(code_value());
|
||||
codenum = millis();
|
||||
|
@ -1155,7 +1192,7 @@ void process_commands()
|
|||
#endif
|
||||
break;
|
||||
|
||||
#if FAN_PIN > -1
|
||||
#if FAN_PIN > 0
|
||||
case 106: //M106 Fan On
|
||||
if (code_seen('S')){
|
||||
fanSpeed=constrain(code_value(),0,255);
|
||||
|
@ -1168,8 +1205,39 @@ void process_commands()
|
|||
fanSpeed = 0;
|
||||
break;
|
||||
#endif //FAN_PIN
|
||||
#ifdef BARICUDA
|
||||
// PWM for HEATER_1_PIN
|
||||
#if HEATER_1_PIN > 0
|
||||
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
|
||||
|
||||
#if (PS_ON_PIN > -1)
|
||||
// PWM for HEATER_2_PIN
|
||||
#if HEATER_2_PIN > 0
|
||||
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 > 0)
|
||||
case 80: // M80 - ATX Power On
|
||||
SET_OUTPUT(PS_ON_PIN); //GND
|
||||
WRITE(PS_ON_PIN, PS_ON_AWAKE);
|
||||
|
@ -1178,10 +1246,10 @@ void process_commands()
|
|||
|
||||
case 81: // M81 - ATX Power Off
|
||||
|
||||
#if defined SUICIDE_PIN && SUICIDE_PIN > -1
|
||||
#if defined SUICIDE_PIN && SUICIDE_PIN > 0
|
||||
st_synchronize();
|
||||
suicide();
|
||||
#elif (PS_ON_PIN > -1)
|
||||
#elif (PS_ON_PIN > 0)
|
||||
SET_OUTPUT(PS_ON_PIN);
|
||||
WRITE(PS_ON_PIN, PS_ON_ASLEEP);
|
||||
#endif
|
||||
|
@ -1286,27 +1354,27 @@ void process_commands()
|
|||
break;
|
||||
case 119: // M119
|
||||
SERIAL_PROTOCOLLN(MSG_M119_REPORT);
|
||||
#if (X_MIN_PIN > -1)
|
||||
#if (X_MIN_PIN > 0)
|
||||
SERIAL_PROTOCOLPGM(MSG_X_MIN);
|
||||
SERIAL_PROTOCOLLN(((READ(X_MIN_PIN)^X_ENDSTOPS_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
|
||||
#endif
|
||||
#if (X_MAX_PIN > -1)
|
||||
#if (X_MAX_PIN > 0)
|
||||
SERIAL_PROTOCOLPGM(MSG_X_MAX);
|
||||
SERIAL_PROTOCOLLN(((READ(X_MAX_PIN)^X_ENDSTOPS_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
|
||||
#endif
|
||||
#if (Y_MIN_PIN > -1)
|
||||
#if (Y_MIN_PIN > 0)
|
||||
SERIAL_PROTOCOLPGM(MSG_Y_MIN);
|
||||
SERIAL_PROTOCOLLN(((READ(Y_MIN_PIN)^Y_ENDSTOPS_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
|
||||
#endif
|
||||
#if (Y_MAX_PIN > -1)
|
||||
#if (Y_MAX_PIN > 0)
|
||||
SERIAL_PROTOCOLPGM(MSG_Y_MAX);
|
||||
SERIAL_PROTOCOLLN(((READ(Y_MAX_PIN)^Y_ENDSTOPS_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
|
||||
#endif
|
||||
#if (Z_MIN_PIN > -1)
|
||||
#if (Z_MIN_PIN > 0)
|
||||
SERIAL_PROTOCOLPGM(MSG_Z_MIN);
|
||||
SERIAL_PROTOCOLLN(((READ(Z_MIN_PIN)^Z_ENDSTOPS_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
|
||||
#endif
|
||||
#if (Z_MAX_PIN > -1)
|
||||
#if (Z_MAX_PIN > 0)
|
||||
SERIAL_PROTOCOLPGM(MSG_Z_MAX);
|
||||
SERIAL_PROTOCOLLN(((READ(Z_MAX_PIN)^Z_ENDSTOPS_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
|
||||
#endif
|
||||
|
@ -1446,14 +1514,45 @@ void process_commands()
|
|||
}
|
||||
break;
|
||||
|
||||
#if defined(LARGE_FLASH) && LARGE_FLASH == true
|
||||
#if 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 LARGE_FLASH == true && ( BEEPER > 0 || defined(ULTRALCD) )
|
||||
case 300: // M300
|
||||
{
|
||||
int beepS = 400;
|
||||
int beepP = 1000;
|
||||
if(code_seen('S')) beepS = code_value();
|
||||
if(code_seen('P')) beepP = code_value();
|
||||
#if defined(BEEPER) && BEEPER > -1
|
||||
#if BEEPER > 0
|
||||
tone(BEEPER, beepS);
|
||||
delay(beepP);
|
||||
noTone(BEEPER);
|
||||
|
@ -1514,7 +1613,7 @@ void process_commands()
|
|||
case 240: // M240 Triggers a camera by emulating a Canon RC-1 : http://www.doc-diy.net/photo/rc-1_hacked/
|
||||
{
|
||||
#ifdef PHOTOGRAPH_PIN
|
||||
#if (PHOTOGRAPH_PIN > -1)
|
||||
#if (PHOTOGRAPH_PIN > 0)
|
||||
const uint8_t NUM_PULSES=16;
|
||||
const float PULSE_LENGTH=0.01524;
|
||||
for(int i=0; i < NUM_PULSES; i++) {
|
||||
|
@ -1675,10 +1774,9 @@ void process_commands()
|
|||
manage_heater();
|
||||
manage_inactivity();
|
||||
lcd_update();
|
||||
|
||||
if(cnt==0)
|
||||
{
|
||||
#if defined(BEEPER) && BEEPER > -1
|
||||
#if BEEPER > 0
|
||||
SET_OUTPUT(BEEPER);
|
||||
|
||||
WRITE(BEEPER,HIGH);
|
||||
|
@ -1713,15 +1811,16 @@ void process_commands()
|
|||
#endif //FILAMENTCHANGEENABLE
|
||||
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());
|
||||
#if DIGIPOTSS_PIN > 0
|
||||
for(int i=0;i<NUM_AXIS;i++) if(code_seen(axis_codes[i])) digipot_current(i,code_value());
|
||||
if(code_seen('B')) digipot_current(4,code_value());
|
||||
if(code_seen('S')) for(int i=0;i<=4;i++) digipot_current(i,code_value());
|
||||
#endif
|
||||
}
|
||||
break;
|
||||
case 908: // M908 Control digital trimpot directly.
|
||||
{
|
||||
#if DIGIPOTSS_PIN > -1
|
||||
#if DIGIPOTSS_PIN > 0
|
||||
uint8_t channel,current;
|
||||
if(code_seen('P')) channel=code_value();
|
||||
if(code_seen('S')) current=code_value();
|
||||
|
@ -1731,9 +1830,9 @@ void process_commands()
|
|||
break;
|
||||
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 X_MS1_PIN > 0
|
||||
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<NUM_AXIS;i++) if(code_seen(axis_codes[i])) microstep_mode(i,(uint8_t)code_value());
|
||||
if(code_seen('B')) microstep_mode(4,code_value());
|
||||
microstep_readings();
|
||||
#endif
|
||||
|
@ -1741,15 +1840,15 @@ void process_commands()
|
|||
break;
|
||||
case 351: // M351 Toggle MS1 MS2 pins directly, S# determines MS1 or MS2, X# sets the pin high/low.
|
||||
{
|
||||
#if X_MS1_PIN > -1
|
||||
#if X_MS1_PIN > 0
|
||||
if(code_seen('S')) switch((int)code_value())
|
||||
{
|
||||
case 1:
|
||||
for(int i=0;i<=NUM_AXIS;i++) if(code_seen(axis_codes[i])) microstep_ms(i,code_value(),-1);
|
||||
for(int i=0;i<NUM_AXIS;i++) if(code_seen(axis_codes[i])) microstep_ms(i,code_value(),-1);
|
||||
if(code_seen('B')) microstep_ms(4,code_value(),-1);
|
||||
break;
|
||||
case 2:
|
||||
for(int i=0;i<=NUM_AXIS;i++) if(code_seen(axis_codes[i])) microstep_ms(i,-1,code_value());
|
||||
for(int i=0;i<NUM_AXIS;i++) if(code_seen(axis_codes[i])) microstep_ms(i,-1,code_value());
|
||||
if(code_seen('B')) microstep_ms(4,-1,code_value());
|
||||
break;
|
||||
}
|
||||
|
@ -1980,7 +2079,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...
|
||||
{
|
||||
|
@ -2079,7 +2178,7 @@ void kill()
|
|||
disable_e1();
|
||||
disable_e2();
|
||||
|
||||
if(PS_ON_PIN > -1) pinMode(PS_ON_PIN,INPUT);
|
||||
if(PS_ON_PIN > 0) pinMode(PS_ON_PIN,INPUT);
|
||||
SERIAL_ERROR_START;
|
||||
SERIAL_ERRORLNPGM(MSG_ERR_KILLED);
|
||||
LCD_ALERTMESSAGEPGM(MSG_KILLED);
|
||||
|
|
337
Marlin/Servo.cpp
Normal file
337
Marlin/Servo.cpp
Normal file
|
@ -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 <avr/interrupt.h>
|
||||
#include <Arduino.h>
|
||||
|
||||
#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 ;
|
||||
}
|
132
Marlin/Servo.h
Normal file
132
Marlin/Servo.h
Normal file
|
@ -0,0 +1,132 @@
|
|||
/*
|
||||
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 <inttypes.h>
|
||||
|
||||
/*
|
||||
* 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 ;
|
||||
typedef enum { _timer5, _timer3, _timer4, _Nbr_16timers } timer16_Sequence_t ;
|
||||
|
||||
#elif defined(__AVR_ATmega32U4__)
|
||||
//#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 ;
|
||||
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 ;
|
||||
typedef enum { _timer3, _Nbr_16timers } timer16_Sequence_t ;
|
||||
|
||||
#else // everything else
|
||||
//#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
|
||||
|
||||
#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
|
|
@ -290,6 +290,7 @@
|
|||
#define BTN_EN1 11
|
||||
#define BTN_EN2 10
|
||||
#define BTN_ENC 12 //the click
|
||||
|
||||
#endif
|
||||
|
||||
/****************************************************************************************
|
||||
|
@ -374,6 +375,11 @@
|
|||
#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
|
||||
|
@ -397,9 +403,18 @@
|
|||
#define BEEPER 33 // Beeper on AUX-4
|
||||
|
||||
//buttons are directly attached using AUX-2
|
||||
#ifdef REPRAPWORLD_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
|
||||
#else
|
||||
#define BTN_EN1 37
|
||||
#define BTN_EN2 35
|
||||
#define BTN_ENC 31 //the click
|
||||
#endif
|
||||
|
||||
#ifdef G3D_PANEL
|
||||
#define SDCARDDETECT 49
|
||||
|
@ -952,17 +967,56 @@
|
|||
#define PS_ON_PIN 45
|
||||
#define KILL_PIN 46
|
||||
|
||||
#if (TEMP_SENSOR_0==0)
|
||||
#define TEMP_0_PIN -1
|
||||
#define HEATER_0_PIN -1
|
||||
#else
|
||||
#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==-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
|
||||
|
@ -1365,7 +1419,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
|
||||
|
|
|
@ -439,12 +439,20 @@ void check_axes_activity()
|
|||
unsigned char z_active = 0;
|
||||
unsigned char e_active = 0;
|
||||
unsigned char tail_fan_speed = fanSpeed;
|
||||
#ifdef BARICUDA
|
||||
unsigned char tail_valve_pressure = ValvePressure;
|
||||
unsigned char tail_e_to_p_pressure = EtoPPressure;
|
||||
#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];
|
||||
|
@ -486,6 +494,16 @@ void check_axes_activity()
|
|||
#ifdef AUTOTEMP
|
||||
getHighESpeed();
|
||||
#endif
|
||||
|
||||
#ifdef BARICUDA
|
||||
#if HEATER_1_PIN > -1
|
||||
analogWrite(HEATER_1_PIN,tail_valve_pressure);
|
||||
#endif
|
||||
|
||||
#if HEATER_2_PIN > -1
|
||||
analogWrite(HEATER_2_PIN,tail_e_to_p_pressure);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
|
@ -559,6 +577,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;
|
||||
|
@ -582,8 +604,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
|
||||
|
|
|
@ -60,6 +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;
|
||||
|
||||
|
|
|
@ -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<<JTD);
|
||||
MCUCR=(1<<JTD);
|
||||
#endif
|
||||
|
||||
// Finish init of mult extruder arrays
|
||||
for(int e = 0; e < EXTRUDERS; e++) {
|
||||
// populate with the first value
|
||||
|
@ -647,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)
|
||||
|
@ -689,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
|
||||
|
@ -710,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
|
||||
|
|
|
@ -116,14 +116,18 @@ static void menu_action_setting_edit_callback_long5(const char* pstr, unsigned l
|
|||
} } while(0)
|
||||
|
||||
/** Used variables to keep track of the menu */
|
||||
#ifndef REPRAPWORLD_KEYPAD
|
||||
volatile uint8_t buttons;//Contains the bits of the currently pressed buttons.
|
||||
#else
|
||||
volatile uint16_t buttons;//Contains the bits of the currently pressed buttons (extended).
|
||||
#endif
|
||||
|
||||
uint8_t currentMenuViewOffset; /* scroll offset in the current menu */
|
||||
uint32_t blocking_enc;
|
||||
uint8_t lastEncoderBits;
|
||||
int8_t encoderDiff; /* encoderDiff is updated from interrupt context and added to encoderPosition every LCD update */
|
||||
uint32_t encoderPosition;
|
||||
#if (SDCARDDETECT > -1)
|
||||
#if (SDCARDDETECT > 0)
|
||||
bool lcd_oldcardstatus;
|
||||
#endif
|
||||
#endif//ULTIPANEL
|
||||
|
@ -255,6 +259,7 @@ void lcd_preheat_pla()
|
|||
setTargetBed(plaPreheatHPBTemp);
|
||||
fanSpeed = plaPreheatFanSpeed;
|
||||
lcd_return_to_status();
|
||||
setWatch(); // heater sanity check timer
|
||||
}
|
||||
|
||||
void lcd_preheat_abs()
|
||||
|
@ -265,6 +270,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()
|
||||
|
@ -302,7 +317,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();
|
||||
}
|
||||
|
@ -691,6 +706,24 @@ menu_edit_type(float, float51, ftostr51, 10)
|
|||
menu_edit_type(float, float52, ftostr52, 100)
|
||||
menu_edit_type(unsigned long, long5, ftostr5, 0.01)
|
||||
|
||||
#ifdef REPRAPWORLD_KEYPAD
|
||||
static void reprapworld_keypad_move_y_down() {
|
||||
encoderPosition = 1;
|
||||
move_menu_scale = REPRAPWORLD_KEYPAD_MOVE_STEP;
|
||||
lcd_move_y();
|
||||
}
|
||||
static void reprapworld_keypad_move_y_up() {
|
||||
encoderPosition = -1;
|
||||
move_menu_scale = REPRAPWORLD_KEYPAD_MOVE_STEP;
|
||||
lcd_move_y();
|
||||
}
|
||||
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")));
|
||||
}
|
||||
#endif
|
||||
|
||||
/** End of menus **/
|
||||
|
||||
static void lcd_quick_feedback()
|
||||
|
@ -752,10 +785,17 @@ void lcd_init()
|
|||
pinMode(SDCARDDETECT,INPUT);
|
||||
WRITE(BTN_EN1,HIGH);
|
||||
WRITE(BTN_EN2,HIGH);
|
||||
#if defined(BTN_ENC) && BTN_ENC > -1
|
||||
#if BTN_ENC > 0
|
||||
pinMode(BTN_ENC,INPUT);
|
||||
WRITE(BTN_ENC,HIGH);
|
||||
#endif
|
||||
#ifdef REPRAPWORLD_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);
|
||||
|
@ -765,10 +805,10 @@ void lcd_init()
|
|||
WRITE(SHIFT_LD,HIGH);
|
||||
WRITE(SHIFT_EN,LOW);
|
||||
#endif//!NEWPANEL
|
||||
#if (SDCARDDETECT > -1)
|
||||
#if (SDCARDDETECT > 0)
|
||||
WRITE(SDCARDDETECT, HIGH);
|
||||
lcd_oldcardstatus = IS_SD_INSERTED;
|
||||
#endif//(SDCARDDETECT > -1)
|
||||
#endif//(SDCARDDETECT > 0)
|
||||
lcd_buttons_update();
|
||||
#ifdef ULTIPANEL
|
||||
encoderDiff = 0;
|
||||
|
@ -785,7 +825,7 @@ void lcd_update()
|
|||
buttons |= lcd_implementation_read_slow_buttons(); // buttons which take too long to read in interrupt context
|
||||
#endif
|
||||
|
||||
#if (SDCARDDETECT > -1)
|
||||
#if (SDCARDDETECT > 0)
|
||||
if((IS_SD_INSERTED != lcd_oldcardstatus))
|
||||
{
|
||||
lcdDrawUpdate = 2;
|
||||
|
@ -808,6 +848,17 @@ void lcd_update()
|
|||
if (lcd_next_update_millis < millis())
|
||||
{
|
||||
#ifdef ULTIPANEL
|
||||
#ifdef REPRAPWORLD_KEYPAD
|
||||
if (REPRAPWORLD_KEYPAD_MOVE_Y_DOWN) {
|
||||
reprapworld_keypad_move_y_down();
|
||||
}
|
||||
if (REPRAPWORLD_KEYPAD_MOVE_Y_UP) {
|
||||
reprapworld_keypad_move_y_up();
|
||||
}
|
||||
if (REPRAPWORLD_KEYPAD_MOVE_HOME) {
|
||||
reprapworld_keypad_move_home();
|
||||
}
|
||||
#endif
|
||||
if (encoderDiff)
|
||||
{
|
||||
lcdDrawUpdate = 1;
|
||||
|
@ -890,9 +941,23 @@ void lcd_buttons_update()
|
|||
uint8_t newbutton=0;
|
||||
if(READ(BTN_EN1)==0) newbutton|=EN_A;
|
||||
if(READ(BTN_EN2)==0) newbutton|=EN_B;
|
||||
#if defined(BTN_ENC) && BTN_ENC > -1
|
||||
#if BTN_ENC > 0
|
||||
if((blocking_enc<millis()) && (READ(BTN_ENC)==0))
|
||||
newbutton |= EN_C;
|
||||
#endif
|
||||
#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);
|
||||
}
|
||||
newbutton |= ((~newbutton_reprapworld_keypad) << REPRAPWORLD_BTN_OFFSET); //invert it, because a pressed switch produces a logical 0
|
||||
#endif
|
||||
buttons = newbutton;
|
||||
#else //read it from the shift register
|
||||
|
|
|
@ -35,7 +35,6 @@
|
|||
extern int absPreheatFanSpeed;
|
||||
|
||||
void lcd_buzz(long duration,uint16_t freq);
|
||||
|
||||
bool lcd_clicked();
|
||||
|
||||
#else //no lcd
|
||||
|
|
|
@ -6,7 +6,11 @@
|
|||
* When selecting the rusian language, a slightly different LCD implementation is used to handle UTF8 characters.
|
||||
**/
|
||||
|
||||
#ifndef REPRAPWORLD_KEYPAD
|
||||
extern volatile uint8_t buttons; //the last checked buttons in a bit array.
|
||||
#else
|
||||
extern volatile uint16_t buttons; //an extended version of the last checked buttons in a bit array.
|
||||
#endif
|
||||
|
||||
////////////////////////////////////
|
||||
// Setup button and encode mappings for each panel (into 'buttons' variable)
|
||||
|
@ -55,7 +59,7 @@ extern volatile uint8_t buttons; //the last checked buttons in a bit array.
|
|||
|
||||
#elif defined(LCD_I2C_PANELOLU2)
|
||||
// encoder click can be read through I2C if not directly connected
|
||||
#if !defined(BTN_ENC) || BTN_ENC == -1
|
||||
#if BTN_ENC <= 0
|
||||
#define B_I2C_BTN_OFFSET 3 // (the first three bit positions reserved for EN_A, EN_B, EN_C)
|
||||
|
||||
#define B_MI (PANELOLU2_ENCODER_C<<B_I2C_BTN_OFFSET) // requires LiquidTWI2 library v1.2.3 or later
|
||||
|
@ -68,6 +72,33 @@ extern volatile uint8_t buttons; //the last checked buttons in a bit array.
|
|||
#define LCD_CLICKED (buttons&EN_C)
|
||||
#endif
|
||||
|
||||
#elif defined(REPRAPWORLD_KEYPAD)
|
||||
// define register bit values, don't change it
|
||||
#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
|
||||
|
||||
#define REPRAPWORLD_BTN_OFFSET 3 // bit offset into buttons for shift register values
|
||||
|
||||
#define EN_REPRAPWORLD_KEYPAD_F3 (1<<(BLEN_REPRAPWORLD_KEYPAD_F3+REPRAPWORLD_BTN_OFFSET))
|
||||
#define EN_REPRAPWORLD_KEYPAD_F2 (1<<(BLEN_REPRAPWORLD_KEYPAD_F2+REPRAPWORLD_BTN_OFFSET))
|
||||
#define EN_REPRAPWORLD_KEYPAD_F1 (1<<(BLEN_REPRAPWORLD_KEYPAD_F1+REPRAPWORLD_BTN_OFFSET))
|
||||
#define EN_REPRAPWORLD_KEYPAD_UP (1<<(BLEN_REPRAPWORLD_KEYPAD_UP+REPRAPWORLD_BTN_OFFSET))
|
||||
#define EN_REPRAPWORLD_KEYPAD_RIGHT (1<<(BLEN_REPRAPWORLD_KEYPAD_RIGHT+REPRAPWORLD_BTN_OFFSET))
|
||||
#define EN_REPRAPWORLD_KEYPAD_MIDDLE (1<<(BLEN_REPRAPWORLD_KEYPAD_MIDDLE+REPRAPWORLD_BTN_OFFSET))
|
||||
#define EN_REPRAPWORLD_KEYPAD_DOWN (1<<(BLEN_REPRAPWORLD_KEYPAD_DOWN+REPRAPWORLD_BTN_OFFSET))
|
||||
#define EN_REPRAPWORLD_KEYPAD_LEFT (1<<(BLEN_REPRAPWORLD_KEYPAD_LEFT+REPRAPWORLD_BTN_OFFSET))
|
||||
|
||||
#define LCD_CLICKED ((buttons&EN_C) || (buttons&EN_REPRAPWORLD_KEYPAD_F1))
|
||||
#define REPRAPWORLD_KEYPAD_MOVE_Y_DOWN (buttons&EN_REPRAPWORLD_KEYPAD_DOWN)
|
||||
#define REPRAPWORLD_KEYPAD_MOVE_Y_UP (buttons&EN_REPRAPWORLD_KEYPAD_UP)
|
||||
#define REPRAPWORLD_KEYPAD_MOVE_HOME (buttons&EN_REPRAPWORLD_KEYPAD_MIDDLE)
|
||||
|
||||
#elif defined(NEWPANEL)
|
||||
#define LCD_CLICKED (buttons&EN_C)
|
||||
|
||||
|
@ -90,7 +121,7 @@ extern volatile uint8_t buttons; //the last checked buttons in a bit array.
|
|||
#define B_ST (1<<BL_ST)
|
||||
|
||||
#define LCD_CLICKED (buttons&(B_MI|B_ST))
|
||||
#endif//else NEWPANEL
|
||||
#endif
|
||||
|
||||
////////////////////////
|
||||
// Setup Rotary Encoder Bit Values (for two pin encoders to indicate movement)
|
||||
|
|
Loading…
Reference in a new issue