Merge remote-tracking branch 'upstream/MK3' into MK3
merging new changes from upsream
This commit is contained in:
commit
f48bb1e83f
40 changed files with 3660 additions and 1843 deletions
|
@ -186,7 +186,6 @@
|
||||||
#undef PREVENT_LENGTHY_EXTRUDE
|
#undef PREVENT_LENGTHY_EXTRUDE
|
||||||
#endif //DEBUG_DISABLE_PREVENT_EXTRUDER
|
#endif //DEBUG_DISABLE_PREVENT_EXTRUDER
|
||||||
|
|
||||||
|
|
||||||
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
|
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
|
||||||
|
|
||||||
/*================== Thermal Runaway Protection ==============================
|
/*================== Thermal Runaway Protection ==============================
|
||||||
|
@ -258,8 +257,8 @@ your extruder heater takes 2 minutes to hit the target on heating.
|
||||||
|
|
||||||
// The pullups are needed if you directly connect a mechanical endswitch between the signal and ground pins.
|
// The pullups are needed if you directly connect a mechanical endswitch between the signal and ground pins.
|
||||||
|
|
||||||
const bool X_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
const bool X_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||||
const bool Y_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
const bool Y_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||||
const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
||||||
//#define DISABLE_MAX_ENDSTOPS
|
//#define DISABLE_MAX_ENDSTOPS
|
||||||
//#define DISABLE_MIN_ENDSTOPS
|
//#define DISABLE_MIN_ENDSTOPS
|
||||||
|
@ -295,12 +294,12 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
|
||||||
#define Y_HOME_DIR -1
|
#define Y_HOME_DIR -1
|
||||||
#define Z_HOME_DIR -1
|
#define Z_HOME_DIR -1
|
||||||
|
|
||||||
#define min_software_endstops true // If true, axis won't move to coordinates less than HOME_POS.
|
|
||||||
#define max_software_endstops true // If true, axis won't move to coordinates greater than the defined lengths below.
|
|
||||||
|
|
||||||
#ifdef DEBUG_DISABLE_SWLIMITS
|
#ifdef DEBUG_DISABLE_SWLIMITS
|
||||||
#define min_software_endstops false
|
#define min_software_endstops false
|
||||||
#define max_software_endstops false
|
#define max_software_endstops false
|
||||||
|
#else
|
||||||
|
#define min_software_endstops true // If true, axis won't move to coordinates less than HOME_POS.
|
||||||
|
#define max_software_endstops true // If true, axis won't move to coordinates greater than the defined lengths below.
|
||||||
#endif //DEBUG_DISABLE_SWLIMITS
|
#endif //DEBUG_DISABLE_SWLIMITS
|
||||||
|
|
||||||
|
|
||||||
|
@ -745,4 +744,8 @@ enum CalibrationStatus
|
||||||
#include "Configuration_adv.h"
|
#include "Configuration_adv.h"
|
||||||
#include "thermistortables.h"
|
#include "thermistortables.h"
|
||||||
|
|
||||||
|
#define PINDA_THERMISTOR
|
||||||
|
|
||||||
|
#define AMBIENT_THERMISTOR
|
||||||
|
|
||||||
#endif //__CONFIGURATION_H
|
#endif //__CONFIGURATION_H
|
||||||
|
|
|
@ -356,6 +356,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
//The ASCII buffer for receiving from the serial:
|
//The ASCII buffer for receiving from the serial:
|
||||||
#define MAX_CMD_SIZE 96
|
#define MAX_CMD_SIZE 96
|
||||||
#define BUFSIZE 4
|
#define BUFSIZE 4
|
||||||
|
#define CMDHDRSIZE 2
|
||||||
|
|
||||||
|
|
||||||
// Firmware based and LCD controlled retract
|
// Firmware based and LCD controlled retract
|
||||||
|
@ -413,6 +414,12 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
#define THERMISTORBED TEMP_SENSOR_BED
|
#define THERMISTORBED TEMP_SENSOR_BED
|
||||||
#define BED_USES_THERMISTOR
|
#define BED_USES_THERMISTOR
|
||||||
#endif
|
#endif
|
||||||
|
#if TEMP_SENSOR_PINDA > 0
|
||||||
|
#define THERMISTORPINDA TEMP_SENSOR_PINDA
|
||||||
|
#endif
|
||||||
|
#if TEMP_SENSOR_AMBIENT > 0
|
||||||
|
#define THERMISTORAMBIENT TEMP_SENSOR_AMBIENT
|
||||||
|
#endif
|
||||||
#if TEMP_SENSOR_0 == -1
|
#if TEMP_SENSOR_0 == -1
|
||||||
#define HEATER_0_USES_AD595
|
#define HEATER_0_USES_AD595
|
||||||
#endif
|
#endif
|
||||||
|
|
485
Firmware/Configuration_prusa.h
Normal file
485
Firmware/Configuration_prusa.h
Normal file
|
@ -0,0 +1,485 @@
|
||||||
|
#ifndef CONFIGURATION_PRUSA_H
|
||||||
|
#define CONFIGURATION_PRUSA_H
|
||||||
|
|
||||||
|
/*------------------------------------
|
||||||
|
GENERAL SETTINGS
|
||||||
|
*------------------------------------*/
|
||||||
|
|
||||||
|
// Printer revision
|
||||||
|
#define FILAMENT_SIZE "1_75mm_MK3"
|
||||||
|
#define NOZZLE_TYPE "E3Dv6full"
|
||||||
|
|
||||||
|
// Developer flag
|
||||||
|
#define DEVELOPER
|
||||||
|
|
||||||
|
// Printer name
|
||||||
|
#define CUSTOM_MENDEL_NAME "Prusa i3 MK3"
|
||||||
|
|
||||||
|
// Electronics
|
||||||
|
#define MOTHERBOARD BOARD_EINY_0_4a
|
||||||
|
|
||||||
|
|
||||||
|
// Uncomment the below for the E3D PT100 temperature sensor (with or without PT100 Amplifier)
|
||||||
|
//#define E3D_PT100_EXTRUDER_WITH_AMP
|
||||||
|
//#define E3D_PT100_EXTRUDER_NO_AMP
|
||||||
|
//#define E3D_PT100_BED_WITH_AMP
|
||||||
|
//#define E3D_PT100_BED_NO_AMP
|
||||||
|
|
||||||
|
|
||||||
|
/*------------------------------------
|
||||||
|
AXIS SETTINGS
|
||||||
|
*------------------------------------*/
|
||||||
|
|
||||||
|
// Steps per unit {X,Y,Z,E}
|
||||||
|
//#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,140}
|
||||||
|
#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,280}
|
||||||
|
|
||||||
|
// Endstop inverting
|
||||||
|
const bool X_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||||
|
const bool Y_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||||
|
const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||||
|
|
||||||
|
// Home position
|
||||||
|
#define MANUAL_X_HOME_POS 0
|
||||||
|
#define MANUAL_Y_HOME_POS -2.2
|
||||||
|
#define MANUAL_Z_HOME_POS 0.2
|
||||||
|
|
||||||
|
// Travel limits after homing
|
||||||
|
#define X_MAX_POS 255
|
||||||
|
#define X_MIN_POS 0
|
||||||
|
#define Y_MAX_POS 210
|
||||||
|
#define Y_MIN_POS -12 //orig -4
|
||||||
|
#define Z_MAX_POS 210
|
||||||
|
#define Z_MIN_POS 0.15
|
||||||
|
|
||||||
|
// Canceled home position
|
||||||
|
#define X_CANCEL_POS 50
|
||||||
|
#define Y_CANCEL_POS 190
|
||||||
|
|
||||||
|
//Pause print position
|
||||||
|
#define X_PAUSE_POS 50
|
||||||
|
#define Y_PAUSE_POS 190
|
||||||
|
#define Z_PAUSE_LIFT 20
|
||||||
|
|
||||||
|
#define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
|
||||||
|
#define HOMING_FEEDRATE {3000, 3000, 800, 0} // set the homing speeds (mm/min) // 3000 is also valid for stallGuard homing. Valid range: 2200 - 3000
|
||||||
|
|
||||||
|
//#define DEFAULT_MAX_FEEDRATE {400, 400, 12, 120} // (mm/sec)
|
||||||
|
#define DEFAULT_MAX_FEEDRATE {500, 500, 12, 120} // (mm/sec)
|
||||||
|
#define DEFAULT_MAX_ACCELERATION {1000, 1000, 200, 5000} // 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 1250 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
|
||||||
|
#define DEFAULT_RETRACT_ACCELERATION 1250 // X, Y, Z and E max acceleration in mm/s^2 for retracts
|
||||||
|
|
||||||
|
#define MANUAL_FEEDRATE {2700, 2700, 1000, 100} // set the speeds for manual moves (mm/min)
|
||||||
|
//#define MAX_SILENT_FEEDRATE 2700 //
|
||||||
|
|
||||||
|
#define Z_AXIS_ALWAYS_ON 1
|
||||||
|
|
||||||
|
//DEBUG
|
||||||
|
#define DEBUG_DCODES //D codes
|
||||||
|
#if 0
|
||||||
|
#define DEBUG_DISABLE_XMINLIMIT //x min limit ignored
|
||||||
|
#define DEBUG_DISABLE_XMAXLIMIT //x max limit ignored
|
||||||
|
#define DEBUG_DISABLE_YMINLIMIT //y min limit ignored
|
||||||
|
#define DEBUG_DISABLE_YMAXLIMIT //y max limit ignored
|
||||||
|
#define DEBUG_DISABLE_ZMINLIMIT //z min limit ignored
|
||||||
|
#define DEBUG_DISABLE_ZMAXLIMIT //z max limit ignored
|
||||||
|
#define DEBUG_DISABLE_STARTMSGS //no startup messages
|
||||||
|
#define DEBUG_DISABLE_MINTEMP //mintemp error ignored
|
||||||
|
#define DEBUG_DISABLE_SWLIMITS //sw limits ignored
|
||||||
|
#define DEBUG_DISABLE_LCD_STATUS_LINE //empty four lcd line
|
||||||
|
#define DEBUG_DISABLE_PREVENT_EXTRUDER //cold extrusion and long extrusion allowed
|
||||||
|
#define DEBUG_DISABLE_PRUSA_STATISTICS //disable prusa_statistics() mesages
|
||||||
|
//#define DEBUG_XSTEP_DUP_PIN 21 //duplicate x-step output to pin 21 (SCL on P3)
|
||||||
|
//#define DEBUG_YSTEP_DUP_PIN 21 //duplicate y-step output to pin 21 (SCL on P3)
|
||||||
|
//#define DEBUG_BLINK_ACTIVE
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/*------------------------------------
|
||||||
|
TMC2130 default settings
|
||||||
|
*------------------------------------*/
|
||||||
|
|
||||||
|
#define TMC2130_FCLK 12000000 // fclk = 12MHz
|
||||||
|
|
||||||
|
#define TMC2130_USTEPS_XY 16 // microstep resolution for XY axes
|
||||||
|
#define TMC2130_USTEPS_Z 16 // microstep resolution for Z axis
|
||||||
|
#define TMC2130_USTEPS_E 32 // microstep resolution for E axis
|
||||||
|
#define TMC2130_INTPOL_XY 1 // extrapolate 256 for XY axes
|
||||||
|
#define TMC2130_INTPOL_Z 1 // extrapolate 256 for Z axis
|
||||||
|
#define TMC2130_INTPOL_E 1 // extrapolate 256 for E axis
|
||||||
|
|
||||||
|
#define TMC2130_PWM_GRAD_X 4 // PWMCONF
|
||||||
|
#define TMC2130_PWM_AMPL_X 200 // PWMCONF
|
||||||
|
#define TMC2130_PWM_AUTO_X 1 // PWMCONF
|
||||||
|
#define TMC2130_PWM_FREQ_X 2 // PWMCONF
|
||||||
|
|
||||||
|
#define TMC2130_PWM_GRAD_Y 4 // PWMCONF
|
||||||
|
#define TMC2130_PWM_AMPL_Y 210 // PWMCONF
|
||||||
|
#define TMC2130_PWM_AUTO_Y 1 // PWMCONF
|
||||||
|
#define TMC2130_PWM_FREQ_Y 2 // PWMCONF
|
||||||
|
|
||||||
|
/* //not used
|
||||||
|
#define TMC2130_PWM_GRAD_Z 4 // PWMCONF
|
||||||
|
#define TMC2130_PWM_AMPL_Z 200 // PWMCONF
|
||||||
|
#define TMC2130_PWM_AUTO_Z 1 // PWMCONF
|
||||||
|
#define TMC2130_PWM_FREQ_Z 2 // PWMCONF
|
||||||
|
#define TMC2130_PWM_GRAD_E 4 // PWMCONF
|
||||||
|
#define TMC2130_PWM_AMPL_E 200 // PWMCONF
|
||||||
|
#define TMC2130_PWM_AUTO_E 1 // PWMCONF
|
||||||
|
#define TMC2130_PWM_FREQ_E 2 // PWMCONF
|
||||||
|
*/
|
||||||
|
|
||||||
|
//#define TMC2130_PWM_DIV 683 // PWM frequency divider (1024, 683, 512, 410)
|
||||||
|
#define TMC2130_PWM_DIV 512 // PWM frequency divider (1024, 683, 512, 410)
|
||||||
|
#define TMC2130_PWM_CLK (2 * TMC2130_FCLK / TMC2130_PWM_DIV) // PWM frequency (23.4kHz, 35.1kHz, 46.9kHz, 58.5kHz for 12MHz fclk)
|
||||||
|
|
||||||
|
#define TMC2130_TPWMTHRS 0 // TPWMTHRS - Sets the switching speed threshold based on TSTEP from stealthChop to spreadCycle mode
|
||||||
|
#define TMC2130_THIGH 0 // THIGH - unused
|
||||||
|
|
||||||
|
#define TMC2130_TCOOLTHRS 239 // TCOOLTHRS - coolstep treshold
|
||||||
|
|
||||||
|
#define TMC2130_SG_HOMING 1 // stallguard homing
|
||||||
|
//#define TMC2130_SG_HOMING_SW_XY 1 // stallguard "software" homing for XY axes
|
||||||
|
#define TMC2130_SG_HOMING_SW_Z 1 // stallguard "software" homing for Z axis
|
||||||
|
#define TMC2130_SG_THRS_X 0 // stallguard sensitivity for X axis
|
||||||
|
#define TMC2130_SG_THRS_Y 0 // stallguard sensitivity for Y axis
|
||||||
|
#define TMC2130_SG_THRS_Z 2 // stallguard sensitivity for Z axis
|
||||||
|
#define TMC2130_SG_DELTA 128 // stallguard delta [usteps] (minimum usteps before stallguard readed - SW homing)
|
||||||
|
|
||||||
|
//new settings is possible for vsense = 1, running current value > 31 set vsense to zero and shift both currents by 1 bit right (Z axis only)
|
||||||
|
#define TMC2130_CURRENTS_H {3, 3, 5, 8} // default holding currents for all axes
|
||||||
|
#define TMC2130_CURRENTS_R {13, 13, 20, 20} // default running currents for all axes
|
||||||
|
|
||||||
|
//#define TMC2130_DEBUG
|
||||||
|
//#define TMC2130_DEBUG_WR
|
||||||
|
//#define TMC2130_DEBUG_RD
|
||||||
|
|
||||||
|
|
||||||
|
/*------------------------------------
|
||||||
|
EXTRUDER SETTINGS
|
||||||
|
*------------------------------------*/
|
||||||
|
|
||||||
|
// Mintemps
|
||||||
|
#define HEATER_0_MINTEMP 15
|
||||||
|
#define HEATER_1_MINTEMP 5
|
||||||
|
#define HEATER_2_MINTEMP 5
|
||||||
|
#define BED_MINTEMP 15
|
||||||
|
|
||||||
|
// Maxtemps
|
||||||
|
#if defined(E3D_PT100_EXTRUDER_WITH_AMP) || defined(E3D_PT100_EXTRUDER_NO_AMP)
|
||||||
|
#define HEATER_0_MAXTEMP 410
|
||||||
|
#else
|
||||||
|
#define HEATER_0_MAXTEMP 305
|
||||||
|
#endif
|
||||||
|
#define HEATER_1_MAXTEMP 305
|
||||||
|
#define HEATER_2_MAXTEMP 305
|
||||||
|
#define BED_MAXTEMP 150
|
||||||
|
|
||||||
|
#if defined(E3D_PT100_EXTRUDER_WITH_AMP) || defined(E3D_PT100_EXTRUDER_NO_AMP)
|
||||||
|
// Define PID constants for extruder with PT100
|
||||||
|
#define DEFAULT_Kp 21.70
|
||||||
|
#define DEFAULT_Ki 1.60
|
||||||
|
#define DEFAULT_Kd 73.76
|
||||||
|
#else
|
||||||
|
// Define PID constants for extruder
|
||||||
|
//#define DEFAULT_Kp 40.925
|
||||||
|
//#define DEFAULT_Ki 4.875
|
||||||
|
//#define DEFAULT_Kd 86.085
|
||||||
|
#define DEFAULT_Kp 16.13
|
||||||
|
#define DEFAULT_Ki 1.1625
|
||||||
|
#define DEFAULT_Kd 56.23
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Extrude mintemp
|
||||||
|
#define EXTRUDE_MINTEMP 130
|
||||||
|
|
||||||
|
// Extruder cooling fans
|
||||||
|
#define EXTRUDER_0_AUTO_FAN_PIN 8
|
||||||
|
#define EXTRUDER_1_AUTO_FAN_PIN -1
|
||||||
|
#define EXTRUDER_2_AUTO_FAN_PIN -1
|
||||||
|
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
|
||||||
|
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
/*------------------------------------
|
||||||
|
LOAD/UNLOAD FILAMENT SETTINGS
|
||||||
|
*------------------------------------*/
|
||||||
|
|
||||||
|
// Load filament commands
|
||||||
|
#define LOAD_FILAMENT_0 "M83"
|
||||||
|
#define LOAD_FILAMENT_1 "G1 E70 F400"
|
||||||
|
#define LOAD_FILAMENT_2 "G1 E40 F100"
|
||||||
|
|
||||||
|
// Unload filament commands
|
||||||
|
#define UNLOAD_FILAMENT_0 "M83"
|
||||||
|
#define UNLOAD_FILAMENT_1 "G1 E-80 F7000"
|
||||||
|
|
||||||
|
/*------------------------------------
|
||||||
|
CHANGE FILAMENT SETTINGS
|
||||||
|
*------------------------------------*/
|
||||||
|
|
||||||
|
// Filament change configuration
|
||||||
|
#define FILAMENTCHANGEENABLE
|
||||||
|
#ifdef FILAMENTCHANGEENABLE
|
||||||
|
#define FILAMENTCHANGE_XPOS 211
|
||||||
|
#define FILAMENTCHANGE_YPOS 0
|
||||||
|
#define FILAMENTCHANGE_ZADD 2
|
||||||
|
#define FILAMENTCHANGE_FIRSTRETRACT -2
|
||||||
|
#define FILAMENTCHANGE_FINALRETRACT -80
|
||||||
|
|
||||||
|
#define FILAMENTCHANGE_FIRSTFEED 70
|
||||||
|
#define FILAMENTCHANGE_FINALFEED 50
|
||||||
|
#define FILAMENTCHANGE_RECFEED 5
|
||||||
|
|
||||||
|
#define FILAMENTCHANGE_XYFEED 50
|
||||||
|
#define FILAMENTCHANGE_EFEED 20
|
||||||
|
#define FILAMENTCHANGE_RFEED 400
|
||||||
|
#define FILAMENTCHANGE_EXFEED 2
|
||||||
|
#define FILAMENTCHANGE_ZFEED 15
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/*------------------------------------
|
||||||
|
ADDITIONAL FEATURES SETTINGS
|
||||||
|
*------------------------------------*/
|
||||||
|
|
||||||
|
// Define Prusa filament runout sensor
|
||||||
|
//#define FILAMENT_RUNOUT_SUPPORT
|
||||||
|
|
||||||
|
#ifdef FILAMENT_RUNOUT_SUPPORT
|
||||||
|
#define FILAMENT_RUNOUT_SENSOR 1
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// temperature runaway
|
||||||
|
//#define TEMP_RUNAWAY_BED_HYSTERESIS 5
|
||||||
|
//#define TEMP_RUNAWAY_BED_TIMEOUT 360
|
||||||
|
|
||||||
|
#define TEMP_RUNAWAY_EXTRUDER_HYSTERESIS 15
|
||||||
|
#define TEMP_RUNAWAY_EXTRUDER_TIMEOUT 45
|
||||||
|
|
||||||
|
/*------------------------------------
|
||||||
|
MOTOR CURRENT SETTINGS
|
||||||
|
*------------------------------------*/
|
||||||
|
|
||||||
|
// Motor Current setting for BIG RAMBo
|
||||||
|
#define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
|
||||||
|
#define DIGIPOT_MOTOR_CURRENT_LOUD {135,135,135,135,135}
|
||||||
|
|
||||||
|
// Motor Current settings for RAMBo mini PWM value = MotorCurrentSetting * 255 / range
|
||||||
|
#if MOTHERBOARD == 200 || MOTHERBOARD == 203 || MOTHERBOARD == 303 || MOTHERBOARD == 304 || MOTHERBOARD == 305
|
||||||
|
#define MOTOR_CURRENT_PWM_RANGE 2000
|
||||||
|
#define DEFAULT_PWM_MOTOR_CURRENT {400, 750, 750} // {XY,Z,E}
|
||||||
|
#define DEFAULT_PWM_MOTOR_CURRENT_LOUD {400, 750, 750} // {XY,Z,E}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/*------------------------------------
|
||||||
|
BED SETTINGS
|
||||||
|
*------------------------------------*/
|
||||||
|
|
||||||
|
// Define Mesh Bed Leveling system to enable it
|
||||||
|
#define MESH_BED_LEVELING
|
||||||
|
#ifdef MESH_BED_LEVELING
|
||||||
|
|
||||||
|
#define MBL_Z_STEP 0.01
|
||||||
|
|
||||||
|
// Mesh definitions
|
||||||
|
#define MESH_MIN_X 35
|
||||||
|
#define MESH_MAX_X 238
|
||||||
|
#define MESH_MIN_Y 6
|
||||||
|
#define MESH_MAX_Y 202
|
||||||
|
|
||||||
|
// Mesh upsample definition
|
||||||
|
#define MESH_NUM_X_POINTS 7
|
||||||
|
#define MESH_NUM_Y_POINTS 7
|
||||||
|
// Mesh measure definition
|
||||||
|
#define MESH_MEAS_NUM_X_POINTS 3
|
||||||
|
#define MESH_MEAS_NUM_Y_POINTS 3
|
||||||
|
|
||||||
|
#define MESH_HOME_Z_CALIB 0.2
|
||||||
|
#define MESH_HOME_Z_SEARCH 5 //Z lift for homing, mesh bed leveling etc.
|
||||||
|
|
||||||
|
#define X_PROBE_OFFSET_FROM_EXTRUDER 23 // Z probe to nozzle X offset: -left +right
|
||||||
|
#define Y_PROBE_OFFSET_FROM_EXTRUDER 9 // Z probe to nozzle Y offset: -front +behind
|
||||||
|
#define Z_PROBE_OFFSET_FROM_EXTRUDER -0.4 // Z probe to nozzle Z offset: -below (always!)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// 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 frequency 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 probably
|
||||||
|
// shouldn't use bed PID until someone else verifies your hardware works.
|
||||||
|
// If this is enabled, find your own PID constants below.
|
||||||
|
#define PIDTEMPBED
|
||||||
|
//
|
||||||
|
//#define BED_LIMIT_SWITCHING
|
||||||
|
|
||||||
|
// This sets the max power delivered to the bed, and replaces the HEATER_BED_DUTY_CYCLE_DIVIDER option.
|
||||||
|
// all forms of bed control obey this (PID, bang-bang, bang-bang with hysteresis)
|
||||||
|
// setting this to anything other than 255 enables a form of PWM to the bed just like HEATER_BED_DUTY_CYCLE_DIVIDER did,
|
||||||
|
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
|
||||||
|
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
|
||||||
|
|
||||||
|
// Bed temperature compensation settings
|
||||||
|
#define BED_OFFSET 10
|
||||||
|
#define BED_OFFSET_START 40
|
||||||
|
#define BED_OFFSET_CENTER 50
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef PIDTEMPBED
|
||||||
|
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
||||||
|
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
|
||||||
|
#if defined(E3D_PT100_BED_WITH_AMP) || defined(E3D_PT100_BED_NO_AMP)
|
||||||
|
// Define PID constants for extruder with PT100
|
||||||
|
#define DEFAULT_bedKp 21.70
|
||||||
|
#define DEFAULT_bedKi 1.60
|
||||||
|
#define DEFAULT_bedKd 73.76
|
||||||
|
#else
|
||||||
|
#define DEFAULT_bedKp 126.13
|
||||||
|
#define DEFAULT_bedKi 4.30
|
||||||
|
#define DEFAULT_bedKd 924.76
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
||||||
|
//from pidautotune
|
||||||
|
// #define DEFAULT_bedKp 97.1
|
||||||
|
// #define DEFAULT_bedKi 1.41
|
||||||
|
// #define DEFAULT_bedKd 1675.16
|
||||||
|
|
||||||
|
// FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles.
|
||||||
|
#endif // PIDTEMPBED
|
||||||
|
|
||||||
|
|
||||||
|
/*-----------------------------------
|
||||||
|
PREHEAT SETTINGS
|
||||||
|
*------------------------------------*/
|
||||||
|
|
||||||
|
#define PLA_PREHEAT_HOTEND_TEMP 215
|
||||||
|
#define PLA_PREHEAT_HPB_TEMP 55
|
||||||
|
#define PLA_PREHEAT_FAN_SPEED 0
|
||||||
|
|
||||||
|
#define ABS_PREHEAT_HOTEND_TEMP 255
|
||||||
|
#define ABS_PREHEAT_HPB_TEMP 100
|
||||||
|
#define ABS_PREHEAT_FAN_SPEED 0
|
||||||
|
|
||||||
|
#define HIPS_PREHEAT_HOTEND_TEMP 220
|
||||||
|
#define HIPS_PREHEAT_HPB_TEMP 100
|
||||||
|
#define HIPS_PREHEAT_FAN_SPEED 0
|
||||||
|
|
||||||
|
#define PP_PREHEAT_HOTEND_TEMP 254
|
||||||
|
#define PP_PREHEAT_HPB_TEMP 100
|
||||||
|
#define PP_PREHEAT_FAN_SPEED 0
|
||||||
|
|
||||||
|
#define PET_PREHEAT_HOTEND_TEMP 240
|
||||||
|
#define PET_PREHEAT_HPB_TEMP 90
|
||||||
|
#define PET_PREHEAT_FAN_SPEED 0
|
||||||
|
|
||||||
|
#define FLEX_PREHEAT_HOTEND_TEMP 230
|
||||||
|
#define FLEX_PREHEAT_HPB_TEMP 50
|
||||||
|
#define FLEX_PREHEAT_FAN_SPEED 0
|
||||||
|
|
||||||
|
/*------------------------------------
|
||||||
|
THERMISTORS SETTINGS
|
||||||
|
*------------------------------------*/
|
||||||
|
|
||||||
|
//
|
||||||
|
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
|
||||||
|
//
|
||||||
|
//// Temperature sensor settings:
|
||||||
|
// -2 is thermocouple with MAX6675 (only for sensor 0)
|
||||||
|
// -1 is thermocouple with AD595
|
||||||
|
// 0 is not used
|
||||||
|
// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
|
||||||
|
// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
|
||||||
|
// 3 is Mendel-parts thermistor (4.7k pullup)
|
||||||
|
// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
|
||||||
|
// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
|
||||||
|
// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
|
||||||
|
// 7 is 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
|
||||||
|
// 71 is 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
|
||||||
|
// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
|
||||||
|
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
|
||||||
|
// 10 is 100k RS thermistor 198-961 (4.7k pullup)
|
||||||
|
// 11 is 100k beta 3950 1% thermistor (4.7k pullup)
|
||||||
|
// 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
|
||||||
|
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
|
||||||
|
// 20 is the PT100 circuit found in the Ultimainboard V2.x
|
||||||
|
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
|
||||||
|
//
|
||||||
|
// 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)
|
||||||
|
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
|
||||||
|
//
|
||||||
|
// 1047 is Pt1000 with 4k7 pullup
|
||||||
|
// 1010 is Pt1000 with 1k pullup (non standard)
|
||||||
|
// 147 is Pt100 with 4k7 pullup
|
||||||
|
// 148 is E3D Pt100 with 4k7 pullup and no PT100 Amplifier on a MiniRambo 1.3a
|
||||||
|
// 247 is Pt100 with 4k7 pullup and PT100 Amplifier
|
||||||
|
// 110 is Pt100 with 1k pullup (non standard)
|
||||||
|
|
||||||
|
#if defined(E3D_PT100_EXTRUDER_WITH_AMP)
|
||||||
|
#define TEMP_SENSOR_0 247
|
||||||
|
#elif defined(E3D_PT100_EXTRUDER_NO_AMP)
|
||||||
|
#define TEMP_SENSOR_0 148
|
||||||
|
#else
|
||||||
|
#define TEMP_SENSOR_0 5
|
||||||
|
#endif
|
||||||
|
#define TEMP_SENSOR_1 0
|
||||||
|
#define TEMP_SENSOR_2 0
|
||||||
|
#if defined(E3D_PT100_BED_WITH_AMP)
|
||||||
|
#define TEMP_SENSOR_BED 247
|
||||||
|
#elif defined(E3D_PT100_BED_NO_AMP)
|
||||||
|
#define TEMP_SENSOR_BED 148
|
||||||
|
#else
|
||||||
|
#define TEMP_SENSOR_BED 1
|
||||||
|
#endif
|
||||||
|
#define TEMP_SENSOR_PINDA 1
|
||||||
|
#define TEMP_SENSOR_AMBIENT 2000
|
||||||
|
|
||||||
|
#define STACK_GUARD_TEST_VALUE 0xA2A2
|
||||||
|
|
||||||
|
#define MAX_BED_TEMP_CALIBRATION 50
|
||||||
|
#define MAX_HOTEND_TEMP_CALIBRATION 50
|
||||||
|
|
||||||
|
#define MAX_E_STEPS_PER_UNIT 250
|
||||||
|
#define MIN_E_STEPS_PER_UNIT 100
|
||||||
|
|
||||||
|
#define Z_BABYSTEP_MIN -3999
|
||||||
|
#define Z_BABYSTEP_MAX 0
|
||||||
|
|
||||||
|
#define PINDA_PREHEAT_X 70
|
||||||
|
#define PINDA_PREHEAT_Y -3
|
||||||
|
#define PINDA_PREHEAT_Z 1
|
||||||
|
#define PINDA_HEAT_T 120 //time in s
|
||||||
|
|
||||||
|
#define PINDA_MIN_T 50
|
||||||
|
#define PINDA_STEP_T 10
|
||||||
|
#define PINDA_MAX_T 100
|
||||||
|
|
||||||
|
#define PING_TIME 60 //time in s
|
||||||
|
#define PING_TIME_LONG 600 //10 min; used when length of commands buffer > 0 to avoid false triggering when dealing with long gcodes
|
||||||
|
#define PING_ALLERT_PERIOD 60 //time in s
|
||||||
|
|
||||||
|
#define LONG_PRESS_TIME 1000 //time in ms for button long press
|
||||||
|
#define BUTTON_BLANKING_TIME 200 //time in ms for blanking after button release
|
||||||
|
|
||||||
|
#define DEFAULT_PID_TEMP 210
|
||||||
|
|
||||||
|
#define MIN_PRINT_FAN_SPEED 50
|
||||||
|
|
||||||
|
#ifdef SNMM
|
||||||
|
#define DEFAULT_RETRACTION 4 //used for PINDA temp calibration and pause print
|
||||||
|
#else
|
||||||
|
#define DEFAULT_RETRACTION 1 //used for PINDA temp calibration and pause print
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define UVLO_Z_AXIS_SHIFT 2
|
||||||
|
|
||||||
|
#endif //__CONFIGURATION_PRUSA_H
|
192
Firmware/Dcodes.cpp
Normal file
192
Firmware/Dcodes.cpp
Normal file
|
@ -0,0 +1,192 @@
|
||||||
|
#include "Dcodes.h"
|
||||||
|
#include "Marlin.h"
|
||||||
|
#include "cmdqueue.h"
|
||||||
|
|
||||||
|
inline void serial_print_hex_nibble(uint8_t val)
|
||||||
|
{
|
||||||
|
MYSERIAL.write((val > 9)?(val - 10 + 'a'):(val + '0'));
|
||||||
|
}
|
||||||
|
|
||||||
|
void serial_print_hex_byte(uint8_t val)
|
||||||
|
{
|
||||||
|
serial_print_hex_nibble(val >> 4);
|
||||||
|
serial_print_hex_nibble(val & 15);
|
||||||
|
}
|
||||||
|
|
||||||
|
void serial_print_hex_word(uint16_t val)
|
||||||
|
{
|
||||||
|
serial_print_hex_byte(val >> 8);
|
||||||
|
serial_print_hex_byte(val & 255);
|
||||||
|
}
|
||||||
|
|
||||||
|
int parse_hex(char* hex, uint8_t* data, int count)
|
||||||
|
{
|
||||||
|
int parsed = 0;
|
||||||
|
while (*hex)
|
||||||
|
{
|
||||||
|
if (count && (parsed >= count)) break;
|
||||||
|
char c = *(hex++);
|
||||||
|
if (c == ' ') continue;
|
||||||
|
if (c == '\n') break;
|
||||||
|
uint8_t val = 0x00;
|
||||||
|
if ((c >= '0') && (c <= '9')) val |= ((c - '0') << 4);
|
||||||
|
else if ((c >= 'a') && (c <= 'f')) val |= ((c - 'a' + 10) << 4);
|
||||||
|
else return -parsed;
|
||||||
|
c = *(hex++);
|
||||||
|
if ((c >= '0') && (c <= '9')) val |= (c - '0');
|
||||||
|
else if ((c >= 'a') && (c <= 'f')) val |= (c - 'a' + 10);
|
||||||
|
else return -parsed;
|
||||||
|
data[parsed] = val;
|
||||||
|
parsed++;
|
||||||
|
}
|
||||||
|
return parsed;
|
||||||
|
}
|
||||||
|
|
||||||
|
void dcode_0()
|
||||||
|
{
|
||||||
|
if (*(strchr_pointer + 1) == 0) return;
|
||||||
|
MYSERIAL.println("D0 - Reset");
|
||||||
|
if (code_seen('B')) //bootloader
|
||||||
|
asm volatile("jmp 0x1e000");
|
||||||
|
else //reset
|
||||||
|
asm volatile("jmp 0x00000");
|
||||||
|
/*
|
||||||
|
cli(); //disable interrupts
|
||||||
|
wdt_reset(); //reset watchdog
|
||||||
|
WDTCSR = (1<<WDCE) | (1<<WDE); //enable watchdog
|
||||||
|
WDTCSR = (1<<WDE) | (1<<WDP0); //30ms prescaler
|
||||||
|
while(1); //wait for reset
|
||||||
|
*/
|
||||||
|
}
|
||||||
|
|
||||||
|
void dcode_1()
|
||||||
|
{
|
||||||
|
MYSERIAL.println("D1 - Clear EEPROM");
|
||||||
|
cli();
|
||||||
|
for (int i = 0; i < 4096; i++)
|
||||||
|
eeprom_write_byte((unsigned char*)i, (unsigned char)0);
|
||||||
|
sei();
|
||||||
|
}
|
||||||
|
|
||||||
|
void dcode_2()
|
||||||
|
{
|
||||||
|
MYSERIAL.println("D2 - Read/Write RAM");
|
||||||
|
uint16_t address = 0x0000; //default 0x0000
|
||||||
|
uint16_t count = 0x2000; //default 0x2000 (entire ram)
|
||||||
|
if (code_seen('A')) // Address (0x0000-0x1fff)
|
||||||
|
address = (strchr_pointer[1] == 'x')?strtol(strchr_pointer + 2, 0, 16):(int)code_value();
|
||||||
|
if (code_seen('C')) // Count (0x0001-0x2000)
|
||||||
|
count = (int)code_value();
|
||||||
|
address &= 0x1fff;
|
||||||
|
if (count > 0x2000) count = 0x2000;
|
||||||
|
if ((address + count) > 0x2000) count = 0x2000 - address;
|
||||||
|
if (code_seen('X')) // Data
|
||||||
|
{
|
||||||
|
uint8_t data[16];
|
||||||
|
count = parse_hex(strchr_pointer + 1, data, 16);
|
||||||
|
if (count > 0)
|
||||||
|
{
|
||||||
|
for (int i = 0; i < count; i++)
|
||||||
|
*((uint8_t*)(address + i)) = data[i];
|
||||||
|
MYSERIAL.print(count, DEC);
|
||||||
|
MYSERIAL.println(" bytes written to RAM at addres ");
|
||||||
|
serial_print_hex_word(address);
|
||||||
|
MYSERIAL.write('\n');
|
||||||
|
}
|
||||||
|
else
|
||||||
|
count = 0;
|
||||||
|
}
|
||||||
|
while (count)
|
||||||
|
{
|
||||||
|
serial_print_hex_word(address);
|
||||||
|
MYSERIAL.write(' ');
|
||||||
|
uint8_t countperline = 16;
|
||||||
|
while (count && countperline)
|
||||||
|
{
|
||||||
|
uint8_t data = *((uint8_t*)address++);
|
||||||
|
MYSERIAL.write(' ');
|
||||||
|
serial_print_hex_byte(data);
|
||||||
|
countperline--;
|
||||||
|
count--;
|
||||||
|
}
|
||||||
|
MYSERIAL.write('\n');
|
||||||
|
}
|
||||||
|
}
|
||||||
|
void dcode_3()
|
||||||
|
{
|
||||||
|
MYSERIAL.println("D3 - Read/Write EEPROM");
|
||||||
|
uint16_t address = 0x0000; //default 0x0000
|
||||||
|
uint16_t count = 0x2000; //default 0x2000 (entire eeprom)
|
||||||
|
if (code_seen('A')) // Address (0x0000-0x1fff)
|
||||||
|
address = (strchr_pointer[1] == 'x')?strtol(strchr_pointer + 2, 0, 16):(int)code_value();
|
||||||
|
if (code_seen('C')) // Count (0x0001-0x2000)
|
||||||
|
count = (int)code_value();
|
||||||
|
address &= 0x1fff;
|
||||||
|
if (count > 0x2000) count = 0x2000;
|
||||||
|
if ((address + count) > 0x2000) count = 0x2000 - address;
|
||||||
|
if (code_seen('X')) // Data
|
||||||
|
{
|
||||||
|
uint8_t data[16];
|
||||||
|
count = parse_hex(strchr_pointer + 1, data, 16);
|
||||||
|
if (count > 0)
|
||||||
|
{
|
||||||
|
for (int i = 0; i < count; i++)
|
||||||
|
eeprom_write_byte((uint8_t*)(address + i), data[i]);
|
||||||
|
MYSERIAL.print(count, DEC);
|
||||||
|
MYSERIAL.println(" bytes written to EEPROM at addres ");
|
||||||
|
serial_print_hex_word(address);
|
||||||
|
MYSERIAL.write('\n');
|
||||||
|
}
|
||||||
|
else
|
||||||
|
count = 0;
|
||||||
|
}
|
||||||
|
while (count)
|
||||||
|
{
|
||||||
|
serial_print_hex_word(address);
|
||||||
|
MYSERIAL.write(' ');
|
||||||
|
uint8_t countperline = 16;
|
||||||
|
while (count && countperline)
|
||||||
|
{
|
||||||
|
uint8_t data = eeprom_read_byte((uint8_t*)address++);
|
||||||
|
MYSERIAL.write(' ');
|
||||||
|
serial_print_hex_byte(data);
|
||||||
|
countperline--;
|
||||||
|
count--;
|
||||||
|
}
|
||||||
|
MYSERIAL.write('\n');
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void dcode_4()
|
||||||
|
{
|
||||||
|
MYSERIAL.println("D4 - Read/Write PIN");
|
||||||
|
if (code_seen('P')) // Pin (0-255)
|
||||||
|
{
|
||||||
|
int pin = (int)code_value();
|
||||||
|
if ((pin >= 0) && (pin <= 255))
|
||||||
|
{
|
||||||
|
if (code_seen('F')) // Function in/out (0/1)
|
||||||
|
{
|
||||||
|
int fnc = (int)code_value();
|
||||||
|
if (fnc == 0) pinMode(pin, INPUT);
|
||||||
|
else if (fnc == 1) pinMode(pin, OUTPUT);
|
||||||
|
}
|
||||||
|
if (code_seen('V')) // Value (0/1)
|
||||||
|
{
|
||||||
|
int val = (int)code_value();
|
||||||
|
if (val == 0) digitalWrite(pin, LOW);
|
||||||
|
else if (val == 1) digitalWrite(pin, HIGH);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
int val = (digitalRead(pin) != LOW)?1:0;
|
||||||
|
MYSERIAL.print("PIN");
|
||||||
|
MYSERIAL.print(pin);
|
||||||
|
MYSERIAL.print("=");
|
||||||
|
MYSERIAL.println(val);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
11
Firmware/Dcodes.h
Normal file
11
Firmware/Dcodes.h
Normal file
|
@ -0,0 +1,11 @@
|
||||||
|
#ifndef DCODES_H
|
||||||
|
#define DCODES_H
|
||||||
|
|
||||||
|
extern void dcode_0();
|
||||||
|
extern void dcode_1();
|
||||||
|
extern void dcode_2();
|
||||||
|
extern void dcode_3();
|
||||||
|
extern void dcode_4();
|
||||||
|
|
||||||
|
|
||||||
|
#endif //DCODES_H
|
|
@ -269,6 +269,11 @@ extern void homeaxis(int axis);
|
||||||
extern unsigned char fanSpeedSoftPwm;
|
extern unsigned char fanSpeedSoftPwm;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if defined(LCD_PWM_PIN) && (LCD_PWM_PIN > -1)
|
||||||
|
extern unsigned char lcdSoftPwm;
|
||||||
|
extern unsigned char lcdBlinkDelay;
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifdef FILAMENT_SENSOR
|
#ifdef FILAMENT_SENSOR
|
||||||
extern float filament_width_nominal; //holds the theoretical filament diameter ie., 3.00 or 1.75
|
extern float filament_width_nominal; //holds the theoretical filament diameter ie., 3.00 or 1.75
|
||||||
extern bool filament_sensor; //indicates that filament sensor readings should control extrusion
|
extern bool filament_sensor; //indicates that filament sensor readings should control extrusion
|
||||||
|
@ -356,6 +361,11 @@ void bed_analysis(float x_dimension, float y_dimension, int x_points_num, int y_
|
||||||
float temp_comp_interpolation(float temperature);
|
float temp_comp_interpolation(float temperature);
|
||||||
void temp_compensation_apply();
|
void temp_compensation_apply();
|
||||||
void temp_compensation_start();
|
void temp_compensation_start();
|
||||||
|
|
||||||
|
#ifdef PINDA_THERMISTOR
|
||||||
|
float temp_compensation_pinda_thermistor_offset();
|
||||||
|
#endif //PINDA_THERMISTOR
|
||||||
|
|
||||||
void wait_for_heater(long codenum);
|
void wait_for_heater(long codenum);
|
||||||
void serialecho_temperatures();
|
void serialecho_temperatures();
|
||||||
|
|
||||||
|
|
|
@ -23,6 +23,8 @@
|
||||||
#include "Marlin.h"
|
#include "Marlin.h"
|
||||||
#include "MarlinSerial.h"
|
#include "MarlinSerial.h"
|
||||||
|
|
||||||
|
int selectedSerialPort = 0;
|
||||||
|
|
||||||
#ifndef AT90USB
|
#ifndef AT90USB
|
||||||
// this next line disables the entire HardwareSerial.cpp,
|
// this next line disables the entire HardwareSerial.cpp,
|
||||||
// this is so I can support Attiny series and any other chip without a UART
|
// this is so I can support Attiny series and any other chip without a UART
|
||||||
|
@ -64,6 +66,23 @@ FORCE_INLINE void store_char(unsigned char c)
|
||||||
store_char(c);
|
store_char(c);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
SIGNAL(USART2_RX_vect)
|
||||||
|
{
|
||||||
|
if (selectedSerialPort == 1) {
|
||||||
|
// Test for a framing error.
|
||||||
|
if (UCSR2A & (1<<FE2)) {
|
||||||
|
// Characters received with the framing errors will be ignored.
|
||||||
|
// The temporary variable "c" was made volatile, so the compiler does not optimize this out.
|
||||||
|
volatile unsigned char c = UDR2;
|
||||||
|
} else {
|
||||||
|
// Read the input register.
|
||||||
|
unsigned char c = UDR2;
|
||||||
|
store_char(c);
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Constructors ////////////////////////////////////////////////////////////////
|
// Constructors ////////////////////////////////////////////////////////////////
|
||||||
|
@ -88,7 +107,7 @@ void MarlinSerial::begin(long baud)
|
||||||
useU2X = false;
|
useU2X = false;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
// set up the first (original serial port)
|
||||||
if (useU2X) {
|
if (useU2X) {
|
||||||
M_UCSRxA = 1 << M_U2Xx;
|
M_UCSRxA = 1 << M_U2Xx;
|
||||||
baud_setting = (F_CPU / 4 / baud - 1) / 2;
|
baud_setting = (F_CPU / 4 / baud - 1) / 2;
|
||||||
|
@ -104,6 +123,24 @@ void MarlinSerial::begin(long baud)
|
||||||
sbi(M_UCSRxB, M_RXENx);
|
sbi(M_UCSRxB, M_RXENx);
|
||||||
sbi(M_UCSRxB, M_TXENx);
|
sbi(M_UCSRxB, M_TXENx);
|
||||||
sbi(M_UCSRxB, M_RXCIEx);
|
sbi(M_UCSRxB, M_RXCIEx);
|
||||||
|
|
||||||
|
|
||||||
|
// set up the second serial port
|
||||||
|
if (useU2X) {
|
||||||
|
UCSR2A = 1 << U2X2;
|
||||||
|
baud_setting = (F_CPU / 4 / baud - 1) / 2;
|
||||||
|
} else {
|
||||||
|
UCSR2A = 0;
|
||||||
|
baud_setting = (F_CPU / 8 / baud - 1) / 2;
|
||||||
|
}
|
||||||
|
|
||||||
|
// assign the baud_setting, a.k.a. ubbr (USART Baud Rate Register)
|
||||||
|
UBRR2H = baud_setting >> 8;
|
||||||
|
UBRR2L = baud_setting;
|
||||||
|
|
||||||
|
sbi(UCSR2B, RXEN2);
|
||||||
|
sbi(UCSR2B, TXEN2);
|
||||||
|
sbi(UCSR2B, RXCIE2);
|
||||||
}
|
}
|
||||||
|
|
||||||
void MarlinSerial::end()
|
void MarlinSerial::end()
|
||||||
|
@ -111,6 +148,10 @@ void MarlinSerial::end()
|
||||||
cbi(M_UCSRxB, M_RXENx);
|
cbi(M_UCSRxB, M_RXENx);
|
||||||
cbi(M_UCSRxB, M_TXENx);
|
cbi(M_UCSRxB, M_TXENx);
|
||||||
cbi(M_UCSRxB, M_RXCIEx);
|
cbi(M_UCSRxB, M_RXCIEx);
|
||||||
|
|
||||||
|
cbi(UCSR2B, RXEN2);
|
||||||
|
cbi(UCSR2B, TXEN2);
|
||||||
|
cbi(UCSR2B, RXCIE2);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -73,6 +73,7 @@
|
||||||
// is the index of the location from which to read.
|
// is the index of the location from which to read.
|
||||||
#define RX_BUFFER_SIZE 128
|
#define RX_BUFFER_SIZE 128
|
||||||
|
|
||||||
|
extern int selectedSerialPort;
|
||||||
|
|
||||||
struct ring_buffer
|
struct ring_buffer
|
||||||
{
|
{
|
||||||
|
@ -110,24 +111,48 @@ class MarlinSerial //: public Stream
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
FORCE_INLINE void checkRx(void)
|
void checkRx(void)
|
||||||
{
|
{
|
||||||
if((M_UCSRxA & (1<<M_RXCx)) != 0) {
|
if (selectedSerialPort == 0) {
|
||||||
// Test for a framing error.
|
if((M_UCSRxA & (1<<M_RXCx)) != 0) {
|
||||||
if (M_UCSRxA & (1<<M_FEx)) {
|
// Test for a framing error.
|
||||||
// Characters received with the framing errors will be ignored.
|
if (M_UCSRxA & (1<<M_FEx)) {
|
||||||
// The temporary variable "c" was made volatile, so the compiler does not optimize this out.
|
// Characters received with the framing errors will be ignored.
|
||||||
volatile unsigned char c = M_UDRx;
|
// The temporary variable "c" was made volatile, so the compiler does not optimize this out.
|
||||||
} else {
|
volatile unsigned char c = M_UDRx;
|
||||||
unsigned char c = M_UDRx;
|
} else {
|
||||||
int i = (unsigned int)(rx_buffer.head + 1) % RX_BUFFER_SIZE;
|
unsigned char c = M_UDRx;
|
||||||
// if we should be storing the received character into the location
|
int i = (unsigned int)(rx_buffer.head + 1) % RX_BUFFER_SIZE;
|
||||||
// just before the tail (meaning that the head would advance to the
|
// if we should be storing the received character into the location
|
||||||
// current location of the tail), we're about to overflow the buffer
|
// just before the tail (meaning that the head would advance to the
|
||||||
// and so we don't write the character or advance the head.
|
// current location of the tail), we're about to overflow the buffer
|
||||||
if (i != rx_buffer.tail) {
|
// and so we don't write the character or advance the head.
|
||||||
rx_buffer.buffer[rx_buffer.head] = c;
|
if (i != rx_buffer.tail) {
|
||||||
rx_buffer.head = i;
|
rx_buffer.buffer[rx_buffer.head] = c;
|
||||||
|
rx_buffer.head = i;
|
||||||
|
}
|
||||||
|
selectedSerialPort = 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
} else if(selectedSerialPort == 1) {
|
||||||
|
if((UCSR2A & (1<<RXC2)) != 0) {
|
||||||
|
// Test for a framing error.
|
||||||
|
if (UCSR2A & (1<<FE2)) {
|
||||||
|
// Characters received with the framing errors will be ignored.
|
||||||
|
// The temporary variable "c" was made volatile, so the compiler does not optimize this out.
|
||||||
|
volatile unsigned char c = UDR2;
|
||||||
|
} else {
|
||||||
|
unsigned char c = UDR2;
|
||||||
|
int i = (unsigned int)(rx_buffer.head + 1) % RX_BUFFER_SIZE;
|
||||||
|
// if we should be storing the received character into the location
|
||||||
|
// just before the tail (meaning that the head would advance to the
|
||||||
|
// current location of the tail), we're about to overflow the buffer
|
||||||
|
// and so we don't write the character or advance the head.
|
||||||
|
if (i != rx_buffer.tail) {
|
||||||
|
rx_buffer.buffer[rx_buffer.head] = c;
|
||||||
|
rx_buffer.head = i;
|
||||||
|
}
|
||||||
|
selectedSerialPort = 1;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
File diff suppressed because it is too large
Load diff
|
@ -3,15 +3,14 @@
|
||||||
|
|
||||||
#define BOARD_UNKNOWN -1
|
#define BOARD_UNKNOWN -1
|
||||||
|
|
||||||
#define BOARD_EINY_0_3a 300 // EINY 0.3a
|
#define BOARD_RAMBO 100 // Rambo - 100 (orig 301)
|
||||||
#define BOARD_EINY_0_4a 299 // EINY 0.4a
|
|
||||||
|
|
||||||
#define BOARD_RAMBO 301 // Rambo
|
#define BOARD_RAMBO_MINI_1_0 200 // Rambo-mini 1.0 - 200 (orig 102)
|
||||||
#define BOARD_RAMBO_MINI_1_3 302 // Rambo-mini 1.3
|
#define BOARD_RAMBO_MINI_1_3 203 // Rambo-mini 1.3 - 203 (orig 302)
|
||||||
#define BOARD_RAMBO_MINI_1_0 102 // Rambo-mini 1.0
|
|
||||||
|
|
||||||
|
#define BOARD_EINY_0_3a 303 // EINY 0.3a - 303 (orig 300)
|
||||||
#define BOARD_99 99 // This is in pins.h but...?
|
#define BOARD_EINY_0_4a 304 // EINY 0.4a - 304 (orig 299)
|
||||||
|
#define BOARD_EINY_0_5a 305 // EINY 0.5a - 305 (orig 298)
|
||||||
|
|
||||||
#define MB(board) (MOTHERBOARD==BOARD_##board)
|
#define MB(board) (MOTHERBOARD==BOARD_##board)
|
||||||
#define IS_RAMPS (MB(RAMPS_OLD) || MB(RAMPS_13_EFB) || MB(RAMPS_13_EEB) || MB(RAMPS_13_EFF) || MB(RAMPS_13_EEF))
|
#define IS_RAMPS (MB(RAMPS_OLD) || MB(RAMPS_13_EFB) || MB(RAMPS_13_EEB) || MB(RAMPS_13_EFF) || MB(RAMPS_13_EEF))
|
||||||
|
|
620
Firmware/cmdqueue.cpp
Normal file
620
Firmware/cmdqueue.cpp
Normal file
|
@ -0,0 +1,620 @@
|
||||||
|
#include "cmdqueue.h"
|
||||||
|
#include "cardreader.h"
|
||||||
|
#include "ultralcd.h"
|
||||||
|
|
||||||
|
extern bool Stopped;
|
||||||
|
|
||||||
|
// Reserve BUFSIZE lines of length MAX_CMD_SIZE plus CMDBUFFER_RESERVE_FRONT.
|
||||||
|
char cmdbuffer[BUFSIZE * (MAX_CMD_SIZE + 1) + CMDBUFFER_RESERVE_FRONT];
|
||||||
|
// Head of the circular buffer, where to read.
|
||||||
|
int bufindr = 0;
|
||||||
|
// Tail of the buffer, where to write.
|
||||||
|
int bufindw = 0;
|
||||||
|
// Number of lines in cmdbuffer.
|
||||||
|
int buflen = 0;
|
||||||
|
// Flag for processing the current command inside the main Arduino loop().
|
||||||
|
// If a new command was pushed to the front of a command buffer while
|
||||||
|
// processing another command, this replaces the command on the top.
|
||||||
|
// Therefore don't remove the command from the queue in the loop() function.
|
||||||
|
bool cmdbuffer_front_already_processed = false;
|
||||||
|
|
||||||
|
int serial_count = 0; //index of character read from serial line
|
||||||
|
boolean comment_mode = false;
|
||||||
|
char *strchr_pointer; // just a pointer to find chars in the command string like X, Y, Z, E, etc
|
||||||
|
|
||||||
|
unsigned long TimeSent = millis();
|
||||||
|
unsigned long TimeNow = millis();
|
||||||
|
|
||||||
|
long gcode_N = 0;
|
||||||
|
long gcode_LastN = 0;
|
||||||
|
long Stopped_gcode_LastN = 0;
|
||||||
|
|
||||||
|
|
||||||
|
// Pop the currently processed command from the queue.
|
||||||
|
// It is expected, that there is at least one command in the queue.
|
||||||
|
bool cmdqueue_pop_front()
|
||||||
|
{
|
||||||
|
if (buflen > 0) {
|
||||||
|
#ifdef CMDBUFFER_DEBUG
|
||||||
|
SERIAL_ECHOPGM("Dequeing ");
|
||||||
|
SERIAL_ECHO(cmdbuffer+bufindr+CMDHDRSIZE);
|
||||||
|
SERIAL_ECHOLNPGM("");
|
||||||
|
SERIAL_ECHOPGM("Old indices: buflen ");
|
||||||
|
SERIAL_ECHO(buflen);
|
||||||
|
SERIAL_ECHOPGM(", bufindr ");
|
||||||
|
SERIAL_ECHO(bufindr);
|
||||||
|
SERIAL_ECHOPGM(", bufindw ");
|
||||||
|
SERIAL_ECHO(bufindw);
|
||||||
|
SERIAL_ECHOPGM(", serial_count ");
|
||||||
|
SERIAL_ECHO(serial_count);
|
||||||
|
SERIAL_ECHOPGM(", bufsize ");
|
||||||
|
SERIAL_ECHO(sizeof(cmdbuffer));
|
||||||
|
SERIAL_ECHOLNPGM("");
|
||||||
|
#endif /* CMDBUFFER_DEBUG */
|
||||||
|
if (-- buflen == 0) {
|
||||||
|
// Empty buffer.
|
||||||
|
if (serial_count == 0)
|
||||||
|
// No serial communication is pending. Reset both pointers to zero.
|
||||||
|
bufindw = 0;
|
||||||
|
bufindr = bufindw;
|
||||||
|
} else {
|
||||||
|
// There is at least one ready line in the buffer.
|
||||||
|
// First skip the current command ID and iterate up to the end of the string.
|
||||||
|
// for (++ bufindr; cmdbuffer[bufindr] != 0; ++ bufindr) ;
|
||||||
|
for (bufindr += CMDHDRSIZE; cmdbuffer[bufindr] != 0; ++ bufindr) ;
|
||||||
|
// Second, skip the end of string null character and iterate until a nonzero command ID is found.
|
||||||
|
for (++ bufindr; bufindr < sizeof(cmdbuffer) && cmdbuffer[bufindr] == 0; ++ bufindr) ;
|
||||||
|
// If the end of the buffer was empty,
|
||||||
|
if (bufindr == sizeof(cmdbuffer)) {
|
||||||
|
// skip to the start and find the nonzero command.
|
||||||
|
for (bufindr = 0; cmdbuffer[bufindr] == 0; ++ bufindr) ;
|
||||||
|
}
|
||||||
|
#ifdef CMDBUFFER_DEBUG
|
||||||
|
SERIAL_ECHOPGM("New indices: buflen ");
|
||||||
|
SERIAL_ECHO(buflen);
|
||||||
|
SERIAL_ECHOPGM(", bufindr ");
|
||||||
|
SERIAL_ECHO(bufindr);
|
||||||
|
SERIAL_ECHOPGM(", bufindw ");
|
||||||
|
SERIAL_ECHO(bufindw);
|
||||||
|
SERIAL_ECHOPGM(", serial_count ");
|
||||||
|
SERIAL_ECHO(serial_count);
|
||||||
|
SERIAL_ECHOPGM(" new command on the top: ");
|
||||||
|
SERIAL_ECHO(cmdbuffer+bufindr+CMDHDRSIZE);
|
||||||
|
SERIAL_ECHOLNPGM("");
|
||||||
|
#endif /* CMDBUFFER_DEBUG */
|
||||||
|
}
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
void cmdqueue_reset()
|
||||||
|
{
|
||||||
|
while (cmdqueue_pop_front()) ;
|
||||||
|
}
|
||||||
|
|
||||||
|
// How long a string could be pushed to the front of the command queue?
|
||||||
|
// If yes, adjust bufindr to the new position, where the new command could be enqued.
|
||||||
|
// len_asked does not contain the zero terminator size.
|
||||||
|
bool cmdqueue_could_enqueue_front(int len_asked)
|
||||||
|
{
|
||||||
|
// MAX_CMD_SIZE has to accommodate the zero terminator.
|
||||||
|
if (len_asked >= MAX_CMD_SIZE)
|
||||||
|
return false;
|
||||||
|
// Remove the currently processed command from the queue.
|
||||||
|
if (! cmdbuffer_front_already_processed) {
|
||||||
|
cmdqueue_pop_front();
|
||||||
|
cmdbuffer_front_already_processed = true;
|
||||||
|
}
|
||||||
|
if (bufindr == bufindw && buflen > 0)
|
||||||
|
// Full buffer.
|
||||||
|
return false;
|
||||||
|
// Adjust the end of the write buffer based on whether a partial line is in the receive buffer.
|
||||||
|
int endw = (serial_count > 0) ? (bufindw + MAX_CMD_SIZE + 1) : bufindw;
|
||||||
|
if (bufindw < bufindr) {
|
||||||
|
int bufindr_new = bufindr - len_asked - (1 + CMDHDRSIZE);
|
||||||
|
// Simple case. There is a contiguous space between the write buffer and the read buffer.
|
||||||
|
if (endw <= bufindr_new) {
|
||||||
|
bufindr = bufindr_new;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
// Otherwise the free space is split between the start and end.
|
||||||
|
if (len_asked + (1 + CMDHDRSIZE) <= bufindr) {
|
||||||
|
// Could fit at the start.
|
||||||
|
bufindr -= len_asked + (1 + CMDHDRSIZE);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
int bufindr_new = sizeof(cmdbuffer) - len_asked - (1 + CMDHDRSIZE);
|
||||||
|
if (endw <= bufindr_new) {
|
||||||
|
memset(cmdbuffer, 0, bufindr);
|
||||||
|
bufindr = bufindr_new;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Could one enqueue a command of lenthg len_asked into the buffer,
|
||||||
|
// while leaving CMDBUFFER_RESERVE_FRONT at the start?
|
||||||
|
// If yes, adjust bufindw to the new position, where the new command could be enqued.
|
||||||
|
// len_asked does not contain the zero terminator size.
|
||||||
|
bool cmdqueue_could_enqueue_back(int len_asked)
|
||||||
|
{
|
||||||
|
// MAX_CMD_SIZE has to accommodate the zero terminator.
|
||||||
|
if (len_asked >= MAX_CMD_SIZE)
|
||||||
|
return false;
|
||||||
|
|
||||||
|
if (bufindr == bufindw && buflen > 0)
|
||||||
|
// Full buffer.
|
||||||
|
return false;
|
||||||
|
|
||||||
|
if (serial_count > 0) {
|
||||||
|
// If there is some data stored starting at bufindw, len_asked is certainly smaller than
|
||||||
|
// the allocated data buffer. Try to reserve a new buffer and to move the already received
|
||||||
|
// serial data.
|
||||||
|
// How much memory to reserve for the commands pushed to the front?
|
||||||
|
// End of the queue, when pushing to the end.
|
||||||
|
int endw = bufindw + len_asked + (1 + CMDHDRSIZE);
|
||||||
|
if (bufindw < bufindr)
|
||||||
|
// Simple case. There is a contiguous space between the write buffer and the read buffer.
|
||||||
|
return endw + CMDBUFFER_RESERVE_FRONT <= bufindr;
|
||||||
|
// Otherwise the free space is split between the start and end.
|
||||||
|
if (// Could one fit to the end, including the reserve?
|
||||||
|
endw + CMDBUFFER_RESERVE_FRONT <= sizeof(cmdbuffer) ||
|
||||||
|
// Could one fit to the end, and the reserve to the start?
|
||||||
|
(endw <= sizeof(cmdbuffer) && CMDBUFFER_RESERVE_FRONT <= bufindr))
|
||||||
|
return true;
|
||||||
|
// Could one fit both to the start?
|
||||||
|
if (len_asked + (1 + CMDHDRSIZE) + CMDBUFFER_RESERVE_FRONT <= bufindr) {
|
||||||
|
// Mark the rest of the buffer as used.
|
||||||
|
memset(cmdbuffer+bufindw, 0, sizeof(cmdbuffer)-bufindw);
|
||||||
|
// and point to the start.
|
||||||
|
bufindw = 0;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
// How much memory to reserve for the commands pushed to the front?
|
||||||
|
// End of the queue, when pushing to the end.
|
||||||
|
int endw = bufindw + len_asked + (1 + CMDHDRSIZE);
|
||||||
|
if (bufindw < bufindr)
|
||||||
|
// Simple case. There is a contiguous space between the write buffer and the read buffer.
|
||||||
|
return endw + CMDBUFFER_RESERVE_FRONT <= bufindr;
|
||||||
|
// Otherwise the free space is split between the start and end.
|
||||||
|
if (// Could one fit to the end, including the reserve?
|
||||||
|
endw + CMDBUFFER_RESERVE_FRONT <= sizeof(cmdbuffer) ||
|
||||||
|
// Could one fit to the end, and the reserve to the start?
|
||||||
|
(endw <= sizeof(cmdbuffer) && CMDBUFFER_RESERVE_FRONT <= bufindr))
|
||||||
|
return true;
|
||||||
|
// Could one fit both to the start?
|
||||||
|
if (len_asked + (1 + CMDHDRSIZE) + CMDBUFFER_RESERVE_FRONT <= bufindr) {
|
||||||
|
// Mark the rest of the buffer as used.
|
||||||
|
memset(cmdbuffer+bufindw, 0, sizeof(cmdbuffer)-bufindw);
|
||||||
|
// and point to the start.
|
||||||
|
bufindw = 0;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef CMDBUFFER_DEBUG
|
||||||
|
void cmdqueue_dump_to_serial_single_line(int nr, const char *p)
|
||||||
|
{
|
||||||
|
SERIAL_ECHOPGM("Entry nr: ");
|
||||||
|
SERIAL_ECHO(nr);
|
||||||
|
SERIAL_ECHOPGM(", type: ");
|
||||||
|
SERIAL_ECHO(int(*p));
|
||||||
|
SERIAL_ECHOPGM(", cmd: ");
|
||||||
|
SERIAL_ECHO(p+1);
|
||||||
|
SERIAL_ECHOLNPGM("");
|
||||||
|
}
|
||||||
|
|
||||||
|
void cmdqueue_dump_to_serial()
|
||||||
|
{
|
||||||
|
if (buflen == 0) {
|
||||||
|
SERIAL_ECHOLNPGM("The command buffer is empty.");
|
||||||
|
} else {
|
||||||
|
SERIAL_ECHOPGM("Content of the buffer: entries ");
|
||||||
|
SERIAL_ECHO(buflen);
|
||||||
|
SERIAL_ECHOPGM(", indr ");
|
||||||
|
SERIAL_ECHO(bufindr);
|
||||||
|
SERIAL_ECHOPGM(", indw ");
|
||||||
|
SERIAL_ECHO(bufindw);
|
||||||
|
SERIAL_ECHOLNPGM("");
|
||||||
|
int nr = 0;
|
||||||
|
if (bufindr < bufindw) {
|
||||||
|
for (const char *p = cmdbuffer + bufindr; p < cmdbuffer + bufindw; ++ nr) {
|
||||||
|
cmdqueue_dump_to_serial_single_line(nr, p);
|
||||||
|
// Skip the command.
|
||||||
|
for (++p; *p != 0; ++ p);
|
||||||
|
// Skip the gaps.
|
||||||
|
for (++p; p < cmdbuffer + bufindw && *p == 0; ++ p);
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
for (const char *p = cmdbuffer + bufindr; p < cmdbuffer + sizeof(cmdbuffer); ++ nr) {
|
||||||
|
cmdqueue_dump_to_serial_single_line(nr, p);
|
||||||
|
// Skip the command.
|
||||||
|
for (++p; *p != 0; ++ p);
|
||||||
|
// Skip the gaps.
|
||||||
|
for (++p; p < cmdbuffer + sizeof(cmdbuffer) && *p == 0; ++ p);
|
||||||
|
}
|
||||||
|
for (const char *p = cmdbuffer; p < cmdbuffer + bufindw; ++ nr) {
|
||||||
|
cmdqueue_dump_to_serial_single_line(nr, p);
|
||||||
|
// Skip the command.
|
||||||
|
for (++p; *p != 0; ++ p);
|
||||||
|
// Skip the gaps.
|
||||||
|
for (++p; p < cmdbuffer + bufindw && *p == 0; ++ p);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
SERIAL_ECHOLNPGM("End of the buffer.");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif /* CMDBUFFER_DEBUG */
|
||||||
|
|
||||||
|
//adds an command to the main command buffer
|
||||||
|
//thats really done in a non-safe way.
|
||||||
|
//needs overworking someday
|
||||||
|
// Currently the maximum length of a command piped through this function is around 20 characters
|
||||||
|
void enquecommand(const char *cmd, bool from_progmem)
|
||||||
|
{
|
||||||
|
int len = from_progmem ? strlen_P(cmd) : strlen(cmd);
|
||||||
|
// Does cmd fit the queue while leaving sufficient space at the front for the chained commands?
|
||||||
|
// If it fits, it may move bufindw, so it points to a contiguous buffer, which fits cmd.
|
||||||
|
if (cmdqueue_could_enqueue_back(len)) {
|
||||||
|
// This is dangerous if a mixing of serial and this happens
|
||||||
|
// This may easily be tested: If serial_count > 0, we have a problem.
|
||||||
|
cmdbuffer[bufindw] = CMDBUFFER_CURRENT_TYPE_UI;
|
||||||
|
if (from_progmem)
|
||||||
|
strcpy_P(cmdbuffer + bufindw + CMDHDRSIZE, cmd);
|
||||||
|
else
|
||||||
|
strcpy(cmdbuffer + bufindw + CMDHDRSIZE, cmd);
|
||||||
|
SERIAL_ECHO_START;
|
||||||
|
SERIAL_ECHORPGM(MSG_Enqueing);
|
||||||
|
SERIAL_ECHO(cmdbuffer + bufindw + CMDHDRSIZE);
|
||||||
|
SERIAL_ECHOLNPGM("\"");
|
||||||
|
bufindw += len + (CMDHDRSIZE + 1);
|
||||||
|
if (bufindw == sizeof(cmdbuffer))
|
||||||
|
bufindw = 0;
|
||||||
|
++ buflen;
|
||||||
|
#ifdef CMDBUFFER_DEBUG
|
||||||
|
cmdqueue_dump_to_serial();
|
||||||
|
#endif /* CMDBUFFER_DEBUG */
|
||||||
|
} else {
|
||||||
|
SERIAL_ERROR_START;
|
||||||
|
SERIAL_ECHORPGM(MSG_Enqueing);
|
||||||
|
if (from_progmem)
|
||||||
|
SERIAL_PROTOCOLRPGM(cmd);
|
||||||
|
else
|
||||||
|
SERIAL_ECHO(cmd);
|
||||||
|
SERIAL_ECHOLNPGM("\" failed: Buffer full!");
|
||||||
|
#ifdef CMDBUFFER_DEBUG
|
||||||
|
cmdqueue_dump_to_serial();
|
||||||
|
#endif /* CMDBUFFER_DEBUG */
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void enquecommand_front(const char *cmd, bool from_progmem)
|
||||||
|
{
|
||||||
|
int len = from_progmem ? strlen_P(cmd) : strlen(cmd);
|
||||||
|
// Does cmd fit the queue? This call shall move bufindr, so the command may be copied.
|
||||||
|
if (cmdqueue_could_enqueue_front(len)) {
|
||||||
|
cmdbuffer[bufindr] = CMDBUFFER_CURRENT_TYPE_UI;
|
||||||
|
if (from_progmem)
|
||||||
|
strcpy_P(cmdbuffer + bufindr + CMDHDRSIZE, cmd);
|
||||||
|
else
|
||||||
|
strcpy(cmdbuffer + bufindr + CMDHDRSIZE, cmd);
|
||||||
|
++ buflen;
|
||||||
|
SERIAL_ECHO_START;
|
||||||
|
SERIAL_ECHOPGM("Enqueing to the front: \"");
|
||||||
|
SERIAL_ECHO(cmdbuffer + bufindr + CMDHDRSIZE);
|
||||||
|
SERIAL_ECHOLNPGM("\"");
|
||||||
|
#ifdef CMDBUFFER_DEBUG
|
||||||
|
cmdqueue_dump_to_serial();
|
||||||
|
#endif /* CMDBUFFER_DEBUG */
|
||||||
|
} else {
|
||||||
|
SERIAL_ERROR_START;
|
||||||
|
SERIAL_ECHOPGM("Enqueing to the front: \"");
|
||||||
|
if (from_progmem)
|
||||||
|
SERIAL_PROTOCOLRPGM(cmd);
|
||||||
|
else
|
||||||
|
SERIAL_ECHO(cmd);
|
||||||
|
SERIAL_ECHOLNPGM("\" failed: Buffer full!");
|
||||||
|
#ifdef CMDBUFFER_DEBUG
|
||||||
|
cmdqueue_dump_to_serial();
|
||||||
|
#endif /* CMDBUFFER_DEBUG */
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Mark the command at the top of the command queue as new.
|
||||||
|
// Therefore it will not be removed from the queue.
|
||||||
|
void repeatcommand_front()
|
||||||
|
{
|
||||||
|
cmdbuffer_front_already_processed = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool is_buffer_empty()
|
||||||
|
{
|
||||||
|
if (buflen == 0) return true;
|
||||||
|
else return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
void get_command()
|
||||||
|
{
|
||||||
|
// Test and reserve space for the new command string.
|
||||||
|
if (!cmdqueue_could_enqueue_back(MAX_CMD_SIZE - 1))
|
||||||
|
return;
|
||||||
|
|
||||||
|
bool rx_buffer_full = false; //flag that serial rx buffer is full
|
||||||
|
|
||||||
|
while (MYSERIAL.available() > 0) {
|
||||||
|
if (MYSERIAL.available() == RX_BUFFER_SIZE - 1) { //compare number of chars buffered in rx buffer with rx buffer size
|
||||||
|
SERIAL_ECHOLNPGM("Full RX Buffer"); //if buffer was full, there is danger that reading of last gcode will not be completed
|
||||||
|
rx_buffer_full = true; //sets flag that buffer was full
|
||||||
|
}
|
||||||
|
char serial_char = MYSERIAL.read();
|
||||||
|
if (selectedSerialPort == 1)
|
||||||
|
{
|
||||||
|
selectedSerialPort = 0;
|
||||||
|
MYSERIAL.write(serial_char); // for debuging serial line 2 in farm_mode
|
||||||
|
selectedSerialPort = 1;
|
||||||
|
}
|
||||||
|
TimeSent = millis();
|
||||||
|
TimeNow = millis();
|
||||||
|
|
||||||
|
if (serial_char < 0)
|
||||||
|
// Ignore extended ASCII characters. These characters have no meaning in the G-code apart from the file names
|
||||||
|
// and Marlin does not support such file names anyway.
|
||||||
|
// Serial characters with a highest bit set to 1 are generated when the USB cable is unplugged, leading
|
||||||
|
// to a hang-up of the print process from an SD card.
|
||||||
|
continue;
|
||||||
|
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
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
cmdbuffer[bufindw+serial_count+CMDHDRSIZE] = 0; //terminate string
|
||||||
|
if(!comment_mode){
|
||||||
|
comment_mode = false; //for new command
|
||||||
|
if ((strchr_pointer = strstr(cmdbuffer+bufindw+CMDHDRSIZE, "PRUSA")) == NULL && (strchr_pointer = strchr(cmdbuffer+bufindw+CMDHDRSIZE, 'N')) != NULL) {
|
||||||
|
if ((strchr_pointer = strchr(cmdbuffer+bufindw+CMDHDRSIZE, 'N')) != NULL)
|
||||||
|
{
|
||||||
|
// Line number met. When sending a G-code over a serial line, each line may be stamped with its index,
|
||||||
|
// and Marlin tests, whether the successive lines are stamped with an increasing line number ID.
|
||||||
|
gcode_N = (strtol(strchr_pointer+1, NULL, 10));
|
||||||
|
if(gcode_N != gcode_LastN+1 && (strstr_P(cmdbuffer+bufindw+CMDHDRSIZE, PSTR("M110")) == NULL) ) {
|
||||||
|
// M110 - set current line number.
|
||||||
|
// Line numbers not sent in succession.
|
||||||
|
SERIAL_ERROR_START;
|
||||||
|
SERIAL_ERRORRPGM(MSG_ERR_LINE_NO);
|
||||||
|
SERIAL_ERRORLN(gcode_LastN);
|
||||||
|
//Serial.println(gcode_N);
|
||||||
|
FlushSerialRequestResend();
|
||||||
|
serial_count = 0;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
if((strchr_pointer = strchr(cmdbuffer+bufindw+CMDHDRSIZE, '*')) != NULL)
|
||||||
|
{
|
||||||
|
byte checksum = 0;
|
||||||
|
char *p = cmdbuffer+bufindw+CMDHDRSIZE;
|
||||||
|
while (p != strchr_pointer)
|
||||||
|
checksum = checksum^(*p++);
|
||||||
|
if (int(strtol(strchr_pointer+1, NULL, 10)) != int(checksum)) {
|
||||||
|
SERIAL_ERROR_START;
|
||||||
|
SERIAL_ERRORRPGM(MSG_ERR_CHECKSUM_MISMATCH);
|
||||||
|
SERIAL_ERRORLN(gcode_LastN);
|
||||||
|
FlushSerialRequestResend();
|
||||||
|
serial_count = 0;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
// If no errors, remove the checksum and continue parsing.
|
||||||
|
*strchr_pointer = 0;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
SERIAL_ERROR_START;
|
||||||
|
SERIAL_ERRORRPGM(MSG_ERR_NO_CHECKSUM);
|
||||||
|
SERIAL_ERRORLN(gcode_LastN);
|
||||||
|
FlushSerialRequestResend();
|
||||||
|
serial_count = 0;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
gcode_LastN = gcode_N;
|
||||||
|
//if no errors, continue parsing
|
||||||
|
} // end of 'N' command
|
||||||
|
}
|
||||||
|
else // if we don't receive 'N' but still see '*'
|
||||||
|
{
|
||||||
|
if((strchr(cmdbuffer+bufindw+CMDHDRSIZE, '*') != NULL))
|
||||||
|
{
|
||||||
|
SERIAL_ERROR_START;
|
||||||
|
SERIAL_ERRORRPGM(MSG_ERR_NO_LINENUMBER_WITH_CHECKSUM);
|
||||||
|
SERIAL_ERRORLN(gcode_LastN);
|
||||||
|
serial_count = 0;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
} // end of '*' command
|
||||||
|
if ((strchr_pointer = strchr(cmdbuffer+bufindw+CMDHDRSIZE, 'G')) != NULL) {
|
||||||
|
if (! IS_SD_PRINTING) {
|
||||||
|
usb_printing_counter = 10;
|
||||||
|
is_usb_printing = true;
|
||||||
|
}
|
||||||
|
if (Stopped == true) {
|
||||||
|
int gcode = strtol(strchr_pointer+1, NULL, 10);
|
||||||
|
if (gcode >= 0 && gcode <= 3) {
|
||||||
|
SERIAL_ERRORLNRPGM(MSG_ERR_STOPPED);
|
||||||
|
LCD_MESSAGERPGM(MSG_STOPPED);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
} // end of 'G' command
|
||||||
|
|
||||||
|
//If command was e-stop process now
|
||||||
|
if(strcmp(cmdbuffer+bufindw+CMDHDRSIZE, "M112") == 0)
|
||||||
|
kill("", 2);
|
||||||
|
|
||||||
|
// Store the current line into buffer, move to the next line.
|
||||||
|
cmdbuffer[bufindw] = CMDBUFFER_CURRENT_TYPE_USB;
|
||||||
|
#ifdef CMDBUFFER_DEBUG
|
||||||
|
SERIAL_ECHO_START;
|
||||||
|
SERIAL_ECHOPGM("Storing a command line to buffer: ");
|
||||||
|
SERIAL_ECHO(cmdbuffer+bufindw+CMDHDRSIZE);
|
||||||
|
SERIAL_ECHOLNPGM("");
|
||||||
|
#endif /* CMDBUFFER_DEBUG */
|
||||||
|
bufindw += strlen(cmdbuffer+bufindw+CMDHDRSIZE) + (1 + CMDHDRSIZE);
|
||||||
|
if (bufindw == sizeof(cmdbuffer))
|
||||||
|
bufindw = 0;
|
||||||
|
++ buflen;
|
||||||
|
#ifdef CMDBUFFER_DEBUG
|
||||||
|
SERIAL_ECHOPGM("Number of commands in the buffer: ");
|
||||||
|
SERIAL_ECHO(buflen);
|
||||||
|
SERIAL_ECHOLNPGM("");
|
||||||
|
#endif /* CMDBUFFER_DEBUG */
|
||||||
|
} // end of 'not comment mode'
|
||||||
|
serial_count = 0; //clear buffer
|
||||||
|
// Don't call cmdqueue_could_enqueue_back if there are no characters waiting
|
||||||
|
// in the queue, as this function will reserve the memory.
|
||||||
|
if (MYSERIAL.available() == 0 || ! cmdqueue_could_enqueue_back(MAX_CMD_SIZE-1))
|
||||||
|
return;
|
||||||
|
} // end of "end of line" processing
|
||||||
|
else {
|
||||||
|
// Not an "end of line" symbol. Store the new character into a buffer.
|
||||||
|
if(serial_char == ';') comment_mode = true;
|
||||||
|
if(!comment_mode) cmdbuffer[bufindw+CMDHDRSIZE+serial_count++] = serial_char;
|
||||||
|
}
|
||||||
|
} // end of serial line processing loop
|
||||||
|
|
||||||
|
if(farm_mode){
|
||||||
|
TimeNow = millis();
|
||||||
|
if ( ((TimeNow - TimeSent) > 800) && (serial_count > 0) ) {
|
||||||
|
cmdbuffer[bufindw+serial_count+CMDHDRSIZE] = 0;
|
||||||
|
|
||||||
|
bufindw += strlen(cmdbuffer+bufindw+CMDHDRSIZE) + (1 + CMDHDRSIZE);
|
||||||
|
if (bufindw == sizeof(cmdbuffer))
|
||||||
|
bufindw = 0;
|
||||||
|
++ buflen;
|
||||||
|
|
||||||
|
serial_count = 0;
|
||||||
|
|
||||||
|
SERIAL_ECHOPGM("TIMEOUT:");
|
||||||
|
//memset(cmdbuffer, 0 , sizeof(cmdbuffer));
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
//add comment
|
||||||
|
if (rx_buffer_full == true && serial_count > 0) { //if rx buffer was full and string was not properly terminated
|
||||||
|
rx_buffer_full = false;
|
||||||
|
bufindw = bufindw - serial_count; //adjust tail of the buffer to prepare buffer for writing new command
|
||||||
|
serial_count = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef SDSUPPORT
|
||||||
|
if(!card.sdprinting || serial_count!=0){
|
||||||
|
// If there is a half filled buffer from serial line, wait until return before
|
||||||
|
// continuing with the serial line.
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
//'#' stops reading from SD to the buffer prematurely, so procedural macro calls are possible
|
||||||
|
// if it occurs, stop_buffering is triggered and the buffer is ran dry.
|
||||||
|
// this character _can_ occur in serial com, due to checksums. however, no checksums are used in SD printing
|
||||||
|
|
||||||
|
static bool stop_buffering=false;
|
||||||
|
if(buflen==0) stop_buffering=false;
|
||||||
|
unsigned char sd_count = 0;
|
||||||
|
// Reads whole lines from the SD card. Never leaves a half-filled line in the cmdbuffer.
|
||||||
|
while( !card.eof() && !stop_buffering) {
|
||||||
|
int16_t n=card.get();
|
||||||
|
sd_count++;
|
||||||
|
char serial_char = (char)n;
|
||||||
|
if(serial_char == '\n' ||
|
||||||
|
serial_char == '\r' ||
|
||||||
|
(serial_char == '#' && comment_mode == false) ||
|
||||||
|
(serial_char == ':' && comment_mode == false) ||
|
||||||
|
serial_count >= (MAX_CMD_SIZE - 1)||n==-1)
|
||||||
|
{
|
||||||
|
if(card.eof()){
|
||||||
|
SERIAL_PROTOCOLLNRPGM(MSG_FILE_PRINTED);
|
||||||
|
stoptime=millis();
|
||||||
|
char time[30];
|
||||||
|
unsigned long t=(stoptime-starttime-pause_time)/1000;
|
||||||
|
pause_time = 0;
|
||||||
|
int hours, minutes;
|
||||||
|
minutes=(t/60)%60;
|
||||||
|
hours=t/60/60;
|
||||||
|
save_statistics(total_filament_used, t);
|
||||||
|
sprintf_P(time, PSTR("%i hours %i minutes"),hours, minutes);
|
||||||
|
SERIAL_ECHO_START;
|
||||||
|
SERIAL_ECHOLN(time);
|
||||||
|
lcd_setstatus(time);
|
||||||
|
card.printingHasFinished();
|
||||||
|
card.checkautostart(true);
|
||||||
|
|
||||||
|
if (farm_mode)
|
||||||
|
{
|
||||||
|
prusa_statistics(6);
|
||||||
|
lcd_commands_type = LCD_COMMAND_FARM_MODE_CONFIRM;
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
if(serial_char=='#')
|
||||||
|
stop_buffering=true;
|
||||||
|
|
||||||
|
if(!serial_count)
|
||||||
|
{
|
||||||
|
comment_mode = false; //for new command
|
||||||
|
return; //if empty line
|
||||||
|
}
|
||||||
|
cmdbuffer[bufindw+serial_count+CMDHDRSIZE] = 0; //terminate string
|
||||||
|
cmdbuffer[bufindw] = CMDBUFFER_CURRENT_TYPE_SDCARD;
|
||||||
|
cmdbuffer[bufindw+1] = sd_count;
|
||||||
|
/* SERIAL_ECHOPGM("SD cmd(");
|
||||||
|
MYSERIAL.print(sd_count, DEC);
|
||||||
|
SERIAL_ECHOPGM(") ");
|
||||||
|
SERIAL_ECHOLN(cmdbuffer+bufindw+CMDHDRSIZE);*/
|
||||||
|
// SERIAL_ECHOPGM("cmdbuffer:");
|
||||||
|
// MYSERIAL.print(cmdbuffer);
|
||||||
|
++ buflen;
|
||||||
|
// SERIAL_ECHOPGM("buflen:");
|
||||||
|
// MYSERIAL.print(buflen);
|
||||||
|
bufindw += strlen(cmdbuffer+bufindw+CMDHDRSIZE) + (1 + CMDHDRSIZE);
|
||||||
|
if (bufindw == sizeof(cmdbuffer))
|
||||||
|
bufindw = 0;
|
||||||
|
comment_mode = false; //for new command
|
||||||
|
serial_count = 0; //clear buffer
|
||||||
|
// The following line will reserve buffer space if available.
|
||||||
|
if (! cmdqueue_could_enqueue_back(MAX_CMD_SIZE-1))
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
if(serial_char == ';') comment_mode = true;
|
||||||
|
if(!comment_mode) cmdbuffer[bufindw+CMDHDRSIZE+serial_count++] = serial_char;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif //SDSUPPORT
|
||||||
|
}
|
||||||
|
|
||||||
|
uint16_t cmdqueue_calc_sd_length()
|
||||||
|
{
|
||||||
|
int _buflen = buflen;
|
||||||
|
int _bufindr = bufindr;
|
||||||
|
uint16_t sdlen = 0;
|
||||||
|
while (_buflen--)
|
||||||
|
{
|
||||||
|
if (cmdbuffer[_bufindr] == CMDBUFFER_CURRENT_TYPE_SDCARD)
|
||||||
|
sdlen += cmdbuffer[_bufindr + 1];
|
||||||
|
//skip header, skip command
|
||||||
|
for (_bufindr += CMDHDRSIZE; cmdbuffer[_bufindr] != 0; ++ _bufindr) ;
|
||||||
|
//skip zeros
|
||||||
|
for (++ _bufindr; _bufindr < sizeof(cmdbuffer) && cmdbuffer[_bufindr] == 0; ++ _bufindr) ;
|
||||||
|
}
|
||||||
|
return sdlen;
|
||||||
|
}
|
86
Firmware/cmdqueue.h
Normal file
86
Firmware/cmdqueue.h
Normal file
|
@ -0,0 +1,86 @@
|
||||||
|
#ifndef CMDQUEUE_H
|
||||||
|
#define CMDQUEUE_H
|
||||||
|
|
||||||
|
#include "Marlin.h"
|
||||||
|
#include "language_all.h"
|
||||||
|
|
||||||
|
|
||||||
|
// String circular buffer. Commands may be pushed to the buffer from both sides:
|
||||||
|
// Chained commands will be pushed to the front, interactive (from LCD menu)
|
||||||
|
// and printing commands (from serial line or from SD card) are pushed to the tail.
|
||||||
|
// First character of each entry indicates the type of the entry:
|
||||||
|
#define CMDBUFFER_CURRENT_TYPE_UNKNOWN 0
|
||||||
|
// Command in cmdbuffer was sent over USB.
|
||||||
|
#define CMDBUFFER_CURRENT_TYPE_USB 1
|
||||||
|
// Command in cmdbuffer was read from SDCARD.
|
||||||
|
#define CMDBUFFER_CURRENT_TYPE_SDCARD 2
|
||||||
|
// Command in cmdbuffer was generated by the UI.
|
||||||
|
#define CMDBUFFER_CURRENT_TYPE_UI 3
|
||||||
|
// Command in cmdbuffer was generated by another G-code.
|
||||||
|
#define CMDBUFFER_CURRENT_TYPE_CHAINED 4
|
||||||
|
|
||||||
|
// How much space to reserve for the chained commands
|
||||||
|
// of type CMDBUFFER_CURRENT_TYPE_CHAINED,
|
||||||
|
// which are pushed to the front of the queue?
|
||||||
|
// Maximum 5 commands of max length 20 + null terminator.
|
||||||
|
#define CMDBUFFER_RESERVE_FRONT (5*21)
|
||||||
|
|
||||||
|
extern char cmdbuffer[BUFSIZE * (MAX_CMD_SIZE + 1) + CMDBUFFER_RESERVE_FRONT];
|
||||||
|
extern int bufindr;
|
||||||
|
extern int bufindw;
|
||||||
|
extern int buflen;
|
||||||
|
extern bool cmdbuffer_front_already_processed;
|
||||||
|
|
||||||
|
// Type of a command, which is to be executed right now.
|
||||||
|
#define CMDBUFFER_CURRENT_TYPE (cmdbuffer[bufindr])
|
||||||
|
// String of a command, which is to be executed right now.
|
||||||
|
#define CMDBUFFER_CURRENT_STRING (cmdbuffer+bufindr+CMDHDRSIZE)
|
||||||
|
|
||||||
|
// Enable debugging of the command buffer.
|
||||||
|
// Debugging information will be sent to serial line.
|
||||||
|
//#define CMDBUFFER_DEBUG
|
||||||
|
|
||||||
|
extern int serial_count;
|
||||||
|
extern boolean comment_mode;
|
||||||
|
extern char *strchr_pointer;
|
||||||
|
|
||||||
|
extern unsigned long TimeSent;
|
||||||
|
extern unsigned long TimeNow;
|
||||||
|
|
||||||
|
extern long gcode_N;
|
||||||
|
extern long gcode_LastN;
|
||||||
|
extern long Stopped_gcode_LastN;
|
||||||
|
|
||||||
|
extern bool cmdqueue_pop_front();
|
||||||
|
extern void cmdqueue_reset();
|
||||||
|
extern bool cmdqueue_could_enqueue_front(int len_asked);
|
||||||
|
extern bool cmdqueue_could_enqueue_back(int len_asked);
|
||||||
|
extern void cmdqueue_dump_to_serial_single_line(int nr, const char *p);
|
||||||
|
extern void cmdqueue_dump_to_serial();
|
||||||
|
extern void enquecommand(const char *cmd, bool from_progmem);
|
||||||
|
extern void enquecommand_front(const char *cmd, bool from_progmem);
|
||||||
|
extern void repeatcommand_front();
|
||||||
|
extern bool is_buffer_empty();
|
||||||
|
extern void get_command();
|
||||||
|
extern uint16_t cmdqueue_calc_sd_length();
|
||||||
|
|
||||||
|
// Return True if a character was found
|
||||||
|
static inline bool code_seen(char code) { return (strchr_pointer = strchr(CMDBUFFER_CURRENT_STRING, code)) != NULL; }
|
||||||
|
static inline bool code_seen(const char *code) { return (strchr_pointer = strstr(CMDBUFFER_CURRENT_STRING, code)) != NULL; }
|
||||||
|
static inline float code_value() { return strtod(strchr_pointer+1, NULL);}
|
||||||
|
static inline long code_value_long() { return strtol(strchr_pointer+1, NULL, 10); }
|
||||||
|
static inline int16_t code_value_short() { return int16_t(strtol(strchr_pointer+1, NULL, 10)); };
|
||||||
|
static inline uint8_t code_value_uint8() { return uint8_t(strtol(strchr_pointer+1, NULL, 10)); };
|
||||||
|
|
||||||
|
static inline float code_value_float()
|
||||||
|
{
|
||||||
|
char* e = strchr(strchr_pointer, 'E');
|
||||||
|
if (!e) return strtod(strchr_pointer + 1, NULL);
|
||||||
|
*e = 0;
|
||||||
|
float ret = strtod(strchr_pointer + 1, NULL);
|
||||||
|
*e = 'E';
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
#endif //CMDQUEUE_H
|
|
@ -1096,6 +1096,21 @@ const char * const MSG_FIND_BED_OFFSET_AND_SKEW_ITERATION_LANG_TABLE[LANG_NUM] P
|
||||||
MSG_FIND_BED_OFFSET_AND_SKEW_ITERATION_EN
|
MSG_FIND_BED_OFFSET_AND_SKEW_ITERATION_EN
|
||||||
};
|
};
|
||||||
|
|
||||||
|
const char MSG_CALIBRATE_Z_AUTO_EN[] PROGMEM = "Calibrating Z...";
|
||||||
|
const char MSG_CALIBRATE_Z_AUTO_CZ[] PROGMEM = "Calibrating Z...";
|
||||||
|
const char MSG_CALIBRATE_Z_AUTO_IT[] PROGMEM = "Calibrating Z...";
|
||||||
|
const char MSG_CALIBRATE_Z_AUTO_ES[] PROGMEM = "Calibrating Z...";
|
||||||
|
const char MSG_CALIBRATE_Z_AUTO_PL[] PROGMEM = "Calibrating Z...";
|
||||||
|
const char MSG_CALIBRATE_Z_AUTO_DE[] PROGMEM = "Calibrating Z...";
|
||||||
|
const char * const MSG_CALIBRATE_Z_AUTO_LANG_TABLE[LANG_NUM] PROGMEM = {
|
||||||
|
MSG_CALIBRATE_Z_AUTO_EN,
|
||||||
|
MSG_CALIBRATE_Z_AUTO_CZ,
|
||||||
|
MSG_CALIBRATE_Z_AUTO_IT,
|
||||||
|
MSG_CALIBRATE_Z_AUTO_ES,
|
||||||
|
MSG_CALIBRATE_Z_AUTO_PL,
|
||||||
|
MSG_CALIBRATE_Z_AUTO_DE
|
||||||
|
};
|
||||||
|
|
||||||
const char MSG_FIND_BED_OFFSET_AND_SKEW_LINE1_EN[] PROGMEM = "Searching bed calibration point";
|
const char MSG_FIND_BED_OFFSET_AND_SKEW_LINE1_EN[] PROGMEM = "Searching bed calibration point";
|
||||||
const char MSG_FIND_BED_OFFSET_AND_SKEW_LINE1_CZ[] PROGMEM = "Hledam kalibracni bod podlozky";
|
const char MSG_FIND_BED_OFFSET_AND_SKEW_LINE1_CZ[] PROGMEM = "Hledam kalibracni bod podlozky";
|
||||||
const char MSG_FIND_BED_OFFSET_AND_SKEW_LINE1_IT[] PROGMEM = "Ricerca del letto punto di calibraz.";
|
const char MSG_FIND_BED_OFFSET_AND_SKEW_LINE1_IT[] PROGMEM = "Ricerca del letto punto di calibraz.";
|
||||||
|
|
|
@ -220,6 +220,8 @@ extern const char* const MSG_FIL_ADJUSTING_LANG_TABLE[LANG_NUM];
|
||||||
#define MSG_FIL_ADJUSTING LANG_TABLE_SELECT(MSG_FIL_ADJUSTING_LANG_TABLE)
|
#define MSG_FIL_ADJUSTING LANG_TABLE_SELECT(MSG_FIL_ADJUSTING_LANG_TABLE)
|
||||||
extern const char* const MSG_FIND_BED_OFFSET_AND_SKEW_ITERATION_LANG_TABLE[LANG_NUM];
|
extern const char* const MSG_FIND_BED_OFFSET_AND_SKEW_ITERATION_LANG_TABLE[LANG_NUM];
|
||||||
#define MSG_FIND_BED_OFFSET_AND_SKEW_ITERATION LANG_TABLE_SELECT(MSG_FIND_BED_OFFSET_AND_SKEW_ITERATION_LANG_TABLE)
|
#define MSG_FIND_BED_OFFSET_AND_SKEW_ITERATION LANG_TABLE_SELECT(MSG_FIND_BED_OFFSET_AND_SKEW_ITERATION_LANG_TABLE)
|
||||||
|
extern const char* const MSG_CALIBRATE_Z_AUTO_LANG_TABLE[LANG_NUM];
|
||||||
|
#define MSG_CALIBRATE_Z_AUTO LANG_TABLE_SELECT(MSG_CALIBRATE_Z_AUTO_LANG_TABLE)
|
||||||
extern const char* const MSG_FIND_BED_OFFSET_AND_SKEW_LINE1_LANG_TABLE[LANG_NUM];
|
extern const char* const MSG_FIND_BED_OFFSET_AND_SKEW_LINE1_LANG_TABLE[LANG_NUM];
|
||||||
#define MSG_FIND_BED_OFFSET_AND_SKEW_LINE1 LANG_TABLE_SELECT(MSG_FIND_BED_OFFSET_AND_SKEW_LINE1_LANG_TABLE)
|
#define MSG_FIND_BED_OFFSET_AND_SKEW_LINE1 LANG_TABLE_SELECT(MSG_FIND_BED_OFFSET_AND_SKEW_LINE1_LANG_TABLE)
|
||||||
extern const char* const MSG_FIND_BED_OFFSET_AND_SKEW_LINE2_LANG_TABLE[LANG_NUM];
|
extern const char* const MSG_FIND_BED_OFFSET_AND_SKEW_LINE2_LANG_TABLE[LANG_NUM];
|
||||||
|
|
|
@ -19,8 +19,8 @@ float world2machine_shift[2];
|
||||||
#define WEIGHT_FIRST_ROW_Y_HIGH (0.3f)
|
#define WEIGHT_FIRST_ROW_Y_HIGH (0.3f)
|
||||||
#define WEIGHT_FIRST_ROW_Y_LOW (0.0f)
|
#define WEIGHT_FIRST_ROW_Y_LOW (0.0f)
|
||||||
|
|
||||||
#define BED_ZERO_REF_X (- 22.f + X_PROBE_OFFSET_FROM_EXTRUDER)
|
#define BED_ZERO_REF_X (- 22.f + X_PROBE_OFFSET_FROM_EXTRUDER) // -22 + 23 = 1
|
||||||
#define BED_ZERO_REF_Y (- 0.6f + Y_PROBE_OFFSET_FROM_EXTRUDER)
|
#define BED_ZERO_REF_Y (- 0.6f + Y_PROBE_OFFSET_FROM_EXTRUDER) // -0.6 + 9 = 8.4
|
||||||
|
|
||||||
// Scaling of the real machine axes against the programmed dimensions in the firmware.
|
// Scaling of the real machine axes against the programmed dimensions in the firmware.
|
||||||
// The correction is tiny, here around 0.5mm on 250mm length.
|
// The correction is tiny, here around 0.5mm on 250mm length.
|
||||||
|
|
|
@ -1,29 +1,34 @@
|
||||||
|
#include "uni_avr_rpi.h"
|
||||||
|
|
||||||
|
#ifdef PAT9125
|
||||||
|
|
||||||
#include "pat9125.h"
|
#include "pat9125.h"
|
||||||
|
|
||||||
|
#ifdef PAT9125_SWSPI
|
||||||
#include "swspi.h"
|
#include "swspi.h"
|
||||||
|
#endif //PAT9125_SWSPI
|
||||||
|
#ifdef PAT9125_SWI2C
|
||||||
|
#include "swi2c.h"
|
||||||
|
#endif //PAT9125_SWI2C
|
||||||
|
|
||||||
|
|
||||||
#ifdef SWSPI_RPI
|
unsigned char pat9125_PID1 = 0;
|
||||||
// #include <bcm2835.h>
|
unsigned char pat9125_PID2 = 0;
|
||||||
#define DELAY(delay) usleep(delay)
|
|
||||||
#endif //SWSPI_RPI
|
|
||||||
|
|
||||||
#ifdef SWSPI_AVR
|
|
||||||
#include "Arduino.h"
|
|
||||||
#define DELAY(delay) delayMicroseconds(delay)
|
|
||||||
#endif //SWSPI_AVR
|
|
||||||
|
|
||||||
unsigned char ucPID1 = 0;
|
|
||||||
unsigned char ucPID2 = 0;
|
|
||||||
int pat9125_x = 0;
|
int pat9125_x = 0;
|
||||||
int pat9125_y = 0;
|
int pat9125_y = 0;
|
||||||
int pat9125_b = 0;
|
int pat9125_b = 0;
|
||||||
|
|
||||||
int pat9125_init(unsigned char xres, unsigned char yres)
|
int pat9125_init(unsigned char xres, unsigned char yres)
|
||||||
{
|
{
|
||||||
|
#ifdef PAT9125_SWSPI
|
||||||
swspi_init();
|
swspi_init();
|
||||||
ucPID1 = pat9125_rd_reg(PAT9125_PID1);
|
#endif //PAT9125_SWSPI
|
||||||
ucPID2 = pat9125_rd_reg(PAT9125_PID2);
|
#ifdef PAT9125_SWI2C
|
||||||
if ((ucPID1 != 0x31) || (ucPID2 != 0x91))
|
swi2c_init(PAT9125_SWI2C_SDA, PAT9125_SWI2C_SCL, PAT9125_SWI2C_CFG);
|
||||||
|
#endif //PAT9125_SWI2C
|
||||||
|
pat9125_PID1 = pat9125_rd_reg(PAT9125_PID1);
|
||||||
|
pat9125_PID2 = pat9125_rd_reg(PAT9125_PID2);
|
||||||
|
if ((pat9125_PID1 != 0x31) || (pat9125_PID2 != 0x91))
|
||||||
{
|
{
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
@ -34,7 +39,7 @@ int pat9125_init(unsigned char xres, unsigned char yres)
|
||||||
|
|
||||||
int pat9125_update()
|
int pat9125_update()
|
||||||
{
|
{
|
||||||
if ((ucPID1 == 0x31) && (ucPID2 == 0x91))
|
if ((pat9125_PID1 == 0x31) && (pat9125_PID2 == 0x91))
|
||||||
{
|
{
|
||||||
unsigned char ucMotion = pat9125_rd_reg(PAT9125_MOTION);
|
unsigned char ucMotion = pat9125_rd_reg(PAT9125_MOTION);
|
||||||
pat9125_b = pat9125_rd_reg(PAT9125_FRAME);
|
pat9125_b = pat9125_rd_reg(PAT9125_FRAME);
|
||||||
|
@ -47,7 +52,7 @@ int pat9125_update()
|
||||||
int iDY = ucYL | ((ucXYH << 8) & 0xf00);
|
int iDY = ucYL | ((ucXYH << 8) & 0xf00);
|
||||||
if (iDX & 0x800) iDX -= 4096;
|
if (iDX & 0x800) iDX -= 4096;
|
||||||
if (iDY & 0x800) iDY -= 4096;
|
if (iDY & 0x800) iDY -= 4096;
|
||||||
// pat9125_x += iDX;
|
pat9125_x += iDX;
|
||||||
pat9125_y += iDY;
|
pat9125_y += iDY;
|
||||||
return 1;
|
return 1;
|
||||||
}
|
}
|
||||||
|
@ -57,23 +62,30 @@ int pat9125_update()
|
||||||
|
|
||||||
unsigned char pat9125_rd_reg(unsigned char addr)
|
unsigned char pat9125_rd_reg(unsigned char addr)
|
||||||
{
|
{
|
||||||
|
unsigned char data = 0;
|
||||||
|
#ifdef PAT9125_SWSPI
|
||||||
swspi_start();
|
swspi_start();
|
||||||
DELAY(100);
|
|
||||||
swspi_tx(addr & 0x7f);
|
swspi_tx(addr & 0x7f);
|
||||||
DELAY(100);
|
data = swspi_rx();
|
||||||
unsigned char data = swspi_rx();
|
|
||||||
swspi_stop();
|
swspi_stop();
|
||||||
DELAY(100);
|
#endif //PAT9125_SWSPI
|
||||||
|
#ifdef PAT9125_SWI2C
|
||||||
|
int iret = swi2c_readByte_A8(PAT9125_I2C_ADDR, addr, &data);
|
||||||
|
#endif //PAT9125_SWI2C
|
||||||
return data;
|
return data;
|
||||||
}
|
}
|
||||||
|
|
||||||
void pat9125_wr_reg(unsigned char addr, unsigned char data)
|
void pat9125_wr_reg(unsigned char addr, unsigned char data)
|
||||||
{
|
{
|
||||||
|
#ifdef PAT9125_SWSPI
|
||||||
swspi_start();
|
swspi_start();
|
||||||
DELAY(100);
|
|
||||||
swspi_tx(addr | 0x80);
|
swspi_tx(addr | 0x80);
|
||||||
DELAY(100);
|
|
||||||
swspi_tx(data);
|
swspi_tx(data);
|
||||||
swspi_stop();
|
swspi_stop();
|
||||||
DELAY(100);
|
#endif //PAT9125_SWSPI
|
||||||
|
#ifdef PAT9125_SWI2C
|
||||||
|
int iret = swi2c_writeByte_A8(PAT9125_I2C_ADDR, addr, &data);
|
||||||
|
#endif //PAT9125_SWI2C
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif //PAT9125
|
||||||
|
|
|
@ -1,8 +1,10 @@
|
||||||
#ifndef PAT9125_H
|
#ifndef PAT9125_H
|
||||||
#define PAT9125_H
|
#define PAT9125_H
|
||||||
|
|
||||||
//#define PAT9125_RPI
|
//PAT9125 I2C
|
||||||
#define PAT9125_AVR
|
#define PAT9125_I2C_ADDR 0x75 //ID=LO
|
||||||
|
//#define PAT9125_I2C_ADDR 0x79 //ID=HI
|
||||||
|
//#define PAT9125_I2C_ADDR 0x73 //ID=NC
|
||||||
|
|
||||||
//PAT9125 registers
|
//PAT9125 registers
|
||||||
#define PAT9125_PID1 0x00
|
#define PAT9125_PID1 0x00
|
||||||
|
@ -22,18 +24,18 @@
|
||||||
#define PAT9125_FRAME 0x17
|
#define PAT9125_FRAME 0x17
|
||||||
#define PAT9125_ORIENTATION 0x19
|
#define PAT9125_ORIENTATION 0x19
|
||||||
|
|
||||||
extern unsigned char ucPID1;
|
extern unsigned char pat9125_PID1;
|
||||||
extern unsigned char ucPID2;
|
extern unsigned char pat9125_PID2;
|
||||||
|
|
||||||
extern int pat9125_x;
|
extern int pat9125_x;
|
||||||
extern int pat9125_y;
|
extern int pat9125_y;
|
||||||
extern int pat9125_b;
|
extern int pat9125_b;
|
||||||
|
|
||||||
int pat9125_init(unsigned char xres, unsigned char yres);
|
extern int pat9125_init(unsigned char xres, unsigned char yres);
|
||||||
int pat9125_update();
|
extern int pat9125_update();
|
||||||
|
|
||||||
unsigned char pat9125_rd_reg(unsigned char addr);
|
extern unsigned char pat9125_rd_reg(unsigned char addr);
|
||||||
void pat9125_wr_reg(unsigned char addr, unsigned char data);
|
extern void pat9125_wr_reg(unsigned char addr, unsigned char data);
|
||||||
|
|
||||||
|
|
||||||
#endif //PAT9125_H
|
#endif //PAT9125_H
|
||||||
|
|
529
Firmware/pins.h
529
Firmware/pins.h
|
@ -22,523 +22,30 @@
|
||||||
/*****************************************************************
|
/*****************************************************************
|
||||||
* Rambo Pin Assignments 1.3
|
* Rambo Pin Assignments 1.3
|
||||||
******************************************************************/
|
******************************************************************/
|
||||||
#if MOTHERBOARD == 302
|
|
||||||
#define MINI_RAMBO
|
|
||||||
|
|
||||||
#endif
|
#if MOTHERBOARD == 100 //100 - orig 301
|
||||||
#if MOTHERBOARD == 301 || MOTHERBOARD == 302
|
#include "pins_Rambo.h"
|
||||||
#define KNOWN_BOARD
|
#endif //MOTHERBOARD == 100
|
||||||
#ifndef __AVR_ATmega2560__
|
|
||||||
#error Oops! Make sure you have 'Arduino Mega 2560' selected from the 'Tools -> Boards' menu.
|
|
||||||
#endif
|
|
||||||
|
|
||||||
|
#if MOTHERBOARD == 200 //200 - orig 102
|
||||||
|
#include "pins_Rambo_1_0.h"
|
||||||
|
#endif //MOTHERBOARD == 200
|
||||||
|
|
||||||
#define FR_SENS 21
|
#if MOTHERBOARD == 203 //203 - orig 302
|
||||||
|
#include "pins_Rambo_1_3.h"
|
||||||
|
#endif //MOTHERBOARD == 203
|
||||||
|
|
||||||
|
#if MOTHERBOARD == 303 //303 - orig 300
|
||||||
|
#include "pins_Einy_0_3.h"
|
||||||
|
#endif //MOTHERBOARD == 303
|
||||||
|
|
||||||
#define X_STEP_PIN 37
|
#if MOTHERBOARD == 304 //304 - orig 299
|
||||||
#define X_DIR_PIN 48
|
#include "pins_Einy_0_4.h"
|
||||||
#define X_MIN_PIN 12
|
#endif //MOTHERBOARD == 304
|
||||||
#define X_MAX_PIN 30
|
|
||||||
#define X_ENABLE_PIN 29
|
|
||||||
#define X_MS1_PIN 40
|
|
||||||
#define X_MS2_PIN 41
|
|
||||||
#define Y_STEP_PIN 36
|
|
||||||
#define Y_DIR_PIN 49
|
|
||||||
#define Y_MIN_PIN 11
|
|
||||||
#define Y_MAX_PIN 24
|
|
||||||
#define Y_ENABLE_PIN 28
|
|
||||||
#define Y_MS1_PIN 69
|
|
||||||
#define Y_MS2_PIN 39
|
|
||||||
#define Z_STEP_PIN 35
|
|
||||||
#define Z_DIR_PIN 47
|
|
||||||
#define Z_MIN_PIN 10
|
|
||||||
#define Z_MAX_PIN 23
|
|
||||||
#define Z_ENABLE_PIN 27
|
|
||||||
#define Z_MS1_PIN 68
|
|
||||||
#define Z_MS2_PIN 67
|
|
||||||
#define TEMP_BED_PIN 2
|
|
||||||
#define TEMP_0_PIN 0
|
|
||||||
#define HEATER_1_PIN 7
|
|
||||||
#define TEMP_1_PIN 1
|
|
||||||
#define TEMP_2_PIN -1
|
|
||||||
|
|
||||||
#ifdef SNMM
|
|
||||||
|
|
||||||
#define E_MUX0_PIN 17
|
|
||||||
#define E_MUX1_PIN 16
|
|
||||||
#define E_MUX2_PIN 84
|
|
||||||
|
|
||||||
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef DIS
|
|
||||||
#define D_REQUIRE 30
|
|
||||||
#define D_DATA 20
|
|
||||||
#define D_DATACLOCK 21
|
|
||||||
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// The SDSS pin uses a different pin mapping from file Sd2PinMap.h
|
|
||||||
#define SDSS 53
|
|
||||||
|
|
||||||
#ifndef SDSUPPORT
|
|
||||||
// these pins are defined in the SD library if building with SD support
|
|
||||||
#define SCK_PIN 52
|
|
||||||
#define MISO_PIN 50
|
|
||||||
#define MOSI_PIN 51
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#define BEEPER 84
|
|
||||||
|
|
||||||
#define BTN_EN1 72
|
|
||||||
#define BTN_EN2 14
|
|
||||||
#define BTN_ENC 9
|
|
||||||
|
|
||||||
#define SDCARDDETECT 15
|
|
||||||
|
|
||||||
#define LCD_PINS_RS 82
|
|
||||||
#define LCD_PINS_ENABLE 18
|
|
||||||
#define LCD_PINS_D4 19
|
|
||||||
#define LCD_PINS_D5 70
|
|
||||||
#define LCD_PINS_D6 85
|
|
||||||
#define LCD_PINS_D7 71
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
#define E0_STEP_PIN 34
|
|
||||||
#define E0_DIR_PIN 43
|
|
||||||
#define E0_ENABLE_PIN 26
|
|
||||||
#define E0_MS1_PIN 65
|
|
||||||
#define E0_MS2_PIN 66
|
|
||||||
#define LED_PIN 13
|
|
||||||
#ifdef THREEMM_PRINTER
|
|
||||||
#define FAN_PIN 8
|
|
||||||
#else
|
|
||||||
#define FAN_PIN 6
|
|
||||||
#endif
|
|
||||||
#define KILL_PIN -1 //80 with Smart Controller LCD
|
|
||||||
#define SUICIDE_PIN -1 //PIN that has to be turned on right after start, to keep power flowing.
|
|
||||||
#define SDPOWER -1
|
|
||||||
#define HEATER_2_PIN -1
|
|
||||||
#ifdef MINI_RAMBO
|
|
||||||
|
|
||||||
#define ELECTRONICS "RAMBo13a"
|
|
||||||
|
|
||||||
#define HEATER_0_PIN 3
|
|
||||||
#define HEATER_BED_PIN 4
|
|
||||||
#define FAN_1_PIN -1 //6
|
|
||||||
#define PS_ON_PIN 71
|
|
||||||
#define MOTOR_CURRENT_PWM_XY_PIN 46
|
|
||||||
#define MOTOR_CURRENT_PWM_Z_PIN 45
|
|
||||||
#define MOTOR_CURRENT_PWM_E_PIN 44
|
|
||||||
|
|
||||||
#else //RAMBo
|
|
||||||
#define ELECTRONICS "RAMBoBig"
|
|
||||||
|
|
||||||
#define E1_STEP_PIN 33
|
|
||||||
#define E1_DIR_PIN 42
|
|
||||||
#define E1_ENABLE_PIN 25
|
|
||||||
#define E1_MS1_PIN 63
|
|
||||||
#define E1_MS2_PIN 64
|
|
||||||
#define DIGIPOTSS_PIN 38
|
|
||||||
#define DIGIPOT_CHANNELS {4,5,3,0,1} // X Y Z E0 E1 digipot channels to stepper driver mapping
|
|
||||||
#define HEATER_0_PIN 9
|
|
||||||
#define HEATER_BED_PIN 3
|
|
||||||
#define PS_ON_PIN 4
|
|
||||||
#define SDSS 53
|
|
||||||
#ifdef ULTRA_LCD
|
|
||||||
#define KILL_PIN 80
|
|
||||||
#ifdef NEWPANEL
|
|
||||||
//arduino pin which triggers an piezzo beeper
|
|
||||||
#define BEEPER 84 // Beeper on AUX-4
|
|
||||||
#define LCD_PINS_RS 82
|
|
||||||
#define LCD_PINS_ENABLE 18
|
|
||||||
#define LCD_PINS_D4 19
|
|
||||||
#define LCD_PINS_D5 70
|
|
||||||
#define LCD_PINS_D6 85
|
|
||||||
#define LCD_PINS_D7 71
|
|
||||||
//buttons are directly attached using AUX-2
|
|
||||||
#define BTN_EN1 76
|
|
||||||
#define BTN_EN2 77
|
|
||||||
#define BTN_ENC 78 //the click
|
|
||||||
#define BLEN_C 2
|
|
||||||
#define BLEN_B 1
|
|
||||||
#define BLEN_A 0
|
|
||||||
#define SDCARDDETECT 81 // Ramps does not use this port
|
|
||||||
//encoder rotation values
|
|
||||||
#define encrot0 0
|
|
||||||
#define encrot1 2
|
|
||||||
#define encrot2 3
|
|
||||||
#define encrot3 1
|
|
||||||
#else //old style panel with shift register
|
|
||||||
//arduino pin witch triggers an piezzo beeper
|
|
||||||
#define BEEPER 84 //No Beeper added
|
|
||||||
//buttons are attached to a shift register
|
|
||||||
// Not wired this yet
|
|
||||||
// #define SHIFT_CLK 38
|
|
||||||
// #define SHIFT_LD 42
|
|
||||||
// #define SHIFT_OUT 40
|
|
||||||
// #define SHIFT_EN 17
|
|
||||||
#define LCD_PINS_RS 82
|
|
||||||
#define LCD_PINS_ENABLE 18
|
|
||||||
#define LCD_PINS_D4 19
|
|
||||||
#define LCD_PINS_D5 70
|
|
||||||
#define LCD_PINS_D6 85
|
|
||||||
#define LCD_PINS_D7 71
|
|
||||||
//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
|
|
||||||
#define BL_UP 6
|
|
||||||
#define BL_MI 5
|
|
||||||
#define BL_DW 4
|
|
||||||
#define BL_RI 3
|
|
||||||
#define BL_ST 2
|
|
||||||
#define BLEN_B 1
|
|
||||||
#define BLEN_A 0
|
|
||||||
#endif
|
|
||||||
#endif //ULTRA_LCD
|
|
||||||
#endif //RAMBo/MiniRambo option
|
|
||||||
#endif
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
/*****************************************************************
|
|
||||||
* Rambo mini Pin Assignments 1.0
|
|
||||||
******************************************************************/
|
|
||||||
#if MOTHERBOARD == 102
|
|
||||||
#define ELECTRONICS "RAMBo10a"
|
|
||||||
#define KNOWN_BOARD
|
|
||||||
#ifndef __AVR_ATmega2560__
|
|
||||||
#error Oops! Make sure you have 'Arduino Mega 2560' selected from the 'Tools -> Boards' menu.
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#define FR_SENS 21
|
|
||||||
|
|
||||||
#ifdef SNMM
|
|
||||||
|
|
||||||
#define E_MUX0_PIN 17
|
|
||||||
#define E_MUX1_PIN 16
|
|
||||||
#define E_MUX2_PIN 84
|
|
||||||
|
|
||||||
|
|
||||||
#endif
|
|
||||||
#define LARGE_FLASH true
|
|
||||||
#define X_STEP_PIN 37
|
|
||||||
#define X_DIR_PIN 48
|
|
||||||
#define X_MIN_PIN 12
|
|
||||||
#define X_MAX_PIN 30
|
|
||||||
#define X_ENABLE_PIN 29
|
|
||||||
#define X_MS1_PIN 40
|
|
||||||
#define X_MS2_PIN 41
|
|
||||||
#define Y_STEP_PIN 36
|
|
||||||
#define Y_DIR_PIN 49
|
|
||||||
#define Y_MIN_PIN 11
|
|
||||||
#define Y_MAX_PIN 24
|
|
||||||
#define Y_ENABLE_PIN 28
|
|
||||||
#define Y_MS1_PIN 69
|
|
||||||
#define Y_MS2_PIN 39
|
|
||||||
#define Z_STEP_PIN 35
|
|
||||||
#define Z_DIR_PIN 47
|
|
||||||
#define Z_MIN_PIN 10
|
|
||||||
#define Z_MAX_PIN 23
|
|
||||||
#define Z_ENABLE_PIN 27
|
|
||||||
#define Z_MS1_PIN 68
|
|
||||||
#define Z_MS2_PIN 67
|
|
||||||
#define TEMP_BED_PIN 2
|
|
||||||
#define TEMP_0_PIN 0
|
|
||||||
#define HEATER_1_PIN 7
|
|
||||||
#define TEMP_1_PIN 1
|
|
||||||
#define TEMP_2_PIN -1
|
|
||||||
|
|
||||||
// The SDSS pin uses a different pin mapping from file Sd2PinMap.h
|
|
||||||
#define SDSS 53
|
|
||||||
|
|
||||||
#ifndef SDSUPPORT
|
|
||||||
// these pins are defined in the SD library if building with SD support
|
|
||||||
#define SCK_PIN 52
|
|
||||||
#define MISO_PIN 50
|
|
||||||
#define MOSI_PIN 51
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#define BEEPER 78
|
|
||||||
|
|
||||||
#define BTN_EN1 80
|
|
||||||
#define BTN_EN2 73
|
|
||||||
#define BTN_ENC 21
|
|
||||||
|
|
||||||
#define SDCARDDETECT 72
|
|
||||||
|
|
||||||
#define LCD_PINS_RS 38
|
|
||||||
#define LCD_PINS_ENABLE 5
|
|
||||||
#define LCD_PINS_D4 14
|
|
||||||
#define LCD_PINS_D5 15
|
|
||||||
#define LCD_PINS_D6 32
|
|
||||||
#define LCD_PINS_D7 31
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
#define E0_STEP_PIN 34
|
|
||||||
#define E0_DIR_PIN 43
|
|
||||||
#define E0_ENABLE_PIN 26
|
|
||||||
#define E0_MS1_PIN 65
|
|
||||||
#define E0_MS2_PIN 66
|
|
||||||
#define LED_PIN 13
|
|
||||||
#ifdef THREEMM_PRINTER
|
|
||||||
#define FAN_PIN 8
|
|
||||||
#else
|
|
||||||
#define FAN_PIN 6
|
|
||||||
#endif
|
|
||||||
#define KILL_PIN -1 //80 with Smart Controller LCD
|
|
||||||
#define SUICIDE_PIN -1 //PIN that has to be turned on right after start, to keep power flowing.
|
|
||||||
#define SDPOWER -1
|
|
||||||
#define HEATER_2_PIN -1
|
|
||||||
|
|
||||||
#define HEATER_0_PIN 3
|
|
||||||
#define HEATER_BED_PIN 4
|
|
||||||
#define FAN_1_PIN -1 //6
|
|
||||||
#define PS_ON_PIN 71
|
|
||||||
#define MOTOR_CURRENT_PWM_XY_PIN 46
|
|
||||||
#define MOTOR_CURRENT_PWM_Z_PIN 45
|
|
||||||
#define MOTOR_CURRENT_PWM_E_PIN 44
|
|
||||||
|
|
||||||
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/*****************************************************************
|
|
||||||
* EINY Rambo Pin Assignments 0.3a
|
|
||||||
******************************************************************/
|
|
||||||
#if MOTHERBOARD == 300
|
|
||||||
#define ELECTRONICS "EINY_03a"
|
|
||||||
#define KNOWN_BOARD
|
|
||||||
#ifndef __AVR_ATmega2560__
|
|
||||||
#error Oops! Make sure you have 'Arduino Mega 2560 or Rambo' selected from the 'Tools -> Boards' menu.
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#define LARGE_FLASH true
|
|
||||||
#define HAVE_TMC2130_DRIVERS
|
|
||||||
#define HAVE_PAT9125_SENSOR
|
|
||||||
|
|
||||||
#define X_STEP_PIN 37
|
|
||||||
#define X_DIR_PIN 49
|
|
||||||
#define X_MIN_PIN 12
|
|
||||||
#define X_MAX_PIN 30
|
|
||||||
//#define X_MIN_PIN 64 //TMC2130 SG homing
|
|
||||||
//#define X_MAX_PIN 64 //TMC2130 SG homing
|
|
||||||
#define X_ENABLE_PIN 29
|
|
||||||
#define X_MS1_PIN -1
|
|
||||||
#define X_MS2_PIN -1
|
|
||||||
#define X_TMC2130_CS 41
|
|
||||||
|
|
||||||
#define Y_STEP_PIN 36
|
|
||||||
#define Y_DIR_PIN 48
|
|
||||||
#define Y_MIN_PIN 11
|
|
||||||
#define Y_MAX_PIN 24
|
|
||||||
//#define Y_MIN_PIN 69 //TMC2130 SG homing
|
|
||||||
//#define Y_MAX_PIN 69 //TMC2130 SG homing
|
|
||||||
#define Y_ENABLE_PIN 28
|
|
||||||
#define Y_MS1_PIN -1
|
|
||||||
#define Y_MS2_PIN -1
|
|
||||||
#define Y_TMC2130_CS 39
|
|
||||||
|
|
||||||
#define Z_STEP_PIN 35
|
|
||||||
#define Z_DIR_PIN 47
|
|
||||||
#define Z_MIN_PIN 10
|
|
||||||
#define Z_MAX_PIN 23
|
|
||||||
#define Z_ENABLE_PIN 27
|
|
||||||
#define Z_MS1_PIN -1
|
|
||||||
#define Z_MS2_PIN -1
|
|
||||||
#define Z_TMC2130_CS 67
|
|
||||||
|
|
||||||
#define HEATER_BED_PIN 4
|
|
||||||
#define TEMP_BED_PIN 2
|
|
||||||
|
|
||||||
#define HEATER_0_PIN 3
|
|
||||||
#define TEMP_0_PIN 0
|
|
||||||
|
|
||||||
#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
|
|
||||||
#define E0_DIR_PIN 43
|
|
||||||
#define E0_ENABLE_PIN 26
|
|
||||||
#define E0_MS1_PIN -1
|
|
||||||
#define E0_MS2_PIN -1
|
|
||||||
#define E0_TMC2130_CS 66
|
|
||||||
|
|
||||||
#define MOTOR_CURRENT_PWM_XY_PIN 46
|
|
||||||
#define MOTOR_CURRENT_PWM_Z_PIN 45
|
|
||||||
#define MOTOR_CURRENT_PWM_E_PIN 44
|
|
||||||
#define SDPOWER -1
|
|
||||||
#define SDSS 53
|
|
||||||
#define LED_PIN 13
|
|
||||||
#define FAN_PIN 6
|
|
||||||
#define FAN_1_PIN -1
|
|
||||||
#define PS_ON_PIN -1
|
|
||||||
#define KILL_PIN -1 // 80 with Smart Controller LCD
|
|
||||||
#define SUICIDE_PIN -1 // PIN that has to be turned on right after start, to keep power flowing.
|
|
||||||
|
|
||||||
#ifdef ULTRA_LCD
|
|
||||||
|
|
||||||
#define KILL_PIN 32
|
|
||||||
|
|
||||||
#ifdef NEWPANEL
|
|
||||||
|
|
||||||
#define BEEPER 84 // Beeper on AUX-4
|
|
||||||
#define LCD_PINS_RS 82
|
|
||||||
#define LCD_PINS_ENABLE 18
|
|
||||||
#define LCD_PINS_D4 19
|
|
||||||
#define LCD_PINS_D5 70
|
|
||||||
#define LCD_PINS_D6 85
|
|
||||||
#define LCD_PINS_D7 71
|
|
||||||
|
|
||||||
//buttons are directly attached using AUX-2
|
|
||||||
#define BTN_EN1 72
|
|
||||||
#define BTN_EN2 14
|
|
||||||
#define BTN_ENC 9 // the click
|
|
||||||
|
|
||||||
#define SDCARDDETECT 15
|
|
||||||
|
|
||||||
#define TACH_0 81
|
|
||||||
#define TACH_1 80
|
|
||||||
|
|
||||||
#endif //NEWPANEL
|
|
||||||
#endif //ULTRA_LCD
|
|
||||||
|
|
||||||
#endif //MOTHERBOARD == 300
|
|
||||||
|
|
||||||
|
|
||||||
/*****************************************************************
|
|
||||||
* EINY Rambo Pin Assignments 0.4a
|
|
||||||
******************************************************************/
|
|
||||||
#if MOTHERBOARD == 299
|
|
||||||
#define ELECTRONICS "EINY_04a"
|
|
||||||
#define KNOWN_BOARD
|
|
||||||
#ifndef __AVR_ATmega2560__
|
|
||||||
#error Oops! Make sure you have 'Arduino Mega 2560 or Rambo' selected from the 'Tools -> Boards' menu.
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#define LARGE_FLASH true
|
|
||||||
#define HAVE_TMC2130_DRIVERS
|
|
||||||
#define HAVE_PAT9125_SENSOR
|
|
||||||
|
|
||||||
#define X_STEP_PIN 37
|
|
||||||
#define X_DIR_PIN 49
|
|
||||||
#define X_MIN_PIN 12
|
|
||||||
#define X_MAX_PIN 30
|
|
||||||
//#define X_MIN_PIN 64 //TMC2130 SG homing
|
|
||||||
//#define X_MAX_PIN 64 //TMC2130 SG homing
|
|
||||||
#define X_ENABLE_PIN 29
|
|
||||||
#define X_MS1_PIN -1
|
|
||||||
#define X_MS2_PIN -1
|
|
||||||
#define X_TMC2130_CS 41
|
|
||||||
|
|
||||||
#define Y_STEP_PIN 36
|
|
||||||
#define Y_DIR_PIN 48
|
|
||||||
#define Y_MIN_PIN 11
|
|
||||||
#define Y_MAX_PIN 24
|
|
||||||
//#define Y_MIN_PIN 69 //TMC2130 SG homing
|
|
||||||
//#define Y_MAX_PIN 69 //TMC2130 SG homing
|
|
||||||
#define Y_ENABLE_PIN 28
|
|
||||||
#define Y_MS1_PIN -1
|
|
||||||
#define Y_MS2_PIN -1
|
|
||||||
#define Y_TMC2130_CS 39
|
|
||||||
|
|
||||||
#define Z_STEP_PIN 35
|
|
||||||
#define Z_DIR_PIN 47
|
|
||||||
#define Z_MIN_PIN 10
|
|
||||||
#define Z_MAX_PIN 23
|
|
||||||
#define Z_ENABLE_PIN 27
|
|
||||||
#define Z_MS1_PIN -1
|
|
||||||
#define Z_MS2_PIN -1
|
|
||||||
#define Z_TMC2130_CS 67
|
|
||||||
|
|
||||||
#define HEATER_BED_PIN 4
|
|
||||||
#define TEMP_BED_PIN 2
|
|
||||||
|
|
||||||
#define HEATER_0_PIN 3
|
|
||||||
#define TEMP_0_PIN 0
|
|
||||||
|
|
||||||
#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
|
|
||||||
#define E0_DIR_PIN 43
|
|
||||||
#define E0_ENABLE_PIN 26
|
|
||||||
#define E0_MS1_PIN -1
|
|
||||||
#define E0_MS2_PIN -1
|
|
||||||
#define E0_TMC2130_CS 66
|
|
||||||
|
|
||||||
#define MOTOR_CURRENT_PWM_XY_PIN 46
|
|
||||||
#define MOTOR_CURRENT_PWM_Z_PIN 45
|
|
||||||
#define MOTOR_CURRENT_PWM_E_PIN 44
|
|
||||||
#define SDPOWER -1
|
|
||||||
#define SDSS 77
|
|
||||||
#define LED_PIN 13
|
|
||||||
#define FAN_PIN 6
|
|
||||||
#define FAN_1_PIN -1
|
|
||||||
#define PS_ON_PIN -1
|
|
||||||
#define KILL_PIN -1 // 80 with Smart Controller LCD
|
|
||||||
#define SUICIDE_PIN -1 // PIN that has to be turned on right after start, to keep power flowing.
|
|
||||||
|
|
||||||
#ifdef ULTRA_LCD
|
|
||||||
|
|
||||||
//#define KILL_PIN 32
|
|
||||||
|
|
||||||
#ifdef NEWPANEL
|
|
||||||
|
|
||||||
|
|
||||||
#define BEEPER 84 // Beeper on AUX-4
|
|
||||||
#define LCD_PINS_RS 82
|
|
||||||
//#define LCD_PINS_ENABLE 18
|
|
||||||
//#define LCD_PINS_D4 19
|
|
||||||
#define LCD_PINS_ENABLE 61
|
|
||||||
#define LCD_PINS_D4 59
|
|
||||||
#define LCD_PINS_D5 70
|
|
||||||
#define LCD_PINS_D6 85
|
|
||||||
#define LCD_PINS_D7 71
|
|
||||||
|
|
||||||
//buttons are directly attached using AUX-2
|
|
||||||
#define BTN_EN1 72
|
|
||||||
#define BTN_EN2 14
|
|
||||||
#define BTN_ENC 9 // the click
|
|
||||||
|
|
||||||
#define SDCARDDETECT 15
|
|
||||||
|
|
||||||
#define TACH_0 79
|
|
||||||
#define TACH_1 80
|
|
||||||
|
|
||||||
#endif //NEWPANEL
|
|
||||||
#endif //ULTRA_LCD
|
|
||||||
|
|
||||||
#endif //MOTHERBOARD == 300
|
|
||||||
|
|
||||||
|
#if MOTHERBOARD == 305 //305 - orig 298
|
||||||
|
#include "pins_Einy_0_4.h"
|
||||||
|
#endif //MOTHERBOARD == 305
|
||||||
|
|
||||||
#ifndef KNOWN_BOARD
|
#ifndef KNOWN_BOARD
|
||||||
#error Unknown MOTHERBOARD value in configuration.h
|
#error Unknown MOTHERBOARD value in configuration.h
|
||||||
|
|
129
Firmware/pins_Einy_0_3.h
Normal file
129
Firmware/pins_Einy_0_3.h
Normal file
|
@ -0,0 +1,129 @@
|
||||||
|
/*****************************************************************
|
||||||
|
* EINY Rambo 0.3a Pin Assignments
|
||||||
|
******************************************************************/
|
||||||
|
|
||||||
|
#define ELECTRONICS "EINY_03a"
|
||||||
|
|
||||||
|
#define KNOWN_BOARD
|
||||||
|
#ifndef __AVR_ATmega2560__
|
||||||
|
#error Oops! Make sure you have 'Arduino Mega 2560 or Rambo' selected from the 'Tools -> Boards' menu.
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define TMC2130
|
||||||
|
#define PAT9125
|
||||||
|
|
||||||
|
#define SWI2C // enable software i2c
|
||||||
|
#define SWI2C_A8 // 8bit address functions
|
||||||
|
|
||||||
|
#define PAT9125_SWI2C
|
||||||
|
#define PAT9125_SWI2C_SDA 20 //SDA on P3
|
||||||
|
#define PAT9125_SWI2C_SCL 21 //SCL on P3
|
||||||
|
#define PAT9125_SWI2C_CFG 0xb1 //2us clock delay, 2048 cycles timeout
|
||||||
|
|
||||||
|
//#define SWSPI_MISO 16 //RX2
|
||||||
|
//#define SWSPI_MOSI 16 //RX2
|
||||||
|
//#define SWSPI_SCK 17 //TX2
|
||||||
|
//#define SWSPI_CS 20 //SDA
|
||||||
|
|
||||||
|
////#define SWI2C_SDA 20 //SDA
|
||||||
|
////#define SWI2C_SCL 21 //SCL
|
||||||
|
//#define SWI2C_SDA 16 //RX2
|
||||||
|
//#define SWI2C_SCL 17 //TX2
|
||||||
|
|
||||||
|
#define X_TMC2130_CS 41
|
||||||
|
#define X_TMC2130_DIAG 40
|
||||||
|
#define X_STEP_PIN 37
|
||||||
|
#define X_DIR_PIN 49
|
||||||
|
//#define X_MIN_PIN 12
|
||||||
|
//#define X_MAX_PIN 30
|
||||||
|
#define X_MIN_PIN X_TMC2130_DIAG
|
||||||
|
#define X_MAX_PIN X_TMC2130_DIAG
|
||||||
|
#define X_ENABLE_PIN 29
|
||||||
|
#define X_MS1_PIN -1
|
||||||
|
#define X_MS2_PIN -1
|
||||||
|
|
||||||
|
#define Y_TMC2130_CS 39
|
||||||
|
#define Y_TMC2130_DIAG 69
|
||||||
|
#define Y_STEP_PIN 36
|
||||||
|
#define Y_DIR_PIN 48
|
||||||
|
//#define Y_MIN_PIN 11
|
||||||
|
//#define Y_MAX_PIN 24
|
||||||
|
#define Y_MIN_PIN Y_TMC2130_DIAG
|
||||||
|
#define Y_MAX_PIN Y_TMC2130_DIAG
|
||||||
|
#define Y_ENABLE_PIN 28
|
||||||
|
#define Y_MS1_PIN -1
|
||||||
|
#define Y_MS2_PIN -1
|
||||||
|
|
||||||
|
#define Z_TMC2130_CS 67
|
||||||
|
#define Z_TMC2130_DIAG 68
|
||||||
|
#define Z_STEP_PIN 35
|
||||||
|
#define Z_DIR_PIN 47
|
||||||
|
#define Z_MIN_PIN 10
|
||||||
|
#define Z_MAX_PIN 23
|
||||||
|
//#define Z_MAX_PIN Z_TMC2130_DIAG
|
||||||
|
#define Z_ENABLE_PIN 27
|
||||||
|
#define Z_MS1_PIN -1
|
||||||
|
#define Z_MS2_PIN -1
|
||||||
|
|
||||||
|
#define HEATER_BED_PIN 4 //PG5
|
||||||
|
#define TEMP_BED_PIN 2 //A2
|
||||||
|
|
||||||
|
#define HEATER_0_PIN 3 //PE5
|
||||||
|
#define TEMP_0_PIN 0 //A0
|
||||||
|
|
||||||
|
#define HEATER_1_PIN -1
|
||||||
|
#define TEMP_1_PIN 1 //A1
|
||||||
|
|
||||||
|
#define HEATER_2_PIN -1
|
||||||
|
#define TEMP_2_PIN -1
|
||||||
|
|
||||||
|
#define TEMP_AMBIENT_PIN 6 //A6
|
||||||
|
|
||||||
|
#define TEMP_PINDA_PIN 3 //A3
|
||||||
|
|
||||||
|
#define E0_TMC2130_CS 66
|
||||||
|
#define E0_TMC2130_DIAG 65
|
||||||
|
#define E0_STEP_PIN 34
|
||||||
|
#define E0_DIR_PIN 43
|
||||||
|
#define E0_ENABLE_PIN 26
|
||||||
|
#define E0_MS1_PIN -1
|
||||||
|
#define E0_MS2_PIN -1
|
||||||
|
|
||||||
|
#define MOTOR_CURRENT_PWM_XY_PIN 46
|
||||||
|
#define MOTOR_CURRENT_PWM_Z_PIN 45
|
||||||
|
#define MOTOR_CURRENT_PWM_E_PIN 44
|
||||||
|
#define SDPOWER -1
|
||||||
|
#define SDSS 53
|
||||||
|
#define LED_PIN 13
|
||||||
|
#define FAN_PIN 6
|
||||||
|
#define FAN_1_PIN -1
|
||||||
|
#define PS_ON_PIN -1
|
||||||
|
#define KILL_PIN -1 // 80 with Smart Controller LCD
|
||||||
|
#define SUICIDE_PIN -1 // PIN that has to be turned on right after start, to keep power flowing.
|
||||||
|
|
||||||
|
#ifdef ULTRA_LCD
|
||||||
|
|
||||||
|
//#define KILL_PIN 32
|
||||||
|
|
||||||
|
#ifdef NEWPANEL
|
||||||
|
|
||||||
|
#define BEEPER 84 // Beeper on AUX-4
|
||||||
|
#define LCD_PINS_RS 82
|
||||||
|
#define LCD_PINS_ENABLE 18
|
||||||
|
#define LCD_PINS_D4 19
|
||||||
|
#define LCD_PINS_D5 70
|
||||||
|
#define LCD_PINS_D6 85
|
||||||
|
#define LCD_PINS_D7 71
|
||||||
|
|
||||||
|
//buttons are directly attached using AUX-2
|
||||||
|
#define BTN_EN1 72
|
||||||
|
#define BTN_EN2 14
|
||||||
|
#define BTN_ENC 9 // the click
|
||||||
|
|
||||||
|
#define SDCARDDETECT 15
|
||||||
|
|
||||||
|
#define TACH_0 81
|
||||||
|
#define TACH_1 80
|
||||||
|
|
||||||
|
#endif //NEWPANEL
|
||||||
|
#endif //ULTRA_LCD
|
122
Firmware/pins_Einy_0_4.h
Normal file
122
Firmware/pins_Einy_0_4.h
Normal file
|
@ -0,0 +1,122 @@
|
||||||
|
/*****************************************************************
|
||||||
|
* EINY Rambo 0.4a Pin Assignments
|
||||||
|
******************************************************************/
|
||||||
|
|
||||||
|
#define ELECTRONICS "EINY_04a"
|
||||||
|
|
||||||
|
#define KNOWN_BOARD
|
||||||
|
#ifndef __AVR_ATmega2560__
|
||||||
|
#error Oops! Make sure you have 'Arduino Mega 2560 or Rambo' selected from the 'Tools -> Boards' menu.
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define TMC2130
|
||||||
|
#define PAT9125
|
||||||
|
|
||||||
|
#define SWI2C // enable software i2c
|
||||||
|
#define SWI2C_A8 // 8bit address functions
|
||||||
|
|
||||||
|
#define PAT9125_SWI2C
|
||||||
|
#define PAT9125_SWI2C_SDA 20 //SDA on P3
|
||||||
|
#define PAT9125_SWI2C_SCL 21 //SCL on P3
|
||||||
|
#define PAT9125_SWI2C_CFG 0xb1 //2us clock delay, 2048 cycles timeout
|
||||||
|
|
||||||
|
#define X_TMC2130_CS 41
|
||||||
|
#define X_TMC2130_DIAG 64 // !!! changed from 40 (EINY03)
|
||||||
|
#define X_STEP_PIN 37
|
||||||
|
#define X_DIR_PIN 49
|
||||||
|
//#define X_MIN_PIN 12
|
||||||
|
//#define X_MAX_PIN 30
|
||||||
|
#define X_MIN_PIN X_TMC2130_DIAG
|
||||||
|
#define X_MAX_PIN X_TMC2130_DIAG
|
||||||
|
#define X_ENABLE_PIN 29
|
||||||
|
#define X_MS1_PIN -1
|
||||||
|
#define X_MS2_PIN -1
|
||||||
|
|
||||||
|
#define Y_TMC2130_CS 39
|
||||||
|
#define Y_TMC2130_DIAG 69
|
||||||
|
#define Y_STEP_PIN 36
|
||||||
|
#define Y_DIR_PIN 48
|
||||||
|
//#define Y_MIN_PIN 11
|
||||||
|
//#define Y_MAX_PIN 24
|
||||||
|
#define Y_MIN_PIN Y_TMC2130_DIAG
|
||||||
|
#define Y_MAX_PIN Y_TMC2130_DIAG
|
||||||
|
#define Y_ENABLE_PIN 28
|
||||||
|
#define Y_MS1_PIN -1
|
||||||
|
#define Y_MS2_PIN -1
|
||||||
|
|
||||||
|
#define Z_TMC2130_CS 67
|
||||||
|
#define Z_TMC2130_DIAG 68
|
||||||
|
#define Z_STEP_PIN 35
|
||||||
|
#define Z_DIR_PIN 47
|
||||||
|
#define Z_MIN_PIN 10
|
||||||
|
#define Z_MAX_PIN 23
|
||||||
|
//#define Z_MAX_PIN Z_TMC2130_DIAG
|
||||||
|
#define Z_ENABLE_PIN 27
|
||||||
|
#define Z_MS1_PIN -1
|
||||||
|
#define Z_MS2_PIN -1
|
||||||
|
|
||||||
|
#define HEATER_BED_PIN 4 //PG5
|
||||||
|
#define TEMP_BED_PIN 2 //A2
|
||||||
|
|
||||||
|
#define HEATER_0_PIN 3 //PE5
|
||||||
|
#define TEMP_0_PIN 0 //A0
|
||||||
|
|
||||||
|
#define HEATER_1_PIN -1
|
||||||
|
#define TEMP_1_PIN 1 //A1
|
||||||
|
|
||||||
|
#define HEATER_2_PIN -1
|
||||||
|
#define TEMP_2_PIN -1
|
||||||
|
|
||||||
|
#define TEMP_AMBIENT_PIN 6 //A6
|
||||||
|
|
||||||
|
#define TEMP_PINDA_PIN 3 //A3
|
||||||
|
|
||||||
|
#define E0_TMC2130_CS 66
|
||||||
|
#define E0_TMC2130_DIAG 65
|
||||||
|
#define E0_STEP_PIN 34
|
||||||
|
#define E0_DIR_PIN 43
|
||||||
|
#define E0_ENABLE_PIN 26
|
||||||
|
#define E0_MS1_PIN -1
|
||||||
|
#define E0_MS2_PIN -1
|
||||||
|
|
||||||
|
#define MOTOR_CURRENT_PWM_XY_PIN 46
|
||||||
|
#define MOTOR_CURRENT_PWM_Z_PIN 45
|
||||||
|
#define MOTOR_CURRENT_PWM_E_PIN 44
|
||||||
|
#define SDPOWER -1
|
||||||
|
#define SDSS 77
|
||||||
|
#define LED_PIN 13
|
||||||
|
#define FAN_PIN 6
|
||||||
|
#define FAN_1_PIN -1
|
||||||
|
#define PS_ON_PIN -1
|
||||||
|
#define KILL_PIN -1 // 80 with Smart Controller LCD
|
||||||
|
#define SUICIDE_PIN -1 // PIN that has to be turned on right after start, to keep power flowing.
|
||||||
|
|
||||||
|
#ifdef ULTRA_LCD
|
||||||
|
|
||||||
|
//#define KILL_PIN 32
|
||||||
|
|
||||||
|
#ifdef NEWPANEL
|
||||||
|
|
||||||
|
#define LCD_PWM_PIN 32 // lcd backlight brightnes pwm control pin
|
||||||
|
#define LCD_PWM_MAX 0x0f // lcd pwm maximum value (0x07=64Hz, 0x0f=32Hz, 0x1f=16Hz)
|
||||||
|
|
||||||
|
#define BEEPER 84 // Beeper on AUX-4
|
||||||
|
#define LCD_PINS_RS 82
|
||||||
|
#define LCD_PINS_ENABLE 61 // !!! changed from 18 (EINY03)
|
||||||
|
#define LCD_PINS_D4 59 // !!! changed from 19 (EINY03)
|
||||||
|
#define LCD_PINS_D5 70
|
||||||
|
#define LCD_PINS_D6 85
|
||||||
|
#define LCD_PINS_D7 71
|
||||||
|
|
||||||
|
//buttons are directly attached using AUX-2
|
||||||
|
#define BTN_EN1 72
|
||||||
|
#define BTN_EN2 14
|
||||||
|
#define BTN_ENC 9 // the click
|
||||||
|
|
||||||
|
#define SDCARDDETECT 15
|
||||||
|
|
||||||
|
#define TACH_0 79 // !!! changed from 81 (EINY03)
|
||||||
|
#define TACH_1 80
|
||||||
|
|
||||||
|
#endif //NEWPANEL
|
||||||
|
#endif //ULTRA_LCD
|
162
Firmware/pins_Rambo.h
Normal file
162
Firmware/pins_Rambo.h
Normal file
|
@ -0,0 +1,162 @@
|
||||||
|
/*****************************************************************
|
||||||
|
* Rambo Pin Assignments
|
||||||
|
******************************************************************/
|
||||||
|
|
||||||
|
#define ELECTRONICS "RAMBoBig"
|
||||||
|
|
||||||
|
#define KNOWN_BOARD
|
||||||
|
#ifndef __AVR_ATmega2560__
|
||||||
|
#error Oops! Make sure you have 'Arduino Mega 2560' selected from the 'Tools -> Boards' menu.
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define FR_SENS 21
|
||||||
|
|
||||||
|
#define X_STEP_PIN 37
|
||||||
|
#define X_DIR_PIN 48
|
||||||
|
#define X_MIN_PIN 12
|
||||||
|
#define X_MAX_PIN 30
|
||||||
|
#define X_ENABLE_PIN 29
|
||||||
|
#define X_MS1_PIN 40
|
||||||
|
#define X_MS2_PIN 41
|
||||||
|
#define Y_STEP_PIN 36
|
||||||
|
#define Y_DIR_PIN 49
|
||||||
|
#define Y_MIN_PIN 11
|
||||||
|
#define Y_MAX_PIN 24
|
||||||
|
#define Y_ENABLE_PIN 28
|
||||||
|
#define Y_MS1_PIN 69
|
||||||
|
#define Y_MS2_PIN 39
|
||||||
|
#define Z_STEP_PIN 35
|
||||||
|
#define Z_DIR_PIN 47
|
||||||
|
#define Z_MIN_PIN 10
|
||||||
|
#define Z_MAX_PIN 23
|
||||||
|
#define Z_ENABLE_PIN 27
|
||||||
|
#define Z_MS1_PIN 68
|
||||||
|
#define Z_MS2_PIN 67
|
||||||
|
#define TEMP_BED_PIN 2
|
||||||
|
#define TEMP_0_PIN 0
|
||||||
|
#define HEATER_1_PIN 7
|
||||||
|
#define TEMP_1_PIN 1
|
||||||
|
#define TEMP_2_PIN -1
|
||||||
|
|
||||||
|
#ifdef SNMM
|
||||||
|
#define E_MUX0_PIN 17
|
||||||
|
#define E_MUX1_PIN 16
|
||||||
|
#define E_MUX2_PIN 84
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef DIS
|
||||||
|
#define D_REQUIRE 30
|
||||||
|
#define D_DATA 20
|
||||||
|
#define D_DATACLOCK 21
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// The SDSS pin uses a different pin mapping from file Sd2PinMap.h
|
||||||
|
#define SDSS 53
|
||||||
|
|
||||||
|
#ifndef SDSUPPORT
|
||||||
|
// these pins are defined in the SD library if building with SD support
|
||||||
|
#define SCK_PIN 52
|
||||||
|
#define MISO_PIN 50
|
||||||
|
#define MOSI_PIN 51
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define BEEPER 84
|
||||||
|
|
||||||
|
#define BTN_EN1 72
|
||||||
|
#define BTN_EN2 14
|
||||||
|
#define BTN_ENC 9
|
||||||
|
|
||||||
|
#define SDCARDDETECT 15
|
||||||
|
|
||||||
|
#define LCD_PINS_RS 82
|
||||||
|
#define LCD_PINS_ENABLE 18
|
||||||
|
#define LCD_PINS_D4 19
|
||||||
|
#define LCD_PINS_D5 70
|
||||||
|
#define LCD_PINS_D6 85
|
||||||
|
#define LCD_PINS_D7 71
|
||||||
|
|
||||||
|
#define E0_STEP_PIN 34
|
||||||
|
#define E0_DIR_PIN 43
|
||||||
|
#define E0_ENABLE_PIN 26
|
||||||
|
#define E0_MS1_PIN 65
|
||||||
|
#define E0_MS2_PIN 66
|
||||||
|
#define LED_PIN 13
|
||||||
|
|
||||||
|
#ifdef THREEMM_PRINTER
|
||||||
|
#define FAN_PIN 8
|
||||||
|
#else
|
||||||
|
#define FAN_PIN 6
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define KILL_PIN -1 //80 with Smart Controller LCD
|
||||||
|
#define SUICIDE_PIN -1 //PIN that has to be turned on right after start, to keep power flowing.
|
||||||
|
#define SDPOWER -1
|
||||||
|
#define HEATER_2_PIN -1
|
||||||
|
|
||||||
|
#define E1_STEP_PIN 33
|
||||||
|
#define E1_DIR_PIN 42
|
||||||
|
#define E1_ENABLE_PIN 25
|
||||||
|
#define E1_MS1_PIN 63
|
||||||
|
#define E1_MS2_PIN 64
|
||||||
|
#define DIGIPOTSS_PIN 38
|
||||||
|
#define DIGIPOT_CHANNELS {4,5,3,0,1} // X Y Z E0 E1 digipot channels to stepper driver mapping
|
||||||
|
#define HEATER_0_PIN 9
|
||||||
|
#define HEATER_BED_PIN 3
|
||||||
|
#define PS_ON_PIN 4
|
||||||
|
#define SDSS 53
|
||||||
|
#ifdef ULTRA_LCD
|
||||||
|
#define KILL_PIN 80
|
||||||
|
#ifdef NEWPANEL
|
||||||
|
//arduino pin which triggers an piezzo beeper
|
||||||
|
#define BEEPER 84 // Beeper on AUX-4
|
||||||
|
#define LCD_PINS_RS 82
|
||||||
|
#define LCD_PINS_ENABLE 18
|
||||||
|
#define LCD_PINS_D4 19
|
||||||
|
#define LCD_PINS_D5 70
|
||||||
|
#define LCD_PINS_D6 85
|
||||||
|
#define LCD_PINS_D7 71
|
||||||
|
//buttons are directly attached using AUX-2
|
||||||
|
#define BTN_EN1 76
|
||||||
|
#define BTN_EN2 77
|
||||||
|
#define BTN_ENC 78 //the click
|
||||||
|
#define BLEN_C 2
|
||||||
|
#define BLEN_B 1
|
||||||
|
#define BLEN_A 0
|
||||||
|
#define SDCARDDETECT 81 // Ramps does not use this port
|
||||||
|
//encoder rotation values
|
||||||
|
#define encrot0 0
|
||||||
|
#define encrot1 2
|
||||||
|
#define encrot2 3
|
||||||
|
#define encrot3 1
|
||||||
|
#else //old style panel with shift register
|
||||||
|
//arduino pin witch triggers an piezzo beeper
|
||||||
|
#define BEEPER 84 //No Beeper added
|
||||||
|
//buttons are attached to a shift register
|
||||||
|
// Not wired this yet
|
||||||
|
// #define SHIFT_CLK 38
|
||||||
|
// #define SHIFT_LD 42
|
||||||
|
// #define SHIFT_OUT 40
|
||||||
|
// #define SHIFT_EN 17
|
||||||
|
#define LCD_PINS_RS 82
|
||||||
|
#define LCD_PINS_ENABLE 18
|
||||||
|
#define LCD_PINS_D4 19
|
||||||
|
#define LCD_PINS_D5 70
|
||||||
|
#define LCD_PINS_D6 85
|
||||||
|
#define LCD_PINS_D7 71
|
||||||
|
//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
|
||||||
|
#define BL_UP 6
|
||||||
|
#define BL_MI 5
|
||||||
|
#define BL_DW 4
|
||||||
|
#define BL_RI 3
|
||||||
|
#define BL_ST 2
|
||||||
|
#define BLEN_B 1
|
||||||
|
#define BLEN_A 0
|
||||||
|
#endif
|
||||||
|
#endif //ULTRA_LCD
|
94
Firmware/pins_Rambo_1_0.h
Normal file
94
Firmware/pins_Rambo_1_0.h
Normal file
|
@ -0,0 +1,94 @@
|
||||||
|
/*****************************************************************
|
||||||
|
* Rambo mini 1.0 Pin Assignments
|
||||||
|
******************************************************************/
|
||||||
|
|
||||||
|
#define ELECTRONICS "RAMBo10a"
|
||||||
|
|
||||||
|
#define KNOWN_BOARD
|
||||||
|
#ifndef __AVR_ATmega2560__
|
||||||
|
#error Oops! Make sure you have 'Arduino Mega 2560' selected from the 'Tools -> Boards' menu.
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define FR_SENS 21
|
||||||
|
|
||||||
|
#define X_STEP_PIN 37
|
||||||
|
#define X_DIR_PIN 48
|
||||||
|
#define X_MIN_PIN 12
|
||||||
|
#define X_MAX_PIN 30
|
||||||
|
#define X_ENABLE_PIN 29
|
||||||
|
#define X_MS1_PIN 40
|
||||||
|
#define X_MS2_PIN 41
|
||||||
|
#define Y_STEP_PIN 36
|
||||||
|
#define Y_DIR_PIN 49
|
||||||
|
#define Y_MIN_PIN 11
|
||||||
|
#define Y_MAX_PIN 24
|
||||||
|
#define Y_ENABLE_PIN 28
|
||||||
|
#define Y_MS1_PIN 69
|
||||||
|
#define Y_MS2_PIN 39
|
||||||
|
#define Z_STEP_PIN 35
|
||||||
|
#define Z_DIR_PIN 47
|
||||||
|
#define Z_MIN_PIN 10
|
||||||
|
#define Z_MAX_PIN 23
|
||||||
|
#define Z_ENABLE_PIN 27
|
||||||
|
#define Z_MS1_PIN 68
|
||||||
|
#define Z_MS2_PIN 67
|
||||||
|
#define TEMP_BED_PIN 2
|
||||||
|
#define TEMP_0_PIN 0
|
||||||
|
#define HEATER_1_PIN 7
|
||||||
|
#define TEMP_1_PIN 1
|
||||||
|
#define TEMP_2_PIN -1
|
||||||
|
|
||||||
|
#ifdef SNMM
|
||||||
|
#define E_MUX0_PIN 17
|
||||||
|
#define E_MUX1_PIN 16
|
||||||
|
#define E_MUX2_PIN 84
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// The SDSS pin uses a different pin mapping from file Sd2PinMap.h
|
||||||
|
#define SDSS 53
|
||||||
|
|
||||||
|
#ifndef SDSUPPORT
|
||||||
|
// these pins are defined in the SD library if building with SD support
|
||||||
|
#define SCK_PIN 52
|
||||||
|
#define MISO_PIN 50
|
||||||
|
#define MOSI_PIN 51
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define BEEPER 78
|
||||||
|
|
||||||
|
#define BTN_EN1 80
|
||||||
|
#define BTN_EN2 73
|
||||||
|
#define BTN_ENC 21
|
||||||
|
|
||||||
|
#define SDCARDDETECT 72
|
||||||
|
|
||||||
|
#define LCD_PINS_RS 38
|
||||||
|
#define LCD_PINS_ENABLE 5
|
||||||
|
#define LCD_PINS_D4 14
|
||||||
|
#define LCD_PINS_D5 15
|
||||||
|
#define LCD_PINS_D6 32
|
||||||
|
#define LCD_PINS_D7 31
|
||||||
|
|
||||||
|
#define E0_STEP_PIN 34
|
||||||
|
#define E0_DIR_PIN 43
|
||||||
|
#define E0_ENABLE_PIN 26
|
||||||
|
#define E0_MS1_PIN 65
|
||||||
|
#define E0_MS2_PIN 66
|
||||||
|
#define LED_PIN 13
|
||||||
|
#ifdef THREEMM_PRINTER
|
||||||
|
#define FAN_PIN 8
|
||||||
|
#else
|
||||||
|
#define FAN_PIN 6
|
||||||
|
#endif
|
||||||
|
#define KILL_PIN -1 //80 with Smart Controller LCD
|
||||||
|
#define SUICIDE_PIN -1 //PIN that has to be turned on right after start, to keep power flowing.
|
||||||
|
#define SDPOWER -1
|
||||||
|
#define HEATER_2_PIN -1
|
||||||
|
|
||||||
|
#define HEATER_0_PIN 3
|
||||||
|
#define HEATER_BED_PIN 4
|
||||||
|
#define FAN_1_PIN -1 //6
|
||||||
|
#define PS_ON_PIN 71
|
||||||
|
#define MOTOR_CURRENT_PWM_XY_PIN 46
|
||||||
|
#define MOTOR_CURRENT_PWM_Z_PIN 45
|
||||||
|
#define MOTOR_CURRENT_PWM_E_PIN 44
|
102
Firmware/pins_Rambo_1_3.h
Normal file
102
Firmware/pins_Rambo_1_3.h
Normal file
|
@ -0,0 +1,102 @@
|
||||||
|
/*****************************************************************
|
||||||
|
* Rambo mini 1.3 Pin Assignments
|
||||||
|
******************************************************************/
|
||||||
|
|
||||||
|
#define ELECTRONICS "RAMBo13a"
|
||||||
|
|
||||||
|
#define KNOWN_BOARD
|
||||||
|
#ifndef __AVR_ATmega2560__
|
||||||
|
#error Oops! Make sure you have 'Arduino Mega 2560' selected from the 'Tools -> Boards' menu.
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define FR_SENS 21
|
||||||
|
|
||||||
|
#define X_STEP_PIN 37
|
||||||
|
#define X_DIR_PIN 48
|
||||||
|
#define X_MIN_PIN 12
|
||||||
|
#define X_MAX_PIN 30
|
||||||
|
#define X_ENABLE_PIN 29
|
||||||
|
#define X_MS1_PIN 40
|
||||||
|
#define X_MS2_PIN 41
|
||||||
|
#define Y_STEP_PIN 36
|
||||||
|
#define Y_DIR_PIN 49
|
||||||
|
#define Y_MIN_PIN 11
|
||||||
|
#define Y_MAX_PIN 24
|
||||||
|
#define Y_ENABLE_PIN 28
|
||||||
|
#define Y_MS1_PIN 69
|
||||||
|
#define Y_MS2_PIN 39
|
||||||
|
#define Z_STEP_PIN 35
|
||||||
|
#define Z_DIR_PIN 47
|
||||||
|
#define Z_MIN_PIN 10
|
||||||
|
#define Z_MAX_PIN 23
|
||||||
|
#define Z_ENABLE_PIN 27
|
||||||
|
#define Z_MS1_PIN 68
|
||||||
|
#define Z_MS2_PIN 67
|
||||||
|
#define TEMP_BED_PIN 2
|
||||||
|
#define TEMP_0_PIN 0
|
||||||
|
#define HEATER_1_PIN 7
|
||||||
|
#define TEMP_1_PIN 1
|
||||||
|
#define TEMP_2_PIN -1
|
||||||
|
|
||||||
|
#ifdef SNMM
|
||||||
|
#define E_MUX0_PIN 17
|
||||||
|
#define E_MUX1_PIN 16
|
||||||
|
#define E_MUX2_PIN 84
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef DIS
|
||||||
|
#define D_REQUIRE 30
|
||||||
|
#define D_DATA 20
|
||||||
|
#define D_DATACLOCK 21
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// The SDSS pin uses a different pin mapping from file Sd2PinMap.h
|
||||||
|
#define SDSS 53
|
||||||
|
|
||||||
|
#ifndef SDSUPPORT
|
||||||
|
// these pins are defined in the SD library if building with SD support
|
||||||
|
#define SCK_PIN 52
|
||||||
|
#define MISO_PIN 50
|
||||||
|
#define MOSI_PIN 51
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define BEEPER 84
|
||||||
|
|
||||||
|
#define BTN_EN1 72
|
||||||
|
#define BTN_EN2 14
|
||||||
|
#define BTN_ENC 9
|
||||||
|
|
||||||
|
#define SDCARDDETECT 15
|
||||||
|
|
||||||
|
#define LCD_PINS_RS 82
|
||||||
|
#define LCD_PINS_ENABLE 18
|
||||||
|
#define LCD_PINS_D4 19
|
||||||
|
#define LCD_PINS_D5 70
|
||||||
|
#define LCD_PINS_D6 85
|
||||||
|
#define LCD_PINS_D7 71
|
||||||
|
|
||||||
|
#define E0_STEP_PIN 34
|
||||||
|
#define E0_DIR_PIN 43
|
||||||
|
#define E0_ENABLE_PIN 26
|
||||||
|
#define E0_MS1_PIN 65
|
||||||
|
#define E0_MS2_PIN 66
|
||||||
|
#define LED_PIN 13
|
||||||
|
|
||||||
|
#ifdef THREEMM_PRINTER
|
||||||
|
#define FAN_PIN 8
|
||||||
|
#else
|
||||||
|
#define FAN_PIN 6
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define KILL_PIN -1 //80 with Smart Controller LCD
|
||||||
|
#define SUICIDE_PIN -1 //PIN that has to be turned on right after start, to keep power flowing.
|
||||||
|
#define SDPOWER -1
|
||||||
|
#define HEATER_2_PIN -1
|
||||||
|
|
||||||
|
#define HEATER_0_PIN 3
|
||||||
|
#define HEATER_BED_PIN 4
|
||||||
|
#define FAN_1_PIN -1 //6
|
||||||
|
#define PS_ON_PIN 71
|
||||||
|
#define MOTOR_CURRENT_PWM_XY_PIN 46
|
||||||
|
#define MOTOR_CURRENT_PWM_Z_PIN 45
|
||||||
|
#define MOTOR_CURRENT_PWM_E_PIN 44
|
|
@ -593,7 +593,7 @@ float junction_deviation = 0.1;
|
||||||
// Add a new linear movement to the buffer. steps_x, _y and _z is the absolute position in
|
// Add a new linear movement to the buffer. steps_x, _y and _z is the absolute position in
|
||||||
// mm. Microseconds specify how many microseconds the move should take to perform. To aid acceleration
|
// mm. Microseconds specify how many microseconds the move should take to perform. To aid acceleration
|
||||||
// calculation the caller must also provide the physical length of the line in millimeters.
|
// calculation the caller must also provide the physical length of the line in millimeters.
|
||||||
void plan_buffer_line(float x, float y, float z, const float &e, float feed_rate, const uint8_t &extruder)
|
void plan_buffer_line(float x, float y, float z, const float &e, float feed_rate, const uint8_t &extruder, uint8_t sdlen)
|
||||||
{
|
{
|
||||||
// Calculate the buffer head after we push this byte
|
// Calculate the buffer head after we push this byte
|
||||||
int next_buffer_head = next_block_index(block_buffer_head);
|
int next_buffer_head = next_block_index(block_buffer_head);
|
||||||
|
@ -723,6 +723,9 @@ void plan_buffer_line(float x, float y, float z, const float &e, float feed_rate
|
||||||
// Prepare to set up new block
|
// Prepare to set up new block
|
||||||
block_t *block = &block_buffer[block_buffer_head];
|
block_t *block = &block_buffer[block_buffer_head];
|
||||||
|
|
||||||
|
// Set sdlen for calculating sd position
|
||||||
|
block->sdlen = sdlen;
|
||||||
|
|
||||||
// Mark block as not busy (Not executed by the stepper interrupt, could be still tinkered with.)
|
// Mark block as not busy (Not executed by the stepper interrupt, could be still tinkered with.)
|
||||||
block->busy = false;
|
block->busy = false;
|
||||||
|
|
||||||
|
@ -1296,3 +1299,16 @@ void planner_queue_min_reset()
|
||||||
g_cntr_planner_queue_min = moves_planned();
|
g_cntr_planner_queue_min = moves_planned();
|
||||||
}
|
}
|
||||||
#endif /* PLANNER_DIAGNOSTICS */
|
#endif /* PLANNER_DIAGNOSTICS */
|
||||||
|
|
||||||
|
uint16_t planner_calc_sd_length()
|
||||||
|
{
|
||||||
|
unsigned char _block_buffer_head = block_buffer_head;
|
||||||
|
unsigned char _block_buffer_tail = block_buffer_tail;
|
||||||
|
uint16_t sdlen = 0;
|
||||||
|
while (_block_buffer_head != _block_buffer_tail)
|
||||||
|
{
|
||||||
|
sdlen += block_buffer[_block_buffer_tail].sdlen;
|
||||||
|
_block_buffer_tail = (_block_buffer_tail + 1) & (BLOCK_BUFFER_SIZE - 1);
|
||||||
|
}
|
||||||
|
return sdlen;
|
||||||
|
}
|
||||||
|
|
|
@ -93,6 +93,8 @@ typedef struct {
|
||||||
bool use_advance_lead;
|
bool use_advance_lead;
|
||||||
unsigned long abs_adv_steps_multiplier8; // Factorised by 2^8 to avoid float
|
unsigned long abs_adv_steps_multiplier8; // Factorised by 2^8 to avoid float
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
uint8_t sdlen;
|
||||||
} block_t;
|
} block_t;
|
||||||
|
|
||||||
#ifdef LIN_ADVANCE
|
#ifdef LIN_ADVANCE
|
||||||
|
@ -111,12 +113,12 @@ void plan_init();
|
||||||
// millimaters. Feed rate specifies the speed of the motion.
|
// millimaters. Feed rate specifies the speed of the motion.
|
||||||
|
|
||||||
#ifdef ENABLE_AUTO_BED_LEVELING
|
#ifdef ENABLE_AUTO_BED_LEVELING
|
||||||
void plan_buffer_line(float x, float y, float z, const float &e, float feed_rate, const uint8_t &extruder);
|
void plan_buffer_line(float x, float y, float z, const float &e, float feed_rate, const uint8_t &extruder, uint8_t sdlen = 0);
|
||||||
|
|
||||||
// Get the position applying the bed level matrix if enabled
|
// Get the position applying the bed level matrix if enabled
|
||||||
vector_3 plan_get_position();
|
vector_3 plan_get_position();
|
||||||
#else
|
#else
|
||||||
void plan_buffer_line(float x, float y, float z, const float &e, float feed_rate, const uint8_t &extruder);
|
void plan_buffer_line(float x, float y, float z, const float &e, float feed_rate, const uint8_t &extruder, uint8_t sdlen = 0);
|
||||||
//void plan_buffer_line(const float &x, const float &y, const float &z, const float &e, float feed_rate, const uint8_t &extruder);
|
//void plan_buffer_line(const float &x, const float &y, const float &z, const float &e, float feed_rate, const uint8_t &extruder);
|
||||||
#endif // ENABLE_AUTO_BED_LEVELING
|
#endif // ENABLE_AUTO_BED_LEVELING
|
||||||
|
|
||||||
|
@ -217,3 +219,5 @@ extern uint8_t planner_queue_min();
|
||||||
// Diagnostic function: Reset the minimum planner segments.
|
// Diagnostic function: Reset the minimum planner segments.
|
||||||
extern void planner_queue_min_reset();
|
extern void planner_queue_min_reset();
|
||||||
#endif /* PLANNER_DIAGNOSTICS */
|
#endif /* PLANNER_DIAGNOSTICS */
|
||||||
|
|
||||||
|
extern uint16_t planner_calc_sd_length();
|
||||||
|
|
|
@ -32,9 +32,9 @@
|
||||||
#if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1
|
#if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1
|
||||||
#include <SPI.h>
|
#include <SPI.h>
|
||||||
#endif
|
#endif
|
||||||
#ifdef HAVE_TMC2130_DRIVERS
|
#ifdef TMC2130
|
||||||
#include "tmc2130.h"
|
#include "tmc2130.h"
|
||||||
#endif //HAVE_TMC2130_DRIVERS
|
#endif //TMC2130
|
||||||
|
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
@ -45,6 +45,8 @@ bool x_min_endstop = false;
|
||||||
bool x_max_endstop = false;
|
bool x_max_endstop = false;
|
||||||
bool y_min_endstop = false;
|
bool y_min_endstop = false;
|
||||||
bool y_max_endstop = false;
|
bool y_max_endstop = false;
|
||||||
|
bool z_min_endstop = false;
|
||||||
|
bool z_max_endstop = false;
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=============================private variables ============================
|
//=============================private variables ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
@ -85,11 +87,7 @@ static bool old_y_max_endstop=false;
|
||||||
static bool old_z_min_endstop=false;
|
static bool old_z_min_endstop=false;
|
||||||
static bool old_z_max_endstop=false;
|
static bool old_z_max_endstop=false;
|
||||||
|
|
||||||
#ifdef TMC2130_SG_HOMING_SW
|
|
||||||
static bool check_endstops = false;
|
|
||||||
#else
|
|
||||||
static bool check_endstops = true;
|
static bool check_endstops = true;
|
||||||
#endif
|
|
||||||
|
|
||||||
static bool check_z_endstop = false;
|
static bool check_z_endstop = false;
|
||||||
|
|
||||||
|
@ -431,12 +429,12 @@ void isr() {
|
||||||
CHECK_ENDSTOPS
|
CHECK_ENDSTOPS
|
||||||
{
|
{
|
||||||
{
|
{
|
||||||
#if defined(X_MIN_PIN) && X_MIN_PIN > -1
|
#if defined(X_MIN_PIN) && (X_MIN_PIN > -1) && !defined(DEBUG_DISABLE_XMINLIMIT)
|
||||||
#ifndef TMC2130_SG_HOMING_SW
|
#ifndef TMC2130_SG_HOMING_SW_XY
|
||||||
x_min_endstop = (READ(X_MIN_PIN) != X_MIN_ENDSTOP_INVERTING);
|
x_min_endstop = (READ(X_MIN_PIN) != X_MIN_ENDSTOP_INVERTING);
|
||||||
#else //TMC2130_SG_HOMING_SW
|
#else //TMC2130_SG_HOMING_SW_XY
|
||||||
x_min_endstop = tmc2130_axis_stalled[X_AXIS];
|
x_min_endstop = tmc2130_axis_stalled[X_AXIS];
|
||||||
#endif //TMC2130_SG_HOMING_SW
|
#endif //TMC2130_SG_HOMING_SW_XY
|
||||||
if(x_min_endstop && old_x_min_endstop && (current_block->steps_x > 0)) {
|
if(x_min_endstop && old_x_min_endstop && (current_block->steps_x > 0)) {
|
||||||
endstops_trigsteps[X_AXIS] = count_position[X_AXIS];
|
endstops_trigsteps[X_AXIS] = count_position[X_AXIS];
|
||||||
endstop_x_hit=true;
|
endstop_x_hit=true;
|
||||||
|
@ -451,12 +449,12 @@ void isr() {
|
||||||
CHECK_ENDSTOPS
|
CHECK_ENDSTOPS
|
||||||
{
|
{
|
||||||
{
|
{
|
||||||
#if defined(X_MAX_PIN) && X_MAX_PIN > -1
|
#if defined(X_MAX_PIN) && (X_MAX_PIN > -1) && !defined(DEBUG_DISABLE_XMAXLIMIT)
|
||||||
#ifndef TMC2130_SG_HOMING_SW
|
#ifndef TMC2130_SG_HOMING_SW_XY
|
||||||
x_max_endstop = (READ(X_MAX_PIN) != X_MAX_ENDSTOP_INVERTING);
|
x_max_endstop = (READ(X_MAX_PIN) != X_MAX_ENDSTOP_INVERTING);
|
||||||
#else //TMC2130_SG_HOMING_SW
|
#else //TMC2130_SG_HOMING_SW_XY
|
||||||
x_max_endstop = tmc2130_axis_stalled[X_AXIS];
|
x_max_endstop = tmc2130_axis_stalled[X_AXIS];
|
||||||
#endif //TMC2130_SG_HOMING_SW
|
#endif //TMC2130_SG_HOMING_SW_XY
|
||||||
if(x_max_endstop && old_x_max_endstop && (current_block->steps_x > 0)){
|
if(x_max_endstop && old_x_max_endstop && (current_block->steps_x > 0)){
|
||||||
endstops_trigsteps[X_AXIS] = count_position[X_AXIS];
|
endstops_trigsteps[X_AXIS] = count_position[X_AXIS];
|
||||||
endstop_x_hit=true;
|
endstop_x_hit=true;
|
||||||
|
@ -475,12 +473,12 @@ void isr() {
|
||||||
#endif
|
#endif
|
||||||
CHECK_ENDSTOPS
|
CHECK_ENDSTOPS
|
||||||
{
|
{
|
||||||
#if defined(Y_MIN_PIN) && Y_MIN_PIN > -1
|
#if defined(Y_MIN_PIN) && (Y_MIN_PIN > -1) && !defined(DEBUG_DISABLE_YMINLIMIT)
|
||||||
#ifndef TMC2130_SG_HOMING_SW
|
#ifndef TMC2130_SG_HOMING_SW_XY
|
||||||
y_min_endstop=(READ(Y_MIN_PIN) != Y_MIN_ENDSTOP_INVERTING);
|
y_min_endstop=(READ(Y_MIN_PIN) != Y_MIN_ENDSTOP_INVERTING);
|
||||||
#else //TMC2130_SG_HOMING_SW
|
#else //TMC2130_SG_HOMING_SW_XY
|
||||||
y_min_endstop = tmc2130_axis_stalled[Y_AXIS];
|
y_min_endstop = tmc2130_axis_stalled[Y_AXIS];
|
||||||
#endif //TMC2130_SG_HOMING_SW
|
#endif //TMC2130_SG_HOMING_SW_XY
|
||||||
if(y_min_endstop && old_y_min_endstop && (current_block->steps_y > 0)) {
|
if(y_min_endstop && old_y_min_endstop && (current_block->steps_y > 0)) {
|
||||||
endstops_trigsteps[Y_AXIS] = count_position[Y_AXIS];
|
endstops_trigsteps[Y_AXIS] = count_position[Y_AXIS];
|
||||||
endstop_y_hit=true;
|
endstop_y_hit=true;
|
||||||
|
@ -493,12 +491,12 @@ void isr() {
|
||||||
else { // +direction
|
else { // +direction
|
||||||
CHECK_ENDSTOPS
|
CHECK_ENDSTOPS
|
||||||
{
|
{
|
||||||
#if defined(Y_MAX_PIN) && Y_MAX_PIN > -1
|
#if defined(Y_MAX_PIN) && (Y_MAX_PIN > -1) && !defined(DEBUG_DISABLE_YMAXLIMIT)
|
||||||
#ifndef TMC2130_SG_HOMING_SW
|
#ifndef TMC2130_SG_HOMING_SW_XY
|
||||||
y_max_endstop=(READ(Y_MAX_PIN) != Y_MAX_ENDSTOP_INVERTING);
|
y_max_endstop=(READ(Y_MAX_PIN) != Y_MAX_ENDSTOP_INVERTING);
|
||||||
#else //TMC2130_SG_HOMING_SW
|
#else //TMC2130_SG_HOMING_SW_XY
|
||||||
y_max_endstop = tmc2130_axis_stalled[Y_AXIS];
|
y_max_endstop = tmc2130_axis_stalled[Y_AXIS];
|
||||||
#endif //TMC2130_SG_HOMING_SW
|
#endif //TMC2130_SG_HOMING_SW_XY
|
||||||
if(y_max_endstop && old_y_max_endstop && (current_block->steps_y > 0)){
|
if(y_max_endstop && old_y_max_endstop && (current_block->steps_y > 0)){
|
||||||
endstops_trigsteps[Y_AXIS] = count_position[Y_AXIS];
|
endstops_trigsteps[Y_AXIS] = count_position[Y_AXIS];
|
||||||
endstop_y_hit=true;
|
endstop_y_hit=true;
|
||||||
|
@ -519,8 +517,8 @@ void isr() {
|
||||||
count_direction[Z_AXIS]=-1;
|
count_direction[Z_AXIS]=-1;
|
||||||
if(check_endstops && ! check_z_endstop)
|
if(check_endstops && ! check_z_endstop)
|
||||||
{
|
{
|
||||||
#if defined(Z_MIN_PIN) && Z_MIN_PIN > -1
|
#if defined(Z_MIN_PIN) && (Z_MIN_PIN > -1) && !defined(DEBUG_DISABLE_ZMINLIMIT)
|
||||||
bool z_min_endstop=(READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING);
|
z_min_endstop=(READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING);
|
||||||
if(z_min_endstop && old_z_min_endstop && (current_block->steps_z > 0)) {
|
if(z_min_endstop && old_z_min_endstop && (current_block->steps_z > 0)) {
|
||||||
endstops_trigsteps[Z_AXIS] = count_position[Z_AXIS];
|
endstops_trigsteps[Z_AXIS] = count_position[Z_AXIS];
|
||||||
endstop_z_hit=true;
|
endstop_z_hit=true;
|
||||||
|
@ -540,8 +538,12 @@ void isr() {
|
||||||
count_direction[Z_AXIS]=1;
|
count_direction[Z_AXIS]=1;
|
||||||
CHECK_ENDSTOPS
|
CHECK_ENDSTOPS
|
||||||
{
|
{
|
||||||
#if defined(Z_MAX_PIN) && Z_MAX_PIN > -1
|
#if defined(Z_MAX_PIN) && (Z_MAX_PIN > -1) && !defined(DEBUG_DISABLE_ZMAXLIMIT)
|
||||||
bool z_max_endstop=(READ(Z_MAX_PIN) != Z_MAX_ENDSTOP_INVERTING);
|
#ifndef TMC2130_SG_HOMING_SW_Z
|
||||||
|
z_max_endstop = (READ(Z_MAX_PIN) != Z_MAX_ENDSTOP_INVERTING);
|
||||||
|
#else //TMC2130_SG_HOMING_SW_Z
|
||||||
|
z_max_endstop = tmc2130_axis_stalled[Z_AXIS];
|
||||||
|
#endif //TMC2130_SG_HOMING_SW_Z
|
||||||
if(z_max_endstop && old_z_max_endstop && (current_block->steps_z > 0)) {
|
if(z_max_endstop && old_z_max_endstop && (current_block->steps_z > 0)) {
|
||||||
endstops_trigsteps[Z_AXIS] = count_position[Z_AXIS];
|
endstops_trigsteps[Z_AXIS] = count_position[Z_AXIS];
|
||||||
endstop_z_hit=true;
|
endstop_z_hit=true;
|
||||||
|
@ -553,11 +555,11 @@ void isr() {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Supporting stopping on a trigger of the Z-stop induction sensor, not only for the Z-minus movements.
|
// Supporting stopping on a trigger of the Z-stop induction sensor, not only for the Z-minus movements.
|
||||||
#if defined(Z_MIN_PIN) && Z_MIN_PIN > -1
|
#if defined(Z_MIN_PIN) && (Z_MIN_PIN > -1) && !defined(DEBUG_DISABLE_ZMINLIMIT)
|
||||||
if(check_z_endstop) {
|
if(check_z_endstop) {
|
||||||
// Check the Z min end-stop no matter what.
|
// Check the Z min end-stop no matter what.
|
||||||
// Good for searching for the center of an induction target.
|
// Good for searching for the center of an induction target.
|
||||||
bool z_min_endstop=(READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING);
|
z_min_endstop=(READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING);
|
||||||
if(z_min_endstop && old_z_min_endstop) {
|
if(z_min_endstop && old_z_min_endstop) {
|
||||||
endstops_trigsteps[Z_AXIS] = count_position[Z_AXIS];
|
endstops_trigsteps[Z_AXIS] = count_position[Z_AXIS];
|
||||||
endstop_z_hit=true;
|
endstop_z_hit=true;
|
||||||
|
@ -829,9 +831,9 @@ void clear_current_adv_vars() {
|
||||||
|
|
||||||
void st_init()
|
void st_init()
|
||||||
{
|
{
|
||||||
#ifdef HAVE_TMC2130_DRIVERS
|
#ifdef TMC2130
|
||||||
tmc2130_init();
|
tmc2130_init();
|
||||||
#endif //HAVE_TMC2130_DRIVERS
|
#endif //TMC2130
|
||||||
|
|
||||||
digipot_init(); //Initialize Digipot Motor Current
|
digipot_init(); //Initialize Digipot Motor Current
|
||||||
microstep_init(); //Initialize Microstepping Pins
|
microstep_init(); //Initialize Microstepping Pins
|
||||||
|
@ -1042,7 +1044,7 @@ void st_synchronize()
|
||||||
{
|
{
|
||||||
while(blocks_queued())
|
while(blocks_queued())
|
||||||
{
|
{
|
||||||
#ifdef HAVE_TMC2130_DRIVERS
|
#ifdef TMC2130
|
||||||
manage_heater();
|
manage_heater();
|
||||||
// Vojtech: Don't disable motors inside the planner!
|
// Vojtech: Don't disable motors inside the planner!
|
||||||
if (!tmc2130_update_sg())
|
if (!tmc2130_update_sg())
|
||||||
|
@ -1050,12 +1052,12 @@ void st_synchronize()
|
||||||
manage_inactivity(true);
|
manage_inactivity(true);
|
||||||
lcd_update();
|
lcd_update();
|
||||||
}
|
}
|
||||||
#else //HAVE_TMC2130_DRIVERS
|
#else //TMC2130
|
||||||
manage_heater();
|
manage_heater();
|
||||||
// Vojtech: Don't disable motors inside the planner!
|
// Vojtech: Don't disable motors inside the planner!
|
||||||
manage_inactivity(true);
|
manage_inactivity(true);
|
||||||
lcd_update();
|
lcd_update();
|
||||||
#endif //HAVE_TMC2130_DRIVERS
|
#endif //TMC2130
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
209
Firmware/swi2c.cpp
Normal file
209
Firmware/swi2c.cpp
Normal file
|
@ -0,0 +1,209 @@
|
||||||
|
#include "uni_avr_rpi.h"
|
||||||
|
|
||||||
|
#ifdef SWI2C
|
||||||
|
#include "swi2c.h"
|
||||||
|
|
||||||
|
#ifdef __AVR
|
||||||
|
unsigned char swi2c_sda = 20; // SDA pin
|
||||||
|
unsigned char swi2c_scl = 21; // SCL pin
|
||||||
|
#endif //__AVR
|
||||||
|
|
||||||
|
#ifdef __RPI
|
||||||
|
unsigned char swi2c_sda = 2; // SDA pin
|
||||||
|
unsigned char swi2c_scl = 3; // SCL pin
|
||||||
|
#endif //__RPI
|
||||||
|
|
||||||
|
unsigned char swi2c_cfg = 0xb1; // config
|
||||||
|
// bit0..3 = clock delay factor = 1 << 1 = 2 [us]
|
||||||
|
// bit4..7 = ack timeout factor = 1 << 11 = 2048 [cycles]
|
||||||
|
|
||||||
|
#define SWI2C_SDA swi2c_sda
|
||||||
|
#define SWI2C_SCL swi2c_scl
|
||||||
|
#define SWI2C_RMSK 0x01 //read mask (bit0 = 1)
|
||||||
|
#define SWI2C_WMSK 0x00 //write mask (bit0 = 0)
|
||||||
|
#define SWI2C_ASHF 0x01 //address shift (<< 1)
|
||||||
|
#define SWI2C_DMSK 0x7f //device address mask
|
||||||
|
|
||||||
|
|
||||||
|
void swi2c_init(unsigned char sda, unsigned char scl, unsigned char cfg)
|
||||||
|
{
|
||||||
|
swi2c_sda = sda;
|
||||||
|
swi2c_scl = scl;
|
||||||
|
swi2c_cfg = cfg;
|
||||||
|
GPIO_OUT(SWI2C_SDA);
|
||||||
|
GPIO_OUT(SWI2C_SCL);
|
||||||
|
GPIO_SET(SWI2C_SDA);
|
||||||
|
GPIO_SET(SWI2C_SCL);
|
||||||
|
DELAY(1000);
|
||||||
|
}
|
||||||
|
|
||||||
|
void swi2c_start(int delay)
|
||||||
|
{
|
||||||
|
GPIO_CLR(SWI2C_SDA);
|
||||||
|
DELAY(delay);
|
||||||
|
GPIO_CLR(SWI2C_SCL);
|
||||||
|
DELAY(delay);
|
||||||
|
}
|
||||||
|
|
||||||
|
void swi2c_stop(int delay)
|
||||||
|
{
|
||||||
|
GPIO_SET(SWI2C_SCL);
|
||||||
|
DELAY(delay);
|
||||||
|
GPIO_SET(SWI2C_SDA);
|
||||||
|
DELAY(delay);
|
||||||
|
}
|
||||||
|
|
||||||
|
void swi2c_ack(int delay)
|
||||||
|
{
|
||||||
|
GPIO_CLR(SWI2C_SDA);
|
||||||
|
DELAY(delay);
|
||||||
|
GPIO_SET(SWI2C_SCL);
|
||||||
|
DELAY(delay);
|
||||||
|
GPIO_CLR(SWI2C_SCL);
|
||||||
|
DELAY(delay);
|
||||||
|
}
|
||||||
|
|
||||||
|
int swi2c_wait_ack(int delay, int ackto)
|
||||||
|
{
|
||||||
|
GPIO_INP(SWI2C_SDA);
|
||||||
|
DELAY(delay);
|
||||||
|
// GPIO_SET(SWI2C_SDA);
|
||||||
|
DELAY(delay);
|
||||||
|
GPIO_SET(SWI2C_SCL);
|
||||||
|
// DELAY(delay);
|
||||||
|
int ack = 0;
|
||||||
|
while (!(ack = !GPIO_GET(SWI2C_SDA)) && ackto--) DELAY(delay);
|
||||||
|
GPIO_CLR(SWI2C_SCL);
|
||||||
|
DELAY(delay);
|
||||||
|
GPIO_OUT(SWI2C_SDA);
|
||||||
|
DELAY(delay);
|
||||||
|
GPIO_CLR(SWI2C_SDA);
|
||||||
|
DELAY(delay);
|
||||||
|
return ack;
|
||||||
|
}
|
||||||
|
|
||||||
|
unsigned char swi2c_read(int delay)
|
||||||
|
{
|
||||||
|
GPIO_SET(SWI2C_SDA);
|
||||||
|
DELAY(delay);
|
||||||
|
GPIO_INP(SWI2C_SDA);
|
||||||
|
unsigned char data = 0;
|
||||||
|
int bit; for (bit = 7; bit >= 0; bit--)
|
||||||
|
{
|
||||||
|
GPIO_SET(SWI2C_SCL);
|
||||||
|
DELAY(delay);
|
||||||
|
data |= GPIO_GET(SWI2C_SDA) << bit;
|
||||||
|
GPIO_CLR(SWI2C_SCL);
|
||||||
|
DELAY(delay);
|
||||||
|
}
|
||||||
|
GPIO_OUT(SWI2C_SDA);
|
||||||
|
return data;
|
||||||
|
}
|
||||||
|
|
||||||
|
void swi2c_write(int delay, unsigned char data)
|
||||||
|
{
|
||||||
|
int bit; for (bit = 7; bit >= 0; bit--)
|
||||||
|
{
|
||||||
|
if (data & (1 << bit)) GPIO_SET(SWI2C_SDA);
|
||||||
|
else GPIO_CLR(SWI2C_SDA);
|
||||||
|
DELAY(delay);
|
||||||
|
GPIO_SET(SWI2C_SCL);
|
||||||
|
DELAY(delay);
|
||||||
|
GPIO_CLR(SWI2C_SCL);
|
||||||
|
DELAY(delay);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
int swi2c_check(unsigned char dev_addr)
|
||||||
|
{
|
||||||
|
int delay = 1 << (swi2c_cfg & 0xf);
|
||||||
|
int tmout = 1 << (swi2c_cfg >> 4);
|
||||||
|
swi2c_start(delay);
|
||||||
|
swi2c_write(delay, (dev_addr & SWI2C_DMSK) << SWI2C_ASHF);
|
||||||
|
if (!swi2c_wait_ack(delay, tmout)) { swi2c_stop(delay); return 0; }
|
||||||
|
swi2c_stop(delay);
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef SWI2C_A8 //8bit address
|
||||||
|
|
||||||
|
int swi2c_readByte_A8(unsigned char dev_addr, unsigned char addr, unsigned char* pbyte)
|
||||||
|
{
|
||||||
|
int delay = 1 << (swi2c_cfg & 0xf);
|
||||||
|
int tmout = 1 << (swi2c_cfg >> 4);
|
||||||
|
swi2c_start(delay);
|
||||||
|
swi2c_write(delay, SWI2C_WMSK | ((dev_addr & SWI2C_DMSK) << SWI2C_ASHF));
|
||||||
|
if (!swi2c_wait_ack(delay, tmout)) { swi2c_stop(delay); return 0; }
|
||||||
|
swi2c_write(delay, addr & 0xff);
|
||||||
|
if (!swi2c_wait_ack(delay, tmout)) return 0;
|
||||||
|
swi2c_stop(delay);
|
||||||
|
swi2c_start(delay);
|
||||||
|
swi2c_write(delay, SWI2C_RMSK | ((dev_addr & SWI2C_DMSK) << SWI2C_ASHF));
|
||||||
|
if (!swi2c_wait_ack(delay, tmout)) return 0;
|
||||||
|
unsigned char byte = swi2c_read(delay);
|
||||||
|
swi2c_stop(delay);
|
||||||
|
if (pbyte) *pbyte = byte;
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
int swi2c_writeByte_A8(unsigned char dev_addr, unsigned char addr, unsigned char* pbyte)
|
||||||
|
{
|
||||||
|
int delay = 1 << (swi2c_cfg & 0xf);
|
||||||
|
int tmout = 1 << (swi2c_cfg >> 4);
|
||||||
|
swi2c_start(delay);
|
||||||
|
swi2c_write(delay, SWI2C_WMSK | ((dev_addr & SWI2C_DMSK) << SWI2C_ASHF));
|
||||||
|
if (!swi2c_wait_ack(delay, tmout)) { swi2c_stop(delay); return 0; }
|
||||||
|
swi2c_write(delay, addr & 0xff);
|
||||||
|
if (!swi2c_wait_ack(delay, tmout)) return 0;
|
||||||
|
swi2c_write(delay, *pbyte);
|
||||||
|
if (!swi2c_wait_ack(delay, tmout)) return 0;
|
||||||
|
swi2c_stop(delay);
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif //SWI2C_A8
|
||||||
|
|
||||||
|
#ifdef SWI2C_A16 //16bit address
|
||||||
|
|
||||||
|
int swi2c_readByte_A16(unsigned char dev_addr, unsigned short addr, unsigned char* pbyte)
|
||||||
|
{
|
||||||
|
int delay = 1 << (swi2c_cfg & 0xf);
|
||||||
|
int tmout = 1 << (swi2c_cfg >> 4);
|
||||||
|
swi2c_start(delay);
|
||||||
|
swi2c_write(delay, SWI2C_WMSK | ((dev_addr & SWI2C_DMSK) << SWI2C_ASHF));
|
||||||
|
if (!swi2c_wait_ack(delay, tmout)) { swi2c_stop(delay); return 0; }
|
||||||
|
swi2c_write(delay, addr >> 8);
|
||||||
|
if (!swi2c_wait_ack(delay, tmout)) return 0;
|
||||||
|
swi2c_write(delay, addr & 0xff);
|
||||||
|
if (!swi2c_wait_ack(delay, tmout)) return 0;
|
||||||
|
swi2c_stop(delay);
|
||||||
|
swi2c_start(delay);
|
||||||
|
swi2c_write(delay, SWI2C_RMSK | ((dev_addr & SWI2C_DMSK) << SWI2C_ASHF));
|
||||||
|
if (!swi2c_wait_ack(delay, tmout)) return 0;
|
||||||
|
unsigned char byte = swi2c_read(delay);
|
||||||
|
swi2c_stop(delay);
|
||||||
|
if (pbyte) *pbyte = byte;
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
int swi2c_writeByte_A16(unsigned char dev_addr, unsigned short addr, unsigned char* pbyte)
|
||||||
|
{
|
||||||
|
int delay = 1 << (swi2c_cfg & 0xf);
|
||||||
|
int tmout = 1 << (swi2c_cfg >> 4);
|
||||||
|
swi2c_start(delay);
|
||||||
|
swi2c_write(delay, SWI2C_WMSK | ((dev_addr & SWI2C_DMSK) << SWI2C_ASHF));
|
||||||
|
if (!swi2c_wait_ack(delay, tmout)) { swi2c_stop(delay); return 0; }
|
||||||
|
swi2c_write(delay, addr >> 8);
|
||||||
|
if (!swi2c_wait_ack(delay, tmout)) return 0;
|
||||||
|
swi2c_write(delay, addr & 0xff);
|
||||||
|
if (!swi2c_wait_ack(delay, tmout)) return 0;
|
||||||
|
swi2c_write(delay, *pbyte);
|
||||||
|
if (!swi2c_wait_ack(delay, tmout)) return 0;
|
||||||
|
swi2c_stop(delay);
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif //SWI2C_A16
|
||||||
|
|
||||||
|
|
||||||
|
#endif //SWI2C
|
22
Firmware/swi2c.h
Normal file
22
Firmware/swi2c.h
Normal file
|
@ -0,0 +1,22 @@
|
||||||
|
#ifndef SWI2C_H
|
||||||
|
#define SWI2C_H
|
||||||
|
|
||||||
|
//initialize
|
||||||
|
extern void swi2c_init(unsigned char sda, unsigned char scl, unsigned char cfg);
|
||||||
|
|
||||||
|
//check device address acknowledge
|
||||||
|
extern int swi2c_check(unsigned char dev_addr);
|
||||||
|
|
||||||
|
//read write functions - 8bit address (most i2c chips)
|
||||||
|
#ifdef SWI2C_A8
|
||||||
|
extern int swi2c_readByte_A8(unsigned char dev_addr, unsigned char addr, unsigned char* pbyte);
|
||||||
|
extern int swi2c_writeByte_A8(unsigned char dev_addr, unsigned char addr, unsigned char* pbyte);
|
||||||
|
#endif //SWI2C_A8
|
||||||
|
|
||||||
|
//read write functions - 16bit address (e.g. serial eeprom AT24C256)
|
||||||
|
#ifdef SWI2C_A16
|
||||||
|
extern int swi2c_readByte_A16(unsigned char dev_addr, unsigned short addr, unsigned char* pbyte);
|
||||||
|
extern int swi2c_writeByte_A16(unsigned char dev_addr, unsigned short addr, unsigned char* pbyte);
|
||||||
|
#endif //SWI2C_A16
|
||||||
|
|
||||||
|
#endif //SWI2C_H
|
|
@ -1,58 +1,54 @@
|
||||||
|
#include "uni_avr_rpi.h"
|
||||||
|
|
||||||
|
#ifdef __SWSPI
|
||||||
#include "swspi.h"
|
#include "swspi.h"
|
||||||
|
|
||||||
|
#ifdef __RPI
|
||||||
#ifdef SWSPI_RPI
|
//#define swspi_miso 9
|
||||||
#include <bcm2835.h>
|
#define swspi_miso 10
|
||||||
#define GPIO_INP(gpio) bcm2835_gpio_fsel(gpio, BCM2835_GPIO_FSEL_INPT)
|
#define swspi_mosi 10
|
||||||
#define GPIO_OUT(gpio) bcm2835_gpio_fsel(gpio, BCM2835_GPIO_FSEL_OUTP)
|
#define swspi_sck 11
|
||||||
#define GPIO_SET(gpio) bcm2835_gpio_write(gpio, HIGH)
|
#define SWSPI_CS 7
|
||||||
#define GPIO_CLR(gpio) bcm2835_gpio_write(gpio, LOW)
|
#endif //__RPI
|
||||||
#define GPIO_GET(gpio) (bcm2835_gpio_lev(gpio) != LOW)
|
|
||||||
#define DELAY(delay) usleep(delay)
|
|
||||||
#endif //SWSPI_RPI
|
|
||||||
|
|
||||||
#ifdef SWSPI_AVR
|
|
||||||
#include "Arduino.h"
|
|
||||||
#define GPIO_INP(gpio) pinMode(gpio, INPUT)
|
|
||||||
#define GPIO_OUT(gpio) pinMode(gpio, OUTPUT)
|
|
||||||
#define GPIO_SET(gpio) digitalWrite(gpio, HIGH)
|
|
||||||
#define GPIO_CLR(gpio) digitalWrite(gpio, LOW)
|
|
||||||
#define GPIO_GET(gpio) (digitalRead(gpio) != LOW)
|
|
||||||
#define DELAY(delay) delayMicroseconds(delay)
|
|
||||||
#endif //SWSPI_AVR
|
|
||||||
|
|
||||||
#if (SWSPI_POL != 0)
|
|
||||||
#define SWSPI_SCK_UP GPIO_CLR(SWSPI_SCK)
|
|
||||||
#define SWSPI_SCK_DN GPIO_SET(SWSPI_SCK)
|
|
||||||
#else
|
|
||||||
#define SWSPI_SCK_UP GPIO_SET(SWSPI_SCK)
|
|
||||||
#define SWSPI_SCK_DN GPIO_CLR(SWSPI_SCK)
|
|
||||||
#endif
|
|
||||||
|
|
||||||
|
|
||||||
void swspi_init()
|
#define SWSPI_DEL 0x0f //delay mask (0-3. bit, delay = 1 << DEL [us])
|
||||||
|
#define SWSPI_POL 0x10 //polarity mask (4. bit, 1=inverted)
|
||||||
|
#define SWSPI_PHA 0x20 //phase mask (5. bit)
|
||||||
|
#define SWSPI_DOR 0x40 //data order mask (6. bit, 0=MSB first, 1=LSB first)
|
||||||
|
|
||||||
|
#define SWSPI_SCK_UP if (swspi_cfg & SWSPI_POL) GPIO_CLR(swspi_sck); else GPIO_SET(swspi_sck);
|
||||||
|
#define SWSPI_SCK_DN if (swspi_cfg & SWSPI_POL) GPIO_SET(swspi_sck); else GPIO_CLR(swspi_sck);
|
||||||
|
|
||||||
|
unsigned char swspi_miso = 0;
|
||||||
|
unsigned char swspi_mosi = 0;
|
||||||
|
unsigned char swspi_sck = 0;
|
||||||
|
unsigned char swspi_cfg = 0;
|
||||||
|
|
||||||
|
void swspi_init(unsigned char miso, unsigned char mosi, unsigned char sck, unsigned char cfg)
|
||||||
{
|
{
|
||||||
GPIO_INP(SWSPI_MISO);
|
swspi_miso = miso;
|
||||||
GPIO_OUT(SWSPI_MOSI);
|
swspi_mosi = mosi;
|
||||||
GPIO_OUT(SWSPI_SCK);
|
swspi_sck = sck;
|
||||||
GPIO_OUT(SWSPI_CS);
|
swspi_cfg = cfg;
|
||||||
GPIO_CLR(SWSPI_MOSI);
|
GPIO_INP(swspi_miso);
|
||||||
|
GPIO_OUT(swspi_mosi);
|
||||||
|
GPIO_OUT(swspi_sck);
|
||||||
|
GPIO_CLR(swspi_mosi);
|
||||||
SWSPI_SCK_DN;
|
SWSPI_SCK_DN;
|
||||||
GPIO_SET(SWSPI_CS);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#if (SWSPI_MOSI == SWSPI_MISO)
|
|
||||||
|
|
||||||
void swspi_tx(unsigned char tx)
|
void swspi_tx(unsigned char tx)
|
||||||
{
|
{
|
||||||
GPIO_OUT(SWSPI_MOSI);
|
int delay = 1 << (swspi_cfg & SWSPI_DEL));
|
||||||
|
if (swspi_miso == swspi_mosi) GPIO_OUT(swspi_mosi);
|
||||||
unsigned char i = 0; for (; i < 8; i++)
|
unsigned char i = 0; for (; i < 8; i++)
|
||||||
{
|
{
|
||||||
if (tx & 0x80) GPIO_SET(SWSPI_MOSI);
|
if (tx & 0x80) GPIO_SET(swspi_mosi);
|
||||||
else GPIO_CLR(SWSPI_MOSI);
|
else GPIO_CLR(swspi_mosi);
|
||||||
DELAY(SWSPI_DEL);
|
DELAY(delay);
|
||||||
SWSPI_SCK_UP;
|
SWSPI_SCK_UP;
|
||||||
DELAY(SWSPI_DEL);
|
DELAY(delay);
|
||||||
SWSPI_SCK_DN;
|
SWSPI_SCK_DN;
|
||||||
tx <<= 1;
|
tx <<= 1;
|
||||||
}
|
}
|
||||||
|
@ -60,48 +56,38 @@ void swspi_tx(unsigned char tx)
|
||||||
|
|
||||||
unsigned char swspi_rx()
|
unsigned char swspi_rx()
|
||||||
{
|
{
|
||||||
GPIO_INP(SWSPI_MISO);
|
int delay = 1 << (swspi_cfg & SWSPI_DEL));
|
||||||
|
if (swspi_miso == swspi_mosi) GPIO_OUT(swspi_mosi);
|
||||||
unsigned char rx = 0;
|
unsigned char rx = 0;
|
||||||
unsigned char i = 0; for (; i < 8; i++)
|
unsigned char i = 0; for (; i < 8; i++)
|
||||||
{
|
{
|
||||||
rx <<= 1;
|
rx <<= 1;
|
||||||
DELAY(SWSPI_DEL);
|
DELAY(delay);
|
||||||
SWSPI_SCK_UP;
|
SWSPI_SCK_UP;
|
||||||
DELAY(SWSPI_DEL);
|
DELAY(delay);
|
||||||
rx |= GPIO_GET(SWSPI_MISO)?1:0;
|
rx |= GPIO_GET(swspi_miso)?1:0;
|
||||||
SWSPI_SCK_DN;
|
SWSPI_SCK_DN;
|
||||||
}
|
}
|
||||||
return rx;
|
return rx;
|
||||||
}
|
}
|
||||||
|
|
||||||
#else //(SWSPI_MOSI == SWSPI_MISO)
|
|
||||||
|
|
||||||
unsigned char swspi_txrx(unsigned char tx)
|
unsigned char swspi_txrx(unsigned char tx)
|
||||||
{
|
{
|
||||||
|
int delay = 1 << (swspi_cfg & SWSPI_DEL));
|
||||||
unsigned char rx = 0;
|
unsigned char rx = 0;
|
||||||
unsigned char i = 0; for (; i < 8; i++)
|
unsigned char i = 0; for (; i < 8; i++)
|
||||||
{
|
{
|
||||||
rx <<= 1;
|
rx <<= 1;
|
||||||
if (tx & 0x80) GPIO_SET(SWSPI_MOSI);
|
if (tx & 0x80) GPIO_SET(swspi_mosi);
|
||||||
else GPIO_CLR(SWSPI_MOSI);
|
else GPIO_CLR(swspi_mosi);
|
||||||
DELAY(SWSPI_DEL);
|
DELAY(delay);
|
||||||
SWSPI_SCK_UP;
|
SWSPI_SCK_UP;
|
||||||
DELAY(SWSPI_DEL);
|
DELAY(delay);
|
||||||
rx |= GPIO_GET(SWSPI_MISO)?1:0;
|
rx |= GPIO_GET(swspi_miso)?1:0;
|
||||||
SWSPI_SCK_DN;
|
SWSPI_SCK_DN;
|
||||||
tx <<= 1;
|
tx <<= 1;
|
||||||
}
|
}
|
||||||
return rx;
|
return rx;
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif //(SWSPI_MOSI == SWSPI_MISO)
|
#endif //__SWSPI
|
||||||
|
|
||||||
void swspi_start()
|
|
||||||
{
|
|
||||||
GPIO_CLR(SWSPI_CS);
|
|
||||||
}
|
|
||||||
|
|
||||||
void swspi_stop()
|
|
||||||
{
|
|
||||||
GPIO_SET(SWSPI_CS);
|
|
||||||
}
|
|
||||||
|
|
|
@ -1,56 +1,14 @@
|
||||||
|
// Software SPI
|
||||||
#ifndef SWSPI_H
|
#ifndef SWSPI_H
|
||||||
#define SWSPI_H
|
#define SWSPI_H
|
||||||
|
|
||||||
|
//initialize gpio
|
||||||
//#define SWSPI_RPI
|
extern void swspi_init(unsigned char miso, unsigned char mosi, unsigned char sck, unsigned char cfg);
|
||||||
#define SWSPI_AVR
|
//transmit and receive (full duplex mode)
|
||||||
|
extern unsigned char swspi_txrx(unsigned char tx);
|
||||||
#ifdef SWSPI_RPI
|
//transmit (half dublex mode, miso == mosi)
|
||||||
//#define SWSPI_MISO 9
|
extern void swspi_tx(unsigned char tx);
|
||||||
#define SWSPI_MISO 10
|
//receive (half dublex mode, miso == mosi)
|
||||||
#define SWSPI_MOSI 10
|
extern unsigned char swspi_rx();
|
||||||
#define SWSPI_SCK 11
|
|
||||||
#define SWSPI_CS 7
|
|
||||||
#endif //SWSPI_RPI
|
|
||||||
|
|
||||||
#ifdef SWSPI_AVR
|
|
||||||
#if (MOTHERBOARD == BOARD_EINY_0_3a)
|
|
||||||
#define SWSPI_MISO 16 //RX2
|
|
||||||
#define SWSPI_MOSI 16 //RX2
|
|
||||||
#define SWSPI_SCK 17 //TX2
|
|
||||||
#define SWSPI_CS 20 //SDA
|
|
||||||
#endif //(MOTHERBOARD == BOARD_EINY_0_3a)
|
|
||||||
#if (MOTHERBOARD == BOARD_EINY_0_4a)
|
|
||||||
#define SWSPI_MISO 21 //PK0
|
|
||||||
#define SWSPI_MOSI 21 //PK0
|
|
||||||
#define SWSPI_SCK 62 //SCL
|
|
||||||
#define SWSPI_CS 20 //SDA
|
|
||||||
#endif //(MOTHERBOARD == BOARD_EINY_0_4a)
|
|
||||||
#endif //SWSPI_AVR
|
|
||||||
|
|
||||||
#define SWSPI_POL 1 //polarity
|
|
||||||
#define SWSPI_PHA 0 //phase
|
|
||||||
#define SWSPI_DOR 0 //data order
|
|
||||||
#define SWSPI_DEL 2 //delay
|
|
||||||
|
|
||||||
|
|
||||||
void swspi_init();
|
|
||||||
|
|
||||||
#if (SWSPI_MOSI == SWSPI_MISO)
|
|
||||||
|
|
||||||
void swspi_tx(unsigned char tx);
|
|
||||||
unsigned char swspi_rx();
|
|
||||||
|
|
||||||
#else //(SWSPI_MOSI == SWSPI_MISO)
|
|
||||||
|
|
||||||
#define swspi_tx swspi_txrx
|
|
||||||
#define swspi_rx swspi_txrx
|
|
||||||
unsigned char swspi_txrx(unsigned char tx);
|
|
||||||
|
|
||||||
#endif //(SWSPI_MOSI == SWSPI_MISO)
|
|
||||||
|
|
||||||
void swspi_start();
|
|
||||||
void swspi_stop();
|
|
||||||
|
|
||||||
|
|
||||||
#endif //SWSPI_H
|
#endif //SWSPI_H
|
||||||
|
|
|
@ -45,6 +45,17 @@ int target_temperature[EXTRUDERS] = { 0 };
|
||||||
int target_temperature_bed = 0;
|
int target_temperature_bed = 0;
|
||||||
int current_temperature_raw[EXTRUDERS] = { 0 };
|
int current_temperature_raw[EXTRUDERS] = { 0 };
|
||||||
float current_temperature[EXTRUDERS] = { 0.0 };
|
float current_temperature[EXTRUDERS] = { 0.0 };
|
||||||
|
|
||||||
|
#ifdef PINDA_THERMISTOR
|
||||||
|
int current_temperature_raw_pinda = 0 ;
|
||||||
|
float current_temperature_pinda = 0.0;
|
||||||
|
#endif //PINDA_THERMISTOR
|
||||||
|
|
||||||
|
#ifdef AMBIENT_THERMISTOR
|
||||||
|
int current_temperature_raw_ambient = 0 ;
|
||||||
|
float current_temperature_ambient = 0.0;
|
||||||
|
#endif //AMBIENT_THERMISTOR
|
||||||
|
|
||||||
int current_temperature_bed_raw = 0;
|
int current_temperature_bed_raw = 0;
|
||||||
float current_temperature_bed = 0.0;
|
float current_temperature_bed = 0.0;
|
||||||
#ifdef TEMP_SENSOR_1_AS_REDUNDANT
|
#ifdef TEMP_SENSOR_1_AS_REDUNDANT
|
||||||
|
@ -75,6 +86,11 @@ float current_temperature_bed = 0.0;
|
||||||
unsigned char fanSpeedSoftPwm;
|
unsigned char fanSpeedSoftPwm;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if defined(LCD_PWM_PIN) && (LCD_PWM_PIN > -1)
|
||||||
|
unsigned char lcdSoftPwm = (LCD_PWM_MAX * 2 + 1); //set default value to maximum
|
||||||
|
unsigned char lcdBlinkDelay = 0; //lcd blinking delay (0 = no blink)
|
||||||
|
#endif
|
||||||
|
|
||||||
unsigned char soft_pwm_bed;
|
unsigned char soft_pwm_bed;
|
||||||
|
|
||||||
#ifdef BABYSTEPPING
|
#ifdef BABYSTEPPING
|
||||||
|
@ -129,6 +145,12 @@ static volatile bool temp_meas_ready = false;
|
||||||
static unsigned long extruder_autofan_last_check;
|
static unsigned long extruder_autofan_last_check;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if defined(LCD_PWM_PIN) && (LCD_PWM_PIN > -1)
|
||||||
|
static unsigned char soft_pwm_lcd = 0;
|
||||||
|
static unsigned char lcd_blink_delay = 0;
|
||||||
|
static bool lcd_blink_on = false;
|
||||||
|
#endif
|
||||||
|
|
||||||
#if EXTRUDERS > 3
|
#if EXTRUDERS > 3
|
||||||
# error Unsupported number of extruders
|
# error Unsupported number of extruders
|
||||||
#elif EXTRUDERS > 2
|
#elif EXTRUDERS > 2
|
||||||
|
@ -161,6 +183,7 @@ static int bed_maxttemp_raw = HEATER_BED_RAW_HI_TEMP;
|
||||||
|
|
||||||
static float analog2temp(int raw, uint8_t e);
|
static float analog2temp(int raw, uint8_t e);
|
||||||
static float analog2tempBed(int raw);
|
static float analog2tempBed(int raw);
|
||||||
|
static float analog2tempAmbient(int raw);
|
||||||
static void updateTemperaturesFromRawValues();
|
static void updateTemperaturesFromRawValues();
|
||||||
|
|
||||||
enum TempRunawayStates
|
enum TempRunawayStates
|
||||||
|
@ -845,6 +868,27 @@ static float analog2tempBed(int raw) {
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static float analog2tempAmbient(int raw)
|
||||||
|
{
|
||||||
|
float celsius = 0;
|
||||||
|
byte i;
|
||||||
|
|
||||||
|
for (i=1; i<AMBIENTTEMPTABLE_LEN; i++)
|
||||||
|
{
|
||||||
|
if (PGM_RD_W(AMBIENTTEMPTABLE[i][0]) > raw)
|
||||||
|
{
|
||||||
|
celsius = PGM_RD_W(AMBIENTTEMPTABLE[i-1][1]) +
|
||||||
|
(raw - PGM_RD_W(AMBIENTTEMPTABLE[i-1][0])) *
|
||||||
|
(float)(PGM_RD_W(AMBIENTTEMPTABLE[i][1]) - PGM_RD_W(AMBIENTTEMPTABLE[i-1][1])) /
|
||||||
|
(float)(PGM_RD_W(AMBIENTTEMPTABLE[i][0]) - PGM_RD_W(AMBIENTTEMPTABLE[i-1][0]));
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
// Overflow: Set to last value in the table
|
||||||
|
if (i == AMBIENTTEMPTABLE_LEN) celsius = PGM_RD_W(AMBIENTTEMPTABLE[i-1][1]);
|
||||||
|
return celsius;
|
||||||
|
}
|
||||||
|
|
||||||
/* Called to get the raw values into the the actual temperatures. The raw values are created in interrupt context,
|
/* Called to get the raw values into the the actual temperatures. The raw values are created in interrupt context,
|
||||||
and this function is called from normal context as it is too slow to run in interrupts and will block the stepper routine otherwise */
|
and this function is called from normal context as it is too slow to run in interrupts and will block the stepper routine otherwise */
|
||||||
static void updateTemperaturesFromRawValues()
|
static void updateTemperaturesFromRawValues()
|
||||||
|
@ -854,6 +898,14 @@ static void updateTemperaturesFromRawValues()
|
||||||
current_temperature[e] = analog2temp(current_temperature_raw[e], e);
|
current_temperature[e] = analog2temp(current_temperature_raw[e], e);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#ifdef PINDA_THERMISTOR
|
||||||
|
current_temperature_pinda = analog2tempBed(current_temperature_raw_pinda); //thermistor for pinda is the same as for bed
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef AMBIENT_THERMISTOR
|
||||||
|
current_temperature_ambient = analog2tempAmbient(current_temperature_raw_ambient); //thermistor for ambient is NTCG104LH104JT1 (2000)
|
||||||
|
#endif
|
||||||
|
|
||||||
current_temperature_bed = analog2tempBed(current_temperature_bed_raw);
|
current_temperature_bed = analog2tempBed(current_temperature_bed_raw);
|
||||||
|
|
||||||
#ifdef TEMP_SENSOR_1_AS_REDUNDANT
|
#ifdef TEMP_SENSOR_1_AS_REDUNDANT
|
||||||
|
@ -941,6 +993,11 @@ void tp_init()
|
||||||
#endif
|
#endif
|
||||||
#ifdef FAN_SOFT_PWM
|
#ifdef FAN_SOFT_PWM
|
||||||
soft_pwm_fan = fanSpeedSoftPwm / 2;
|
soft_pwm_fan = fanSpeedSoftPwm / 2;
|
||||||
|
#endif
|
||||||
|
#if defined(LCD_PWM_PIN) && (LCD_PWM_PIN > -1)
|
||||||
|
soft_pwm_lcd = lcdSoftPwm / 2;
|
||||||
|
lcd_blink_delay = lcdBlinkDelay;
|
||||||
|
lcd_blink_on = true;
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -1469,7 +1526,9 @@ ISR(TIMER0_COMPB_vect)
|
||||||
static unsigned long raw_temp_1_value = 0;
|
static unsigned long raw_temp_1_value = 0;
|
||||||
static unsigned long raw_temp_2_value = 0;
|
static unsigned long raw_temp_2_value = 0;
|
||||||
static unsigned long raw_temp_bed_value = 0;
|
static unsigned long raw_temp_bed_value = 0;
|
||||||
static unsigned char temp_state = 10;
|
static unsigned long raw_temp_pinda_value = 0;
|
||||||
|
static unsigned long raw_temp_ambient_value = 0;
|
||||||
|
static unsigned char temp_state = 14;
|
||||||
static unsigned char pwm_count = (1 << SOFT_PWM_SCALE);
|
static unsigned char pwm_count = (1 << SOFT_PWM_SCALE);
|
||||||
static unsigned char soft_pwm_0;
|
static unsigned char soft_pwm_0;
|
||||||
#ifdef SLOW_PWM_HEATERS
|
#ifdef SLOW_PWM_HEATERS
|
||||||
|
@ -1507,15 +1566,16 @@ ISR(TIMER0_COMPB_vect)
|
||||||
/*
|
/*
|
||||||
* standard PWM modulation
|
* standard PWM modulation
|
||||||
*/
|
*/
|
||||||
if(pwm_count == 0){
|
if (pwm_count == 0)
|
||||||
|
{
|
||||||
soft_pwm_0 = soft_pwm[0];
|
soft_pwm_0 = soft_pwm[0];
|
||||||
if(soft_pwm_0 > 0) {
|
if(soft_pwm_0 > 0)
|
||||||
|
{
|
||||||
WRITE(HEATER_0_PIN,1);
|
WRITE(HEATER_0_PIN,1);
|
||||||
#ifdef HEATERS_PARALLEL
|
#ifdef HEATERS_PARALLEL
|
||||||
WRITE(HEATER_1_PIN,1);
|
WRITE(HEATER_1_PIN,1);
|
||||||
#endif
|
#endif
|
||||||
} else WRITE(HEATER_0_PIN,0);
|
} else WRITE(HEATER_0_PIN,0);
|
||||||
|
|
||||||
#if EXTRUDERS > 1
|
#if EXTRUDERS > 1
|
||||||
soft_pwm_1 = soft_pwm[1];
|
soft_pwm_1 = soft_pwm[1];
|
||||||
if(soft_pwm_1 > 0) WRITE(HEATER_1_PIN,1); else WRITE(HEATER_1_PIN,0);
|
if(soft_pwm_1 > 0) WRITE(HEATER_1_PIN,1); else WRITE(HEATER_1_PIN,0);
|
||||||
|
@ -1533,12 +1593,35 @@ ISR(TIMER0_COMPB_vect)
|
||||||
if(soft_pwm_fan > 0) WRITE(FAN_PIN,1); else WRITE(FAN_PIN,0);
|
if(soft_pwm_fan > 0) WRITE(FAN_PIN,1); else WRITE(FAN_PIN,0);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
if(soft_pwm_0 < pwm_count) {
|
if(soft_pwm_0 < pwm_count)
|
||||||
|
{
|
||||||
WRITE(HEATER_0_PIN,0);
|
WRITE(HEATER_0_PIN,0);
|
||||||
#ifdef HEATERS_PARALLEL
|
#ifdef HEATERS_PARALLEL
|
||||||
WRITE(HEATER_1_PIN,0);
|
WRITE(HEATER_1_PIN,0);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
#if defined(LCD_PWM_PIN) && (LCD_PWM_PIN > -1)
|
||||||
|
if ((pwm_count & LCD_PWM_MAX) == 0)
|
||||||
|
{
|
||||||
|
if (lcd_blink_delay)
|
||||||
|
{
|
||||||
|
lcd_blink_delay--;
|
||||||
|
if (lcd_blink_delay == 0)
|
||||||
|
{
|
||||||
|
lcd_blink_delay = lcdBlinkDelay;
|
||||||
|
lcd_blink_on = !lcd_blink_on;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
lcd_blink_delay = lcdBlinkDelay;
|
||||||
|
lcd_blink_on = true;
|
||||||
|
}
|
||||||
|
soft_pwm_lcd = (lcd_blink_on) ? (lcdSoftPwm / 2) : 0;
|
||||||
|
if (soft_pwm_lcd > 0) WRITE(LCD_PWM_PIN,1); else WRITE(LCD_PWM_PIN,0);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
#if EXTRUDERS > 1
|
#if EXTRUDERS > 1
|
||||||
if(soft_pwm_1 < pwm_count) WRITE(HEATER_1_PIN,0);
|
if(soft_pwm_1 < pwm_count) WRITE(HEATER_1_PIN,0);
|
||||||
#endif
|
#endif
|
||||||
|
@ -1551,6 +1634,9 @@ ISR(TIMER0_COMPB_vect)
|
||||||
#ifdef FAN_SOFT_PWM
|
#ifdef FAN_SOFT_PWM
|
||||||
if(soft_pwm_fan < pwm_count) WRITE(FAN_PIN,0);
|
if(soft_pwm_fan < pwm_count) WRITE(FAN_PIN,0);
|
||||||
#endif
|
#endif
|
||||||
|
#if defined(LCD_PWM_PIN) && (LCD_PWM_PIN > -1)
|
||||||
|
if (soft_pwm_lcd < (pwm_count & LCD_PWM_MAX)) WRITE(LCD_PWM_PIN,0);
|
||||||
|
#endif
|
||||||
|
|
||||||
pwm_count += (1 << SOFT_PWM_SCALE);
|
pwm_count += (1 << SOFT_PWM_SCALE);
|
||||||
pwm_count &= 0x7f;
|
pwm_count &= 0x7f;
|
||||||
|
@ -1881,13 +1967,52 @@ ISR(TIMER0_COMPB_vect)
|
||||||
raw_filwidth_value= raw_filwidth_value + ((unsigned long)ADC<<7); //add new ADC reading
|
raw_filwidth_value= raw_filwidth_value + ((unsigned long)ADC<<7); //add new ADC reading
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
temp_state = 0;
|
temp_state = 10;
|
||||||
|
break;
|
||||||
|
case 10: // Prepare TEMP_AMBIENT
|
||||||
|
#if defined(TEMP_AMBIENT_PIN) && (TEMP_AMBIENT_PIN > -1)
|
||||||
|
#if TEMP_AMBIENT_PIN > 7
|
||||||
|
ADCSRB = 1<<MUX5;
|
||||||
|
#else
|
||||||
|
ADCSRB = 0;
|
||||||
|
#endif
|
||||||
|
ADMUX = ((1 << REFS0) | (TEMP_AMBIENT_PIN & 0x07));
|
||||||
|
ADCSRA |= 1<<ADSC; // Start conversion
|
||||||
|
#endif
|
||||||
|
lcd_buttons_update();
|
||||||
|
temp_state = 11;
|
||||||
|
break;
|
||||||
|
case 11: // Measure TEMP_AMBIENT
|
||||||
|
#if defined(TEMP_AMBIENT_PIN) && (TEMP_AMBIENT_PIN > -1)
|
||||||
|
raw_temp_ambient_value += ADC;
|
||||||
|
#endif
|
||||||
|
temp_state = 12;
|
||||||
|
break;
|
||||||
|
case 12: // Prepare TEMP_PINDA
|
||||||
|
#if defined(TEMP_PINDA_PIN) && (TEMP_PINDA_PIN > -1)
|
||||||
|
#if TEMP_PINDA_PIN > 7
|
||||||
|
ADCSRB = 1<<MUX5;
|
||||||
|
#else
|
||||||
|
ADCSRB = 0;
|
||||||
|
#endif
|
||||||
|
ADMUX = ((1 << REFS0) | (TEMP_PINDA_PIN & 0x07));
|
||||||
|
ADCSRA |= 1<<ADSC; // Start conversion
|
||||||
|
#endif
|
||||||
|
lcd_buttons_update();
|
||||||
|
temp_state = 13;
|
||||||
|
break;
|
||||||
|
case 13: // Measure TEMP_PINDA
|
||||||
|
#if defined(TEMP_PINDA_PIN) && (TEMP_PINDA_PIN > -1)
|
||||||
|
raw_temp_pinda_value += ADC;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
temp_state = 0;
|
||||||
|
|
||||||
temp_count++;
|
temp_count++;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
|
||||||
case 10: //Startup, delay initial temp reading a tiny bit so the hardware can settle.
|
case 14: //Startup, delay initial temp reading a tiny bit so the hardware can settle.
|
||||||
temp_state = 0;
|
temp_state = 0;
|
||||||
break;
|
break;
|
||||||
// default:
|
// default:
|
||||||
|
@ -1900,17 +2025,23 @@ ISR(TIMER0_COMPB_vect)
|
||||||
{
|
{
|
||||||
if (!temp_meas_ready) //Only update the raw values if they have been read. Else we could be updating them during reading.
|
if (!temp_meas_ready) //Only update the raw values if they have been read. Else we could be updating them during reading.
|
||||||
{
|
{
|
||||||
current_temperature_raw[0] = raw_temp_0_value;
|
current_temperature_raw[0] = raw_temp_0_value;
|
||||||
#if EXTRUDERS > 1
|
#if EXTRUDERS > 1
|
||||||
current_temperature_raw[1] = raw_temp_1_value;
|
current_temperature_raw[1] = raw_temp_1_value;
|
||||||
#endif
|
#endif
|
||||||
#ifdef TEMP_SENSOR_1_AS_REDUNDANT
|
#ifdef TEMP_SENSOR_1_AS_REDUNDANT
|
||||||
redundant_temperature_raw = raw_temp_1_value;
|
redundant_temperature_raw = raw_temp_1_value;
|
||||||
#endif
|
#endif
|
||||||
#if EXTRUDERS > 2
|
#if EXTRUDERS > 2
|
||||||
current_temperature_raw[2] = raw_temp_2_value;
|
current_temperature_raw[2] = raw_temp_2_value;
|
||||||
#endif
|
#endif
|
||||||
current_temperature_bed_raw = raw_temp_bed_value;
|
#ifdef PINDA_THERMISTOR
|
||||||
|
current_temperature_raw_pinda = raw_temp_pinda_value;
|
||||||
|
#endif //PINDA_THERMISTOR
|
||||||
|
#ifdef AMBIENT_THERMISTOR
|
||||||
|
current_temperature_raw_ambient = raw_temp_ambient_value;
|
||||||
|
#endif //AMBIENT_THERMISTOR
|
||||||
|
current_temperature_bed_raw = raw_temp_bed_value;
|
||||||
}
|
}
|
||||||
|
|
||||||
//Add similar code for Filament Sensor - can be read any time since IIR filtering is used
|
//Add similar code for Filament Sensor - can be read any time since IIR filtering is used
|
||||||
|
@ -1925,6 +2056,8 @@ ISR(TIMER0_COMPB_vect)
|
||||||
raw_temp_1_value = 0;
|
raw_temp_1_value = 0;
|
||||||
raw_temp_2_value = 0;
|
raw_temp_2_value = 0;
|
||||||
raw_temp_bed_value = 0;
|
raw_temp_bed_value = 0;
|
||||||
|
raw_temp_pinda_value = 0;
|
||||||
|
raw_temp_ambient_value = 0;
|
||||||
|
|
||||||
#if HEATER_0_RAW_LO_TEMP > HEATER_0_RAW_HI_TEMP
|
#if HEATER_0_RAW_LO_TEMP > HEATER_0_RAW_HI_TEMP
|
||||||
if(current_temperature_raw[0] <= maxttemp_raw[0]) {
|
if(current_temperature_raw[0] <= maxttemp_raw[0]) {
|
||||||
|
|
|
@ -49,6 +49,17 @@ extern float current_temperature[EXTRUDERS];
|
||||||
#endif
|
#endif
|
||||||
extern int target_temperature_bed;
|
extern int target_temperature_bed;
|
||||||
extern float current_temperature_bed;
|
extern float current_temperature_bed;
|
||||||
|
|
||||||
|
#ifdef PINDA_THERMISTOR
|
||||||
|
//extern int current_temperature_raw_pinda;
|
||||||
|
extern float current_temperature_pinda;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef AMBIENT_THERMISTOR
|
||||||
|
//extern int current_temperature_raw_ambient;
|
||||||
|
extern float current_temperature_ambient;
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifdef TEMP_SENSOR_1_AS_REDUNDANT
|
#ifdef TEMP_SENSOR_1_AS_REDUNDANT
|
||||||
extern float redundant_temperature;
|
extern float redundant_temperature;
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -1211,6 +1211,47 @@ const short temptable_1047[][2] PROGMEM = {
|
||||||
};
|
};
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if (THERMISTORAMBIENT == 2000) //100k thermistor NTCG104LH104JT1
|
||||||
|
const short temptable_2000[][2] PROGMEM = {
|
||||||
|
// Source: https://product.tdk.com/info/en/catalog/datasheets/503021/tpd_ntc-thermistor_ntcg_en.pdf
|
||||||
|
// Calculated using 4.7kohm pullup, voltage divider math, and manufacturer provided temp/resistance
|
||||||
|
{305*OVERSAMPLENR, 125},
|
||||||
|
{338*OVERSAMPLENR, 120},
|
||||||
|
{374*OVERSAMPLENR, 115},
|
||||||
|
{412*OVERSAMPLENR, 110},
|
||||||
|
{452*OVERSAMPLENR, 105},
|
||||||
|
{494*OVERSAMPLENR, 100},
|
||||||
|
{536*OVERSAMPLENR, 95},
|
||||||
|
{580*OVERSAMPLENR, 90},
|
||||||
|
{623*OVERSAMPLENR, 85},
|
||||||
|
{665*OVERSAMPLENR, 80},
|
||||||
|
{706*OVERSAMPLENR, 75},
|
||||||
|
{744*OVERSAMPLENR, 70},
|
||||||
|
{780*OVERSAMPLENR, 65},
|
||||||
|
{813*OVERSAMPLENR, 60},
|
||||||
|
{843*OVERSAMPLENR, 55},
|
||||||
|
{869*OVERSAMPLENR, 50},
|
||||||
|
{892*OVERSAMPLENR, 45},
|
||||||
|
{912*OVERSAMPLENR, 40},
|
||||||
|
{929*OVERSAMPLENR, 35},
|
||||||
|
{943*OVERSAMPLENR, 30},
|
||||||
|
{955*OVERSAMPLENR, 25},
|
||||||
|
{965*OVERSAMPLENR, 20},
|
||||||
|
{973*OVERSAMPLENR, 15},
|
||||||
|
{979*OVERSAMPLENR, 10},
|
||||||
|
{984*OVERSAMPLENR, 5},
|
||||||
|
{988*OVERSAMPLENR, 0},
|
||||||
|
{991*OVERSAMPLENR, -5},
|
||||||
|
{993*OVERSAMPLENR, -10},
|
||||||
|
{995*OVERSAMPLENR, -15},
|
||||||
|
{996*OVERSAMPLENR, -20},
|
||||||
|
{997*OVERSAMPLENR, -25},
|
||||||
|
{998*OVERSAMPLENR, -30},
|
||||||
|
{999*OVERSAMPLENR, -35},
|
||||||
|
{999*OVERSAMPLENR, -40},
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
#define _TT_NAME(_N) temptable_ ## _N
|
#define _TT_NAME(_N) temptable_ ## _N
|
||||||
#define TT_NAME(_N) _TT_NAME(_N)
|
#define TT_NAME(_N) _TT_NAME(_N)
|
||||||
|
|
||||||
|
@ -1292,6 +1333,11 @@ const short temptable_1047[][2] PROGMEM = {
|
||||||
# endif // BED_USES_THERMISTOR
|
# endif // BED_USES_THERMISTOR
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef THERMISTORAMBIENT
|
||||||
|
# define AMBIENTTEMPTABLE TT_NAME(THERMISTORAMBIENT)
|
||||||
|
# define AMBIENTTEMPTABLE_LEN (sizeof(AMBIENTTEMPTABLE)/sizeof(*AMBIENTTEMPTABLE))
|
||||||
|
#endif
|
||||||
|
|
||||||
//Set the high and low raw values for the heater, this indicates which raw value is a high or low temperature
|
//Set the high and low raw values for the heater, this indicates which raw value is a high or low temperature
|
||||||
#ifndef HEATER_BED_RAW_HI_TEMP
|
#ifndef HEATER_BED_RAW_HI_TEMP
|
||||||
# ifdef BED_USES_THERMISTOR //In case of a thermistor the highest temperature results in the lowest ADC value
|
# ifdef BED_USES_THERMISTOR //In case of a thermistor the highest temperature results in the lowest ADC value
|
||||||
|
|
|
@ -1,16 +1,23 @@
|
||||||
#include "Marlin.h"
|
#include "Marlin.h"
|
||||||
|
|
||||||
#ifdef HAVE_TMC2130_DRIVERS
|
#ifdef TMC2130
|
||||||
|
|
||||||
#include "tmc2130.h"
|
#include "tmc2130.h"
|
||||||
#include <SPI.h>
|
#include <SPI.h>
|
||||||
|
|
||||||
|
#define TMC2130_GCONF_NORMAL 0x00000000 // spreadCycle
|
||||||
|
#define TMC2130_GCONF_SGSENS 0x00003180 // spreadCycle with stallguard (stall activates DIAG0 and DIAG1 [pushpull])
|
||||||
|
#define TMC2130_GCONF_SILENT 0x00000004 // stealthChop
|
||||||
|
|
||||||
//externals for debuging
|
//externals for debuging
|
||||||
extern float current_position[4];
|
extern float current_position[4];
|
||||||
extern void st_get_position_xy(long &x, long &y);
|
extern void st_get_position_xy(long &x, long &y);
|
||||||
|
extern long st_get_position(uint8_t axis);
|
||||||
|
|
||||||
//chipselect pins
|
//chipselect pins
|
||||||
uint8_t tmc2130_cs[4] = { X_TMC2130_CS, Y_TMC2130_CS, Z_TMC2130_CS, E0_TMC2130_CS };
|
uint8_t tmc2130_cs[4] = { X_TMC2130_CS, Y_TMC2130_CS, Z_TMC2130_CS, E0_TMC2130_CS };
|
||||||
|
//diag pins
|
||||||
|
uint8_t tmc2130_diag[4] = { X_TMC2130_DIAG, Y_TMC2130_DIAG, Z_TMC2130_DIAG, E0_TMC2130_DIAG };
|
||||||
//mode
|
//mode
|
||||||
uint8_t tmc2130_mode = TMC2130_MODE_NORMAL;
|
uint8_t tmc2130_mode = TMC2130_MODE_NORMAL;
|
||||||
//holding currents
|
//holding currents
|
||||||
|
@ -18,24 +25,23 @@ uint8_t tmc2130_current_h[4] = TMC2130_CURRENTS_H;
|
||||||
//running currents
|
//running currents
|
||||||
uint8_t tmc2130_current_r[4] = TMC2130_CURRENTS_R;
|
uint8_t tmc2130_current_r[4] = TMC2130_CURRENTS_R;
|
||||||
//axis stalled flags
|
//axis stalled flags
|
||||||
uint8_t tmc2130_axis_stalled[2] = {0, 0};
|
uint8_t tmc2130_axis_stalled[3] = {0, 0, 0};
|
||||||
//last homing stalled
|
|
||||||
uint8_t tmc2130_LastHomingStalled = 0;
|
|
||||||
|
|
||||||
//pwm_ampl
|
//pwm_ampl
|
||||||
uint8_t tmc2130_pwm_ampl[2] = {TMC2130_PWM_AMPL_XY, TMC2130_PWM_AMPL_XY};
|
uint8_t tmc2130_pwm_ampl[2] = {TMC2130_PWM_AMPL_X, TMC2130_PWM_AMPL_Y};
|
||||||
//pwm_grad
|
//pwm_grad
|
||||||
uint8_t tmc2130_pwm_grad[2] = {TMC2130_PWM_GRAD_XY, TMC2130_PWM_GRAD_XY};
|
uint8_t tmc2130_pwm_grad[2] = {TMC2130_PWM_GRAD_X, TMC2130_PWM_GRAD_Y};
|
||||||
//pwm_auto
|
//pwm_auto
|
||||||
uint8_t tmc2130_pwm_auto[2] = {TMC2130_PWM_AUTO_XY, TMC2130_PWM_AUTO_XY};
|
uint8_t tmc2130_pwm_auto[2] = {TMC2130_PWM_AUTO_X, TMC2130_PWM_AUTO_Y};
|
||||||
//pwm_freq
|
//pwm_freq
|
||||||
uint8_t tmc2130_pwm_freq[2] = {TMC2130_PWM_FREQ_XY, TMC2130_PWM_FREQ_XY};
|
uint8_t tmc2130_pwm_freq[2] = {TMC2130_PWM_FREQ_X, TMC2130_PWM_FREQ_Y};
|
||||||
|
|
||||||
|
|
||||||
|
uint8_t tmc2131_axis_sg_thr[3] = {TMC2130_SG_THRS_X, TMC2130_SG_THRS_Y, TMC2130_SG_THRS_Z};
|
||||||
|
|
||||||
|
uint32_t tmc2131_axis_sg_pos[3] = {0, 0, 0};
|
||||||
|
|
||||||
uint8_t sg_homing_axes_mask = 0x00;
|
uint8_t sg_homing_axes_mask = 0x00;
|
||||||
uint8_t sg_homing_delay = 0;
|
|
||||||
uint8_t sg_thrs_x = TMC2130_SG_THRS_X;
|
|
||||||
uint8_t sg_thrs_y = TMC2130_SG_THRS_Y;
|
|
||||||
|
|
||||||
bool skip_debug_msg = false;
|
bool skip_debug_msg = false;
|
||||||
|
|
||||||
|
@ -74,7 +80,8 @@ bool skip_debug_msg = false;
|
||||||
|
|
||||||
|
|
||||||
uint16_t tmc2130_rd_TSTEP(uint8_t cs);
|
uint16_t tmc2130_rd_TSTEP(uint8_t cs);
|
||||||
uint16_t tmc2130_rd_DRV_STATUS(uint8_t chipselect);
|
uint16_t tmc2130_rd_MSCNT(uint8_t cs);
|
||||||
|
uint16_t tmc2130_rd_DRV_STATUS(uint8_t cs);
|
||||||
|
|
||||||
void tmc2130_wr_CHOPCONF(uint8_t cs, uint8_t toff = 3, uint8_t hstrt = 4, uint8_t hend = 1, uint8_t fd3 = 0, uint8_t disfdcc = 0, uint8_t rndtf = 0, uint8_t chm = 0, uint8_t tbl = 2, uint8_t vsense = 0, uint8_t vhighfs = 0, uint8_t vhighchm = 0, uint8_t sync = 0, uint8_t mres = 0b0100, uint8_t intpol = 1, uint8_t dedge = 0, uint8_t diss2g = 0);
|
void tmc2130_wr_CHOPCONF(uint8_t cs, uint8_t toff = 3, uint8_t hstrt = 4, uint8_t hend = 1, uint8_t fd3 = 0, uint8_t disfdcc = 0, uint8_t rndtf = 0, uint8_t chm = 0, uint8_t tbl = 2, uint8_t vsense = 0, uint8_t vhighfs = 0, uint8_t vhighchm = 0, uint8_t sync = 0, uint8_t mres = 0b0100, uint8_t intpol = 1, uint8_t dedge = 0, uint8_t diss2g = 0);
|
||||||
void tmc2130_wr_PWMCONF(uint8_t cs, uint8_t pwm_ampl, uint8_t pwm_grad, uint8_t pwm_freq, uint8_t pwm_auto, uint8_t pwm_symm, uint8_t freewheel);
|
void tmc2130_wr_PWMCONF(uint8_t cs, uint8_t pwm_ampl, uint8_t pwm_grad, uint8_t pwm_freq, uint8_t pwm_auto, uint8_t pwm_symm, uint8_t freewheel);
|
||||||
|
@ -102,6 +109,10 @@ void tmc2130_init()
|
||||||
SET_OUTPUT(Y_TMC2130_CS);
|
SET_OUTPUT(Y_TMC2130_CS);
|
||||||
SET_OUTPUT(Z_TMC2130_CS);
|
SET_OUTPUT(Z_TMC2130_CS);
|
||||||
SET_OUTPUT(E0_TMC2130_CS);
|
SET_OUTPUT(E0_TMC2130_CS);
|
||||||
|
SET_INPUT(X_TMC2130_DIAG);
|
||||||
|
SET_INPUT(Y_TMC2130_DIAG);
|
||||||
|
SET_INPUT(Z_TMC2130_DIAG);
|
||||||
|
SET_INPUT(E0_TMC2130_DIAG);
|
||||||
SPI.begin();
|
SPI.begin();
|
||||||
for (int i = 0; i < 2; i++) // X Y axes
|
for (int i = 0; i < 2; i++) // X Y axes
|
||||||
{
|
{
|
||||||
|
@ -109,7 +120,8 @@ void tmc2130_init()
|
||||||
tmc2130_wr_CHOPCONF(tmc2130_cs[i], 3, 5, 1, 0, 0, 0, 0, 2, 1, 0, 0, 0, mres, TMC2130_INTPOL_XY, 0, 0);
|
tmc2130_wr_CHOPCONF(tmc2130_cs[i], 3, 5, 1, 0, 0, 0, 0, 2, 1, 0, 0, 0, mres, TMC2130_INTPOL_XY, 0, 0);
|
||||||
tmc2130_wr(tmc2130_cs[i], TMC2130_REG_IHOLD_IRUN, 0x000f0000 | ((tmc2130_current_r[i] & 0x1f) << 8) | (tmc2130_current_h[i] & 0x1f));
|
tmc2130_wr(tmc2130_cs[i], TMC2130_REG_IHOLD_IRUN, 0x000f0000 | ((tmc2130_current_r[i] & 0x1f) << 8) | (tmc2130_current_h[i] & 0x1f));
|
||||||
tmc2130_wr(tmc2130_cs[i], TMC2130_REG_TPOWERDOWN, 0x00000000);
|
tmc2130_wr(tmc2130_cs[i], TMC2130_REG_TPOWERDOWN, 0x00000000);
|
||||||
tmc2130_wr(tmc2130_cs[i], TMC2130_REG_GCONF, (tmc2130_mode == TMC2130_MODE_SILENT)?0x00000004:0x00000000);
|
tmc2130_wr(tmc2130_cs[i], TMC2130_REG_GCONF, (tmc2130_mode == TMC2130_MODE_SILENT)?TMC2130_GCONF_SILENT:TMC2130_GCONF_SGSENS);
|
||||||
|
tmc2130_wr(tmc2130_cs[i], TMC2130_REG_TCOOLTHRS, (tmc2130_mode == TMC2130_MODE_SILENT)?0:TMC2130_TCOOLTHRS);
|
||||||
tmc2130_wr_PWMCONF(tmc2130_cs[i], tmc2130_pwm_ampl[i], tmc2130_pwm_grad[i], tmc2130_pwm_freq[i], tmc2130_pwm_auto[i], 0, 0);
|
tmc2130_wr_PWMCONF(tmc2130_cs[i], tmc2130_pwm_ampl[i], tmc2130_pwm_grad[i], tmc2130_pwm_freq[i], tmc2130_pwm_auto[i], 0, 0);
|
||||||
tmc2130_wr_TPWMTHRS(tmc2130_cs[i], TMC2130_TPWMTHRS);
|
tmc2130_wr_TPWMTHRS(tmc2130_cs[i], TMC2130_TPWMTHRS);
|
||||||
//tmc2130_wr_THIGH(tmc2130_cs[i], TMC2130_THIGH);
|
//tmc2130_wr_THIGH(tmc2130_cs[i], TMC2130_THIGH);
|
||||||
|
@ -128,7 +140,7 @@ void tmc2130_init()
|
||||||
tmc2130_wr(tmc2130_cs[i], TMC2130_REG_IHOLD_IRUN, 0x000f0000 | (((tmc2130_current_r[i] >> 1) & 0x1f) << 8) | ((tmc2130_current_h[i] >> 1) & 0x1f));
|
tmc2130_wr(tmc2130_cs[i], TMC2130_REG_IHOLD_IRUN, 0x000f0000 | (((tmc2130_current_r[i] >> 1) & 0x1f) << 8) | ((tmc2130_current_h[i] >> 1) & 0x1f));
|
||||||
}
|
}
|
||||||
tmc2130_wr(tmc2130_cs[i], TMC2130_REG_TPOWERDOWN, 0x00000000);
|
tmc2130_wr(tmc2130_cs[i], TMC2130_REG_TPOWERDOWN, 0x00000000);
|
||||||
tmc2130_wr(tmc2130_cs[i], TMC2130_REG_GCONF, 0x00000000);
|
tmc2130_wr(tmc2130_cs[i], TMC2130_REG_GCONF, TMC2130_GCONF_SGSENS);
|
||||||
}
|
}
|
||||||
for (int i = 3; i < 4; i++) // E axis
|
for (int i = 3; i < 4; i++) // E axis
|
||||||
{
|
{
|
||||||
|
@ -140,13 +152,43 @@ void tmc2130_init()
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void tmc2130_update_sg_axis(uint8_t axis)
|
||||||
|
{
|
||||||
|
if (!tmc2130_axis_stalled[axis])
|
||||||
|
{
|
||||||
|
uint8_t cs = tmc2130_cs[axis];
|
||||||
|
uint16_t tstep = tmc2130_rd_TSTEP(cs);
|
||||||
|
if (tstep < TMC2130_TCOOLTHRS)
|
||||||
|
{
|
||||||
|
long pos = st_get_position(axis);
|
||||||
|
if (abs(pos - tmc2131_axis_sg_pos[axis]) > TMC2130_SG_DELTA)
|
||||||
|
{
|
||||||
|
uint16_t sg = tmc2130_rd_DRV_STATUS(cs) & 0x3ff;
|
||||||
|
if (sg == 0)
|
||||||
|
tmc2130_axis_stalled[axis] = true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
bool tmc2130_update_sg()
|
bool tmc2130_update_sg()
|
||||||
{
|
{
|
||||||
#if (defined(TMC2130_SG_HOMING) && defined(TMC2130_SG_HOMING_SW))
|
#ifdef TMC2130_SG_HOMING_SW_XY
|
||||||
|
if (sg_homing_axes_mask & X_AXIS_MASK) tmc2130_update_sg_axis(X_AXIS);
|
||||||
|
if (sg_homing_axes_mask & Y_AXIS_MASK) tmc2130_update_sg_axis(Y_AXIS);
|
||||||
|
#endif //TMC2130_SG_HOMING_SW_XY
|
||||||
|
#ifdef TMC2130_SG_HOMING_SW_Z
|
||||||
|
if (sg_homing_axes_mask & Z_AXIS_MASK) tmc2130_update_sg_axis(Z_AXIS);
|
||||||
|
#endif //TMC2130_SG_HOMING_SW_Z
|
||||||
|
#if (defined(TMC2130_SG_HOMING) && defined(TMC2130_SG_HOMING_SW_XY))
|
||||||
if (sg_homing_axes_mask == 0) return false;
|
if (sg_homing_axes_mask == 0) return false;
|
||||||
#ifdef TMC2130_DEBUG
|
#ifdef TMC2130_DEBUG
|
||||||
MYSERIAL.print("tmc2130_update_sg mask=0x");
|
MYSERIAL.print("tmc2130_update_sg mask=0x");
|
||||||
MYSERIAL.println((int)sg_homing_axes_mask, 16);
|
MYSERIAL.print((int)sg_homing_axes_mask, 16);
|
||||||
|
MYSERIAL.print(" stalledX=");
|
||||||
|
MYSERIAL.print((int)tmc2130_axis_stalled[0]);
|
||||||
|
MYSERIAL.print(" stalledY=");
|
||||||
|
MYSERIAL.println((int)tmc2130_axis_stalled[1]);
|
||||||
#endif //TMC2130_DEBUG
|
#endif //TMC2130_DEBUG
|
||||||
for (uint8_t axis = X_AXIS; axis <= Y_AXIS; axis++) //only X and Y axes
|
for (uint8_t axis = X_AXIS; axis <= Y_AXIS; axis++) //only X and Y axes
|
||||||
{
|
{
|
||||||
|
@ -159,64 +201,26 @@ bool tmc2130_update_sg()
|
||||||
uint16_t tstep = tmc2130_rd_TSTEP(cs);
|
uint16_t tstep = tmc2130_rd_TSTEP(cs);
|
||||||
if (tstep < TMC2130_TCOOLTHRS)
|
if (tstep < TMC2130_TCOOLTHRS)
|
||||||
{
|
{
|
||||||
if(sg_homing_delay < TMC2130_SG_DELAY) // wait for a few tens microsteps until stallGuard is used //todo: read out microsteps directly, instead of delay counter
|
long pos = st_get_position(axis);
|
||||||
sg_homing_delay++;
|
if (abs(pos - tmc2131_axis_sg_pos[axis]) > TMC2130_SG_DELTA)
|
||||||
else
|
|
||||||
{
|
{
|
||||||
uint16_t sg = tmc2130_rd_DRV_STATUS(cs) & 0x3ff;
|
uint16_t sg = tmc2130_rd_DRV_STATUS(cs) & 0x3ff;
|
||||||
if (sg==0)
|
if (sg == 0)
|
||||||
{
|
{
|
||||||
tmc2130_axis_stalled[axis] = true;
|
tmc2130_axis_stalled[axis] = true;
|
||||||
tmc2130_LastHomingStalled = true;
|
#ifdef TMC2130_DEBUG
|
||||||
|
MYSERIAL.print("tmc2130_update_sg AXIS STALLED ");
|
||||||
|
MYSERIAL.println((int)axis);
|
||||||
|
#endif //TMC2130_DEBUG
|
||||||
}
|
}
|
||||||
// else
|
|
||||||
// tmc2130_axis_stalled[axis] = false;
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
// else
|
|
||||||
// tmc2130_axis_stalled[axis] = false;
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
return true;
|
return true;
|
||||||
// else
|
|
||||||
// {
|
|
||||||
// tmc2130_axis_stalled[X_AXIS] = false;
|
|
||||||
// tmc2130_axis_stalled[Y_AXIS] = false;
|
|
||||||
// }
|
|
||||||
#endif
|
#endif
|
||||||
}
|
return false;
|
||||||
|
|
||||||
void tmc2130_check_overtemp()
|
|
||||||
{
|
|
||||||
const static char TMC_OVERTEMP_MSG[] PROGMEM = "TMC DRIVER OVERTEMP ";
|
|
||||||
uint8_t cs[4] = { X_TMC2130_CS, Y_TMC2130_CS, Z_TMC2130_CS, E0_TMC2130_CS };
|
|
||||||
static uint32_t checktime = 0;
|
|
||||||
//drivers_disabled[0] = 1; //TEST
|
|
||||||
if( millis() - checktime > 1000 )
|
|
||||||
{
|
|
||||||
//SERIAL_ECHOLNPGM("drv_status:");
|
|
||||||
for(int i=0;i<4;i++)
|
|
||||||
{
|
|
||||||
uint32_t drv_status = 0;
|
|
||||||
|
|
||||||
skip_debug_msg = true;
|
|
||||||
|
|
||||||
tmc2130_rd(cs[i], TMC2130_REG_DRV_STATUS, &drv_status);
|
|
||||||
//MYSERIAL.print(drv_status);
|
|
||||||
//SERIAL_ECHOPGM(" ");
|
|
||||||
if (drv_status & ((uint32_t)1<<26))
|
|
||||||
{ // BIT 26 - over temp prewarning ~120C (+-20C)
|
|
||||||
SERIAL_ERRORRPGM(TMC_OVERTEMP_MSG);
|
|
||||||
SERIAL_ECHOLN(i);
|
|
||||||
for(int i=0; i < 4; i++)
|
|
||||||
tmc2130_wr(tmc2130_cs[i], TMC2130_REG_CHOPCONF, 0x00010000);
|
|
||||||
kill(TMC_OVERTEMP_MSG);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
//SERIAL_ECHOLNPGM("");
|
|
||||||
checktime = millis();
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void tmc2130_home_enter(uint8_t axes_mask)
|
void tmc2130_home_enter(uint8_t axes_mask)
|
||||||
|
@ -226,22 +230,23 @@ void tmc2130_home_enter(uint8_t axes_mask)
|
||||||
MYSERIAL.println((int)axes_mask, 16);
|
MYSERIAL.println((int)axes_mask, 16);
|
||||||
#endif //TMC2130_DEBUG
|
#endif //TMC2130_DEBUG
|
||||||
#ifdef TMC2130_SG_HOMING
|
#ifdef TMC2130_SG_HOMING
|
||||||
for (uint8_t axis = X_AXIS; axis <= Y_AXIS; axis++) //only X and Y axes
|
for (uint8_t axis = X_AXIS; axis <= Z_AXIS; axis++) //X Y and Z axes
|
||||||
{
|
{
|
||||||
uint8_t mask = (X_AXIS_MASK << axis);
|
uint8_t mask = (X_AXIS_MASK << axis);
|
||||||
|
uint8_t cs = tmc2130_cs[axis];
|
||||||
if (axes_mask & mask)
|
if (axes_mask & mask)
|
||||||
{
|
{
|
||||||
uint8_t cs = tmc2130_cs[axis];
|
|
||||||
sg_homing_axes_mask |= mask;
|
sg_homing_axes_mask |= mask;
|
||||||
sg_homing_delay = 0;
|
tmc2131_axis_sg_pos[axis] = st_get_position(axis);
|
||||||
tmc2130_axis_stalled[axis] = false;
|
tmc2130_axis_stalled[axis] = false;
|
||||||
//Configuration to spreadCycle
|
//Configuration to spreadCycle
|
||||||
tmc2130_wr(cs, TMC2130_REG_GCONF, 0x00000000);
|
tmc2130_wr(cs, TMC2130_REG_GCONF, TMC2130_GCONF_NORMAL);
|
||||||
tmc2130_wr(cs, TMC2130_REG_COOLCONF, ((axis == X_AXIS)?sg_thrs_x:sg_thrs_y) << 16);
|
tmc2130_wr(cs, TMC2130_REG_COOLCONF, ((unsigned long)tmc2131_axis_sg_thr[axis]) << 16);
|
||||||
tmc2130_wr(cs, TMC2130_REG_TCOOLTHRS, TMC2130_TCOOLTHRS);
|
tmc2130_wr(cs, TMC2130_REG_TCOOLTHRS, TMC2130_TCOOLTHRS);
|
||||||
#ifndef TMC2130_SG_HOMING_SW
|
#ifndef TMC2130_SG_HOMING_SW_XY
|
||||||
tmc2130_wr(cs, TMC2130_REG_GCONF, 0x00000080); //stallguard output to DIAG0
|
if (mask & (X_AXIS_MASK | Y_AXIS_MASK))
|
||||||
#endif //TMC2130_SG_HOMING_SW
|
tmc2130_wr(cs, TMC2130_REG_GCONF, TMC2130_GCONF_SGSENS); //stallguard output DIAG1, DIAG1 = pushpull
|
||||||
|
#endif //TMC2130_SG_HOMING_SW_XY
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif //TMC2130_SG_HOMING
|
#endif //TMC2130_SG_HOMING
|
||||||
|
@ -256,27 +261,55 @@ void tmc2130_home_exit()
|
||||||
#ifdef TMC2130_SG_HOMING
|
#ifdef TMC2130_SG_HOMING
|
||||||
if (sg_homing_axes_mask)
|
if (sg_homing_axes_mask)
|
||||||
{
|
{
|
||||||
for (uint8_t axis = X_AXIS; axis <= Y_AXIS; axis++) //only X and Y axes
|
for (uint8_t axis = X_AXIS; axis <= Z_AXIS; axis++) //X Y and Z axes
|
||||||
{
|
{
|
||||||
uint8_t mask = (X_AXIS_MASK << axis);
|
uint8_t mask = (X_AXIS_MASK << axis);
|
||||||
if (sg_homing_axes_mask & mask)
|
if (sg_homing_axes_mask & mask & (X_AXIS_MASK | Y_AXIS_MASK))
|
||||||
{
|
{
|
||||||
if (tmc2130_mode == TMC2130_MODE_SILENT)
|
if (tmc2130_mode == TMC2130_MODE_SILENT)
|
||||||
tmc2130_wr(tmc2130_cs[axis], TMC2130_REG_GCONF, 0x00000004); // Configuration back to stealthChop
|
tmc2130_wr(tmc2130_cs[axis], TMC2130_REG_GCONF, TMC2130_GCONF_SILENT); // Configuration back to stealthChop
|
||||||
else
|
else
|
||||||
tmc2130_wr(tmc2130_cs[axis], TMC2130_REG_GCONF, 0x00000000);
|
#ifdef TMC2130_SG_HOMING_SW_XY
|
||||||
|
tmc2130_wr(tmc2130_cs[axis], TMC2130_REG_GCONF, TMC2130_GCONF_NORMAL);
|
||||||
|
#else //TMC2130_SG_HOMING_SW_XY
|
||||||
|
tmc2130_wr(tmc2130_cs[axis], TMC2130_REG_GCONF, TMC2130_GCONF_SGSENS);
|
||||||
|
#endif //TMC2130_SG_HOMING_SW_XY
|
||||||
}
|
}
|
||||||
|
tmc2130_axis_stalled[axis] = false;
|
||||||
}
|
}
|
||||||
sg_homing_axes_mask = 0x00;
|
sg_homing_axes_mask = 0x00;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t tmc2130_didLastHomingStall()
|
void tmc2130_home_restart(uint8_t axis)
|
||||||
{
|
{
|
||||||
uint8_t ret = tmc2130_LastHomingStalled;
|
tmc2131_axis_sg_pos[axis] = st_get_position(axis);
|
||||||
tmc2130_LastHomingStalled = false;
|
tmc2130_axis_stalled[axis] = false;
|
||||||
return ret;
|
}
|
||||||
|
|
||||||
|
void tmc2130_check_overtemp()
|
||||||
|
{
|
||||||
|
const static char TMC_OVERTEMP_MSG[] PROGMEM = "TMC DRIVER OVERTEMP ";
|
||||||
|
static uint32_t checktime = 0;
|
||||||
|
if (millis() - checktime > 1000 )
|
||||||
|
{
|
||||||
|
for (int i = 0; i < 4; i++)
|
||||||
|
{
|
||||||
|
uint32_t drv_status = 0;
|
||||||
|
skip_debug_msg = true;
|
||||||
|
tmc2130_rd(tmc2130_cs[i], TMC2130_REG_DRV_STATUS, &drv_status);
|
||||||
|
if (drv_status & ((uint32_t)1 << 26))
|
||||||
|
{ // BIT 26 - over temp prewarning ~120C (+-20C)
|
||||||
|
SERIAL_ERRORRPGM(TMC_OVERTEMP_MSG);
|
||||||
|
SERIAL_ECHOLN(i);
|
||||||
|
for (int j = 0; j < 4; j++)
|
||||||
|
tmc2130_wr(tmc2130_cs[j], TMC2130_REG_CHOPCONF, 0x00010000);
|
||||||
|
kill(TMC_OVERTEMP_MSG);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
checktime = millis();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void tmc2130_set_current_h(uint8_t axis, uint8_t current)
|
void tmc2130_set_current_h(uint8_t axis, uint8_t current)
|
||||||
|
@ -285,7 +318,6 @@ void tmc2130_set_current_h(uint8_t axis, uint8_t current)
|
||||||
MYSERIAL.print((int)axis);
|
MYSERIAL.print((int)axis);
|
||||||
MYSERIAL.print(" ");
|
MYSERIAL.print(" ");
|
||||||
MYSERIAL.println((int)current);
|
MYSERIAL.println((int)current);
|
||||||
// if (current > 15) current = 15; //current>15 is unsafe
|
|
||||||
tmc2130_current_h[axis] = current;
|
tmc2130_current_h[axis] = current;
|
||||||
tmc2130_wr(tmc2130_cs[axis], TMC2130_REG_IHOLD_IRUN, 0x000f0000 | ((tmc2130_current_r[axis] & 0x1f) << 8) | (tmc2130_current_h[axis] & 0x1f));
|
tmc2130_wr(tmc2130_cs[axis], TMC2130_REG_IHOLD_IRUN, 0x000f0000 | ((tmc2130_current_r[axis] & 0x1f) << 8) | (tmc2130_current_h[axis] & 0x1f));
|
||||||
}
|
}
|
||||||
|
@ -296,7 +328,6 @@ void tmc2130_set_current_r(uint8_t axis, uint8_t current)
|
||||||
MYSERIAL.print((int)axis);
|
MYSERIAL.print((int)axis);
|
||||||
MYSERIAL.print(" ");
|
MYSERIAL.print(" ");
|
||||||
MYSERIAL.println((int)current);
|
MYSERIAL.println((int)current);
|
||||||
// if (current > 15) current = 15; //current>15 is unsafe
|
|
||||||
tmc2130_current_r[axis] = current;
|
tmc2130_current_r[axis] = current;
|
||||||
tmc2130_wr(tmc2130_cs[axis], TMC2130_REG_IHOLD_IRUN, 0x000f0000 | ((tmc2130_current_r[axis] & 0x1f) << 8) | (tmc2130_current_h[axis] & 0x1f));
|
tmc2130_wr(tmc2130_cs[axis], TMC2130_REG_IHOLD_IRUN, 0x000f0000 | ((tmc2130_current_r[axis] & 0x1f) << 8) | (tmc2130_current_h[axis] & 0x1f));
|
||||||
}
|
}
|
||||||
|
@ -353,6 +384,13 @@ uint16_t tmc2130_rd_TSTEP(uint8_t cs)
|
||||||
return val32 & 0xffff;
|
return val32 & 0xffff;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
uint16_t tmc2130_rd_MSCNT(uint8_t cs)
|
||||||
|
{
|
||||||
|
uint32_t val32 = 0;
|
||||||
|
tmc2130_rd(cs, TMC2130_REG_MSCNT, &val32);
|
||||||
|
return val32 & 0x3ff;
|
||||||
|
}
|
||||||
|
|
||||||
uint16_t tmc2130_rd_DRV_STATUS(uint8_t cs)
|
uint16_t tmc2130_rd_DRV_STATUS(uint8_t cs)
|
||||||
{
|
{
|
||||||
uint32_t val32 = 0;
|
uint32_t val32 = 0;
|
||||||
|
@ -406,7 +444,7 @@ void tmc2130_wr_THIGH(uint8_t cs, uint32_t val32)
|
||||||
tmc2130_wr(cs, TMC2130_REG_THIGH, val32);
|
tmc2130_wr(cs, TMC2130_REG_THIGH, val32);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if defined(TMC2130_DEBUG_RD) || defined(TMC2130_DEBUG_WR)
|
||||||
uint8_t tmc2130_axis_by_cs(uint8_t cs)
|
uint8_t tmc2130_axis_by_cs(uint8_t cs)
|
||||||
{
|
{
|
||||||
switch (cs)
|
switch (cs)
|
||||||
|
@ -418,6 +456,7 @@ uint8_t tmc2130_axis_by_cs(uint8_t cs)
|
||||||
}
|
}
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
|
#endif //TMC2130_DEBUG
|
||||||
|
|
||||||
uint8_t tmc2130_mres(uint16_t microstep_resolution)
|
uint8_t tmc2130_mres(uint16_t microstep_resolution)
|
||||||
{
|
{
|
||||||
|
@ -498,4 +537,4 @@ uint8_t tmc2130_txrx(uint8_t cs, uint8_t addr, uint32_t wval, uint32_t* rval)
|
||||||
return stat;
|
return stat;
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif //HAVE_TMC2130_DRIVERS
|
#endif //TMC2130
|
||||||
|
|
|
@ -1,18 +1,17 @@
|
||||||
#ifndef TMC2130_H
|
#ifndef TMC2130_H
|
||||||
#define TMC2130_H
|
#define TMC2130_H
|
||||||
|
|
||||||
|
extern uint8_t tmc2130_cs[4];
|
||||||
|
|
||||||
//mode
|
//mode
|
||||||
extern uint8_t tmc2130_mode;
|
extern uint8_t tmc2130_mode;
|
||||||
//holding and running currents
|
//holding and running currents
|
||||||
extern uint8_t tmc2130_current_h[4];
|
extern uint8_t tmc2130_current_h[4];
|
||||||
extern uint8_t tmc2130_current_r[4];
|
extern uint8_t tmc2130_current_r[4];
|
||||||
//flags for axis stall detection
|
//flags for axis stall detection
|
||||||
extern uint8_t tmc2130_axis_stalled[2];
|
extern uint8_t tmc2130_axis_stalled[3];
|
||||||
|
|
||||||
extern uint8_t sg_thrs_x;
|
extern uint8_t tmc2131_axis_sg_thr[3];
|
||||||
extern uint8_t sg_thrs_y;
|
|
||||||
|
|
||||||
extern uint8_t sg_homing_delay;
|
|
||||||
|
|
||||||
#define TMC2130_MODE_NORMAL 0
|
#define TMC2130_MODE_NORMAL 0
|
||||||
#define TMC2130_MODE_SILENT 1
|
#define TMC2130_MODE_SILENT 1
|
||||||
|
@ -24,11 +23,11 @@ extern bool tmc2130_update_sg();
|
||||||
//temperature watching (called from )
|
//temperature watching (called from )
|
||||||
extern void tmc2130_check_overtemp();
|
extern void tmc2130_check_overtemp();
|
||||||
//enter homing (called from homeaxis before homing starts)
|
//enter homing (called from homeaxis before homing starts)
|
||||||
extern void tmc2130_home_enter(uint8_t axis);
|
extern void tmc2130_home_enter(uint8_t axes_mask);
|
||||||
//exit homing (called from homeaxis after homing ends)
|
//exit homing (called from homeaxis after homing ends)
|
||||||
extern void tmc2130_home_exit();
|
extern void tmc2130_home_exit();
|
||||||
//
|
//restart homing (called from homeaxis befor move)
|
||||||
extern uint8_t tmc2130_didLastHomingStall();
|
extern void tmc2130_home_restart(uint8_t axis);
|
||||||
|
|
||||||
//set holding current for any axis (M911)
|
//set holding current for any axis (M911)
|
||||||
extern void tmc2130_set_current_h(uint8_t axis, uint8_t current);
|
extern void tmc2130_set_current_h(uint8_t axis, uint8_t current);
|
||||||
|
@ -43,4 +42,7 @@ extern void tmc2130_set_pwm_ampl(uint8_t axis, uint8_t pwm_ampl);
|
||||||
extern void tmc2130_set_pwm_grad(uint8_t axis, uint8_t pwm_ampl);
|
extern void tmc2130_set_pwm_grad(uint8_t axis, uint8_t pwm_ampl);
|
||||||
|
|
||||||
|
|
||||||
|
extern uint16_t tmc2130_rd_MSCNT(uint8_t cs);
|
||||||
|
|
||||||
|
|
||||||
#endif //TMC2130_H
|
#endif //TMC2130_H
|
|
@ -14,11 +14,14 @@
|
||||||
//#include "Configuration.h"
|
//#include "Configuration.h"
|
||||||
|
|
||||||
#include "SdFatUtil.h"
|
#include "SdFatUtil.h"
|
||||||
#include "pat9125.h"
|
|
||||||
|
|
||||||
#ifdef HAVE_TMC2130_DRIVERS
|
#ifdef PAT9125
|
||||||
|
#include "pat9125.h"
|
||||||
|
#endif //PAT9125
|
||||||
|
|
||||||
|
#ifdef TMC2130
|
||||||
#include "tmc2130.h"
|
#include "tmc2130.h"
|
||||||
#endif //HAVE_TMC2130_DRIVERS
|
#endif //TMC2130
|
||||||
|
|
||||||
#define _STRINGIFY(s) #s
|
#define _STRINGIFY(s) #s
|
||||||
|
|
||||||
|
@ -949,6 +952,24 @@ static void lcd_menu_extruder_info()
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static void lcd_menu_temperatures()
|
||||||
|
{
|
||||||
|
lcd.setCursor(1, 1);
|
||||||
|
lcd.print("Ambient: ");
|
||||||
|
lcd.setCursor(12, 1);
|
||||||
|
lcd.print(ftostr31ns(current_temperature_ambient));
|
||||||
|
lcd.print(LCD_STR_DEGREE);
|
||||||
|
lcd.setCursor(1, 2);
|
||||||
|
lcd.print("PINDA: ");
|
||||||
|
lcd.setCursor(12, 2);
|
||||||
|
lcd.print(ftostr31ns(current_temperature_pinda));
|
||||||
|
lcd.print(LCD_STR_DEGREE);
|
||||||
|
if (lcd_clicked())
|
||||||
|
{
|
||||||
|
lcd_quick_feedback();
|
||||||
|
lcd_return_to_status();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
static void lcd_preheat_menu()
|
static void lcd_preheat_menu()
|
||||||
{
|
{
|
||||||
|
@ -1023,6 +1044,7 @@ static void lcd_support_menu()
|
||||||
MENU_ITEM(function, PSTR("XYZ cal. details"), lcd_service_mode_show_result);
|
MENU_ITEM(function, PSTR("XYZ cal. details"), lcd_service_mode_show_result);
|
||||||
}
|
}
|
||||||
MENU_ITEM(submenu, MSG_INFO_EXTRUDER, lcd_menu_extruder_info);
|
MENU_ITEM(submenu, MSG_INFO_EXTRUDER, lcd_menu_extruder_info);
|
||||||
|
MENU_ITEM(submenu, PSTR("Temperatures"), lcd_menu_temperatures);
|
||||||
#endif //MK1BP
|
#endif //MK1BP
|
||||||
END_MENU();
|
END_MENU();
|
||||||
}
|
}
|
||||||
|
@ -2487,10 +2509,10 @@ static void lcd_fsensor_state_set()
|
||||||
static void lcd_silent_mode_set() {
|
static void lcd_silent_mode_set() {
|
||||||
SilentModeMenu = !SilentModeMenu;
|
SilentModeMenu = !SilentModeMenu;
|
||||||
eeprom_update_byte((unsigned char *)EEPROM_SILENT, SilentModeMenu);
|
eeprom_update_byte((unsigned char *)EEPROM_SILENT, SilentModeMenu);
|
||||||
#ifdef HAVE_TMC2130_DRIVERS
|
#ifdef TMC2130
|
||||||
tmc2130_mode = SilentModeMenu?TMC2130_MODE_SILENT:TMC2130_MODE_NORMAL;
|
tmc2130_mode = SilentModeMenu?TMC2130_MODE_SILENT:TMC2130_MODE_NORMAL;
|
||||||
tmc2130_init();
|
tmc2130_init();
|
||||||
#endif //HAVE_TMC2130_DRIVERS
|
#endif //TMC2130
|
||||||
digipot_init();
|
digipot_init();
|
||||||
lcd_goto_menu(lcd_settings_menu, 7);
|
lcd_goto_menu(lcd_settings_menu, 7);
|
||||||
}
|
}
|
||||||
|
@ -3944,10 +3966,10 @@ static void lcd_autostart_sd()
|
||||||
static void lcd_silent_mode_set_tune() {
|
static void lcd_silent_mode_set_tune() {
|
||||||
SilentModeMenu = !SilentModeMenu;
|
SilentModeMenu = !SilentModeMenu;
|
||||||
eeprom_update_byte((unsigned char*)EEPROM_SILENT, SilentModeMenu);
|
eeprom_update_byte((unsigned char*)EEPROM_SILENT, SilentModeMenu);
|
||||||
#ifdef HAVE_TMC2130_DRIVERS
|
#ifdef TMC2130
|
||||||
tmc2130_mode = SilentModeMenu?TMC2130_MODE_SILENT:TMC2130_MODE_NORMAL;
|
tmc2130_mode = SilentModeMenu?TMC2130_MODE_SILENT:TMC2130_MODE_NORMAL;
|
||||||
tmc2130_init();
|
tmc2130_init();
|
||||||
#endif //HAVE_TMC2130_DRIVERS
|
#endif //TMC2130
|
||||||
digipot_init();
|
digipot_init();
|
||||||
lcd_goto_menu(lcd_tune_menu, 9);
|
lcd_goto_menu(lcd_tune_menu, 9);
|
||||||
}
|
}
|
||||||
|
@ -4373,9 +4395,8 @@ static void lcd_selftest()
|
||||||
|
|
||||||
if (_result)
|
if (_result)
|
||||||
{
|
{
|
||||||
#ifdef HAVE_TMC2130_DRIVERS
|
#ifdef TMC2130
|
||||||
tmc2130_home_exit();
|
tmc2130_home_exit();
|
||||||
sg_homing_delay = 0;
|
|
||||||
enable_endstops(false);
|
enable_endstops(false);
|
||||||
#endif
|
#endif
|
||||||
current_position[X_AXIS] = current_position[X_AXIS] + 14;
|
current_position[X_AXIS] = current_position[X_AXIS] + 14;
|
||||||
|
@ -4437,10 +4458,8 @@ static bool lcd_selfcheck_axis_sg(char axis) {
|
||||||
current_position[axis] = 0;
|
current_position[axis] = 0;
|
||||||
plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
|
plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
|
||||||
|
|
||||||
#ifdef HAVE_TMC2130_DRIVERS
|
#ifdef TMC2130
|
||||||
tmc2130_home_exit();
|
tmc2130_home_exit();
|
||||||
sg_homing_delay = 0;
|
|
||||||
tmc2130_axis_stalled[axis] = false;
|
|
||||||
enable_endstops(true);
|
enable_endstops(true);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -4450,7 +4469,7 @@ static bool lcd_selfcheck_axis_sg(char axis) {
|
||||||
SERIAL_ECHOPGM("Current position 2:");
|
SERIAL_ECHOPGM("Current position 2:");
|
||||||
MYSERIAL.println(current_position[axis]);*/
|
MYSERIAL.println(current_position[axis]);*/
|
||||||
|
|
||||||
#ifdef HAVE_TMC2130_DRIVERS
|
#ifdef TMC2130
|
||||||
tmc2130_home_enter(X_AXIS_MASK << axis);
|
tmc2130_home_enter(X_AXIS_MASK << axis);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -4460,8 +4479,7 @@ static bool lcd_selfcheck_axis_sg(char axis) {
|
||||||
|
|
||||||
st_synchronize();
|
st_synchronize();
|
||||||
|
|
||||||
#ifdef HAVE_TMC2130_DRIVERS
|
#ifdef TMC2130
|
||||||
sg_homing_delay = 0;
|
|
||||||
tmc2130_home_exit();
|
tmc2130_home_exit();
|
||||||
#endif
|
#endif
|
||||||
//current_position[axis] = st_get_position_mm(axis);
|
//current_position[axis] = st_get_position_mm(axis);
|
||||||
|
@ -4475,12 +4493,11 @@ static bool lcd_selfcheck_axis_sg(char axis) {
|
||||||
st_synchronize();
|
st_synchronize();
|
||||||
current_position[axis] += axis_length;
|
current_position[axis] += axis_length;
|
||||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[3], manual_feedrate[0] / 60, active_extruder);
|
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[3], manual_feedrate[0] / 60, active_extruder);
|
||||||
#ifdef HAVE_TMC2130_DRIVERS
|
#ifdef TMC2130
|
||||||
tmc2130_home_enter(X_AXIS_MASK << axis);
|
tmc2130_home_enter(X_AXIS_MASK << axis);
|
||||||
#endif
|
#endif
|
||||||
st_synchronize();
|
st_synchronize();
|
||||||
#ifdef HAVE_TMC2130_DRIVERS
|
#ifdef TMC2130
|
||||||
sg_homing_delay = 0;
|
|
||||||
tmc2130_home_exit();
|
tmc2130_home_exit();
|
||||||
#endif
|
#endif
|
||||||
//current_position[axis] = st_get_position_mm(axis);
|
//current_position[axis] = st_get_position_mm(axis);
|
||||||
|
@ -4495,8 +4512,7 @@ static bool lcd_selfcheck_axis_sg(char axis) {
|
||||||
|
|
||||||
if (abs(measured_axis_length[i] - axis_length) > max_error_mm) {
|
if (abs(measured_axis_length[i] - axis_length) > max_error_mm) {
|
||||||
//axis length
|
//axis length
|
||||||
#ifdef HAVE_TMC2130_DRIVERS
|
#ifdef TMC2130
|
||||||
sg_homing_delay = 0;
|
|
||||||
tmc2130_home_exit();
|
tmc2130_home_exit();
|
||||||
enable_endstops(false);
|
enable_endstops(false);
|
||||||
#endif
|
#endif
|
||||||
|
@ -4576,7 +4592,7 @@ static bool lcd_selfcheck_axis(int _axis, int _travel)
|
||||||
}
|
}
|
||||||
_stepdone = true;
|
_stepdone = true;
|
||||||
}
|
}
|
||||||
#ifdef HAVE_TMC2130_DRIVERS
|
#ifdef TMC2130
|
||||||
tmc2130_home_exit();
|
tmc2130_home_exit();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -4658,8 +4674,8 @@ static bool lcd_selfcheck_pulleys(int axis)
|
||||||
//if (SilentModeMenu == 1) digipot_current(0, tmp_motor[0]); //set back to normal operation currents
|
//if (SilentModeMenu == 1) digipot_current(0, tmp_motor[0]); //set back to normal operation currents
|
||||||
//else digipot_current(0, tmp_motor_loud[0]); //set motor current back
|
//else digipot_current(0, tmp_motor_loud[0]); //set motor current back
|
||||||
current_position[axis] = current_position[axis] - move;
|
current_position[axis] = current_position[axis] - move;
|
||||||
#ifdef HAVE_TMC2130_DRIVERS
|
#ifdef TMC2130
|
||||||
tmc2130_home_enter(axis);
|
tmc2130_home_enter(X_AXIS_MASK << axis);
|
||||||
#endif
|
#endif
|
||||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[3], 50, active_extruder);
|
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[3], 50, active_extruder);
|
||||||
|
|
||||||
|
@ -4668,7 +4684,7 @@ static bool lcd_selfcheck_pulleys(int axis)
|
||||||
lcd_selftest_error(8, (axis == 0) ? "X" : "Y", "");
|
lcd_selftest_error(8, (axis == 0) ? "X" : "Y", "");
|
||||||
return(false);
|
return(false);
|
||||||
}
|
}
|
||||||
#ifdef HAVE_TMC2130_DRIVERS
|
#ifdef TMC2130
|
||||||
tmc2130_home_exit();
|
tmc2130_home_exit();
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
@ -4677,7 +4693,7 @@ static bool lcd_selfcheck_pulleys(int axis)
|
||||||
manage_inactivity(true);
|
manage_inactivity(true);
|
||||||
while (!endstop_triggered) {
|
while (!endstop_triggered) {
|
||||||
if ((x_min_endstop) || (y_min_endstop)) {
|
if ((x_min_endstop) || (y_min_endstop)) {
|
||||||
#ifdef HAVE_TMC2130_DRIVERS
|
#ifdef TMC2130
|
||||||
tmc2130_home_exit();
|
tmc2130_home_exit();
|
||||||
#endif
|
#endif
|
||||||
endstop_triggered = true;
|
endstop_triggered = true;
|
||||||
|
@ -4701,15 +4717,15 @@ static bool lcd_selfcheck_pulleys(int axis)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
#ifdef HAVE_TMC2130_DRIVERS
|
#ifdef TMC2130
|
||||||
tmc2130_home_exit();
|
tmc2130_home_exit();
|
||||||
#endif
|
#endif
|
||||||
//current_position[axis] -= 1;
|
//current_position[axis] -= 1;
|
||||||
current_position[axis] += 50;
|
current_position[axis] += 50;
|
||||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[3], manual_feedrate[0] / 60, active_extruder);
|
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[3], manual_feedrate[0] / 60, active_extruder);
|
||||||
current_position[axis] -= 100;
|
current_position[axis] -= 100;
|
||||||
#ifdef HAVE_TMC2130_DRIVERS
|
#ifdef TMC2130
|
||||||
tmc2130_home_enter(axis);
|
tmc2130_home_enter(X_AXIS_MASK << axis);
|
||||||
#endif
|
#endif
|
||||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[3], manual_feedrate[0] / 60, active_extruder);
|
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[3], manual_feedrate[0] / 60, active_extruder);
|
||||||
st_synchronize();
|
st_synchronize();
|
||||||
|
|
|
@ -734,7 +734,23 @@ static void lcd_implementation_status_screen()
|
||||||
planner_queue_min_reset();
|
planner_queue_min_reset();
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
bool print_sd_status = true;
|
||||||
|
|
||||||
|
#ifdef PINDA_THERMISTOR
|
||||||
|
// if (farm_mode && (custom_message_type == 4))
|
||||||
|
if (false)
|
||||||
|
{
|
||||||
|
lcd.setCursor(0, 2);
|
||||||
|
lcd_printPGM(PSTR("P"));
|
||||||
|
lcd.print(ftostr3(current_temperature_pinda));
|
||||||
|
lcd_printPGM(PSTR(LCD_STR_DEGREE " "));
|
||||||
|
print_sd_status = false;
|
||||||
|
}
|
||||||
|
#endif //PINDA_THERMISTOR
|
||||||
|
|
||||||
|
|
||||||
|
if (print_sd_status)
|
||||||
|
{
|
||||||
//Print SD status
|
//Print SD status
|
||||||
lcd.setCursor(0, 2);
|
lcd.setCursor(0, 2);
|
||||||
if (is_usb_printing)
|
if (is_usb_printing)
|
||||||
|
@ -762,6 +778,7 @@ static void lcd_implementation_status_screen()
|
||||||
lcd.print('%');
|
lcd.print('%');
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
// Farm number display
|
// Farm number display
|
||||||
if (farm_mode)
|
if (farm_mode)
|
||||||
|
|
31
Firmware/uni_avr_rpi.h
Normal file
31
Firmware/uni_avr_rpi.h
Normal file
|
@ -0,0 +1,31 @@
|
||||||
|
// unification for AVR and RPI
|
||||||
|
#define __AVR
|
||||||
|
|
||||||
|
#ifdef __AVR
|
||||||
|
//#include "Arduino.h"
|
||||||
|
#include "Marlin.h"
|
||||||
|
#define GPIO_INP(gpio) pinMode(gpio, INPUT)
|
||||||
|
#define GPIO_OUT(gpio) pinMode(gpio, OUTPUT)
|
||||||
|
#define GPIO_SET(gpio) digitalWrite(gpio, HIGH)
|
||||||
|
#define GPIO_CLR(gpio) digitalWrite(gpio, LOW)
|
||||||
|
#define GPIO_GET(gpio) (digitalRead(gpio) != LOW)
|
||||||
|
#define DELAY(delay) delayMicroseconds(delay)
|
||||||
|
#define PRINT MYSERIAL.print
|
||||||
|
#endif //RC522_AVR
|
||||||
|
|
||||||
|
#ifdef __RPI
|
||||||
|
#include <bcm2835.h>
|
||||||
|
#define GPIO_INP(gpio) bcm2835_gpio_fsel(gpio, BCM2835_GPIO_FSEL_INPT)
|
||||||
|
#define GPIO_OUT(gpio) bcm2835_gpio_fsel(gpio, BCM2835_GPIO_FSEL_OUTP)
|
||||||
|
#define GPIO_SET(gpio) bcm2835_gpio_write(gpio, HIGH)
|
||||||
|
#define GPIO_CLR(gpio) bcm2835_gpio_write(gpio, LOW)
|
||||||
|
#define GPIO_GET(gpio) (bcm2835_gpio_lev(gpio) != LOW)
|
||||||
|
#include <unistd.h>
|
||||||
|
#define DELAY(delay) usleep(delay)
|
||||||
|
#define PRINT(p) print(p)
|
||||||
|
#define DEC 10
|
||||||
|
#define HEX 16
|
||||||
|
void print(const char* pc) { printf("%s", pc); }
|
||||||
|
void print(int v) { printf("%d", v); }
|
||||||
|
void print(float v) { printf("%f", v); }
|
||||||
|
#endif //RC522_RPI
|
|
@ -16,7 +16,6 @@
|
||||||
#define CUSTOM_MENDEL_NAME "Prusa i3 MK3"
|
#define CUSTOM_MENDEL_NAME "Prusa i3 MK3"
|
||||||
|
|
||||||
// Electronics
|
// Electronics
|
||||||
//#define MOTHERBOARD BOARD_EINY_0_4a
|
|
||||||
#define MOTHERBOARD BOARD_EINY_0_3a
|
#define MOTHERBOARD BOARD_EINY_0_3a
|
||||||
|
|
||||||
|
|
||||||
|
@ -33,7 +32,7 @@
|
||||||
|
|
||||||
// Steps per unit {X,Y,Z,E}
|
// Steps per unit {X,Y,Z,E}
|
||||||
//#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,140}
|
//#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,140}
|
||||||
#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,280}
|
#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,280} //Extruder motor changed back to 200step type
|
||||||
|
|
||||||
// Endstop inverting
|
// Endstop inverting
|
||||||
const bool X_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
const bool X_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||||
|
@ -49,7 +48,7 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
|
||||||
#define X_MAX_POS 255
|
#define X_MAX_POS 255
|
||||||
#define X_MIN_POS 0
|
#define X_MIN_POS 0
|
||||||
#define Y_MAX_POS 210
|
#define Y_MAX_POS 210
|
||||||
#define Y_MIN_POS -4
|
#define Y_MIN_POS -12 //orig -4
|
||||||
#define Z_MAX_POS 210
|
#define Z_MAX_POS 210
|
||||||
#define Z_MIN_POS 0.15
|
#define Z_MIN_POS 0.15
|
||||||
|
|
||||||
|
@ -67,11 +66,10 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
|
||||||
|
|
||||||
//#define DEFAULT_MAX_FEEDRATE {400, 400, 12, 120} // (mm/sec)
|
//#define DEFAULT_MAX_FEEDRATE {400, 400, 12, 120} // (mm/sec)
|
||||||
#define DEFAULT_MAX_FEEDRATE {500, 500, 12, 120} // (mm/sec)
|
#define DEFAULT_MAX_FEEDRATE {500, 500, 12, 120} // (mm/sec)
|
||||||
#define DEFAULT_MAX_ACCELERATION {2000, 2000, 250, 5000} // 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_MAX_ACCELERATION {1000, 1000, 200, 5000} // 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 1500 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
|
|
||||||
#define DEFAULT_RETRACT_ACCELERATION 1500 // X, Y, Z and E max acceleration in mm/s^2 for retracts
|
|
||||||
|
|
||||||
|
#define DEFAULT_ACCELERATION 1250 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
|
||||||
|
#define DEFAULT_RETRACT_ACCELERATION 1250 // X, Y, Z and E max acceleration in mm/s^2 for retracts
|
||||||
|
|
||||||
#define MANUAL_FEEDRATE {2700, 2700, 1000, 100} // set the speeds for manual moves (mm/min)
|
#define MANUAL_FEEDRATE {2700, 2700, 1000, 100} // set the speeds for manual moves (mm/min)
|
||||||
//#define MAX_SILENT_FEEDRATE 2700 //
|
//#define MAX_SILENT_FEEDRATE 2700 //
|
||||||
|
@ -80,11 +78,20 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
|
||||||
|
|
||||||
//DEBUG
|
//DEBUG
|
||||||
#if 0
|
#if 0
|
||||||
|
#define DEBUG_DCODES //D codes
|
||||||
|
#define DEBUG_DISABLE_XMINLIMIT //x min limit ignored
|
||||||
|
#define DEBUG_DISABLE_XMAXLIMIT //x max limit ignored
|
||||||
|
#define DEBUG_DISABLE_YMINLIMIT //y min limit ignored
|
||||||
|
#define DEBUG_DISABLE_YMAXLIMIT //y max limit ignored
|
||||||
|
#define DEBUG_DISABLE_ZMINLIMIT //z min limit ignored
|
||||||
|
#define DEBUG_DISABLE_ZMAXLIMIT //z max limit ignored
|
||||||
#define DEBUG_DISABLE_STARTMSGS //no startup messages
|
#define DEBUG_DISABLE_STARTMSGS //no startup messages
|
||||||
#define DEBUG_DISABLE_MINTEMP //mintemp error ignored
|
#define DEBUG_DISABLE_MINTEMP //mintemp error ignored
|
||||||
#define DEBUG_DISABLE_SWLIMITS //sw limits ignored
|
#define DEBUG_DISABLE_SWLIMITS //sw limits ignored
|
||||||
|
#define DEBUG_DISABLE_LCD_STATUS_LINE //empty four lcd line
|
||||||
#define DEBUG_DISABLE_PREVENT_EXTRUDER //cold extrusion and long extrusion allowed
|
#define DEBUG_DISABLE_PREVENT_EXTRUDER //cold extrusion and long extrusion allowed
|
||||||
#define DEBUG_XSTEP_DUP_PIN 21 //duplicate x-step output to pin 21 (SCL on P3)
|
#define DEBUG_DISABLE_PRUSA_STATISTICS //disable prusa_statistics() mesages
|
||||||
|
//#define DEBUG_XSTEP_DUP_PIN 21 //duplicate x-step output to pin 21 (SCL on P3)
|
||||||
//#define DEBUG_YSTEP_DUP_PIN 21 //duplicate y-step output to pin 21 (SCL on P3)
|
//#define DEBUG_YSTEP_DUP_PIN 21 //duplicate y-step output to pin 21 (SCL on P3)
|
||||||
//#define DEBUG_BLINK_ACTIVE
|
//#define DEBUG_BLINK_ACTIVE
|
||||||
#endif
|
#endif
|
||||||
|
@ -97,15 +104,20 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
|
||||||
|
|
||||||
#define TMC2130_USTEPS_XY 16 // microstep resolution for XY axes
|
#define TMC2130_USTEPS_XY 16 // microstep resolution for XY axes
|
||||||
#define TMC2130_USTEPS_Z 16 // microstep resolution for Z axis
|
#define TMC2130_USTEPS_Z 16 // microstep resolution for Z axis
|
||||||
#define TMC2130_USTEPS_E 16 // microstep resolution for E axis
|
#define TMC2130_USTEPS_E 32 // microstep resolution for E axis (increased from 16 to 32)
|
||||||
#define TMC2130_INTPOL_XY 1 // extrapolate 256 for XY axes
|
#define TMC2130_INTPOL_XY 1 // extrapolate 256 for XY axes
|
||||||
#define TMC2130_INTPOL_Z 1 // extrapolate 256 for Z axis
|
#define TMC2130_INTPOL_Z 1 // extrapolate 256 for Z axis
|
||||||
#define TMC2130_INTPOL_E 1 // extrapolate 256 for E axis
|
#define TMC2130_INTPOL_E 1 // extrapolate 256 for E axis
|
||||||
|
|
||||||
#define TMC2130_PWM_GRAD_XY 15 // PWMCONF
|
#define TMC2130_PWM_GRAD_X 4 // PWMCONF
|
||||||
#define TMC2130_PWM_AMPL_XY 200 // PWMCONF
|
#define TMC2130_PWM_AMPL_X 200 // PWMCONF
|
||||||
#define TMC2130_PWM_AUTO_XY 1 // PWMCONF
|
#define TMC2130_PWM_AUTO_X 1 // PWMCONF
|
||||||
#define TMC2130_PWM_FREQ_XY 2 // PWMCONF
|
#define TMC2130_PWM_FREQ_X 2 // PWMCONF
|
||||||
|
|
||||||
|
#define TMC2130_PWM_GRAD_Y 4 // PWMCONF
|
||||||
|
#define TMC2130_PWM_AMPL_Y 210 // PWMCONF
|
||||||
|
#define TMC2130_PWM_AUTO_Y 1 // PWMCONF
|
||||||
|
#define TMC2130_PWM_FREQ_Y 2 // PWMCONF
|
||||||
|
|
||||||
/* //not used
|
/* //not used
|
||||||
#define TMC2130_PWM_GRAD_Z 4 // PWMCONF
|
#define TMC2130_PWM_GRAD_Z 4 // PWMCONF
|
||||||
|
@ -118,26 +130,28 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
|
||||||
#define TMC2130_PWM_FREQ_E 2 // PWMCONF
|
#define TMC2130_PWM_FREQ_E 2 // PWMCONF
|
||||||
*/
|
*/
|
||||||
|
|
||||||
//#define TMC2130_PWM_DIV 683 // PWM frequency divider (1024, 683, 512, 410)
|
//#define TMC2130_PWM_DIV 683 // PWM frequency divider (1024, 683, 512, 410)
|
||||||
#define TMC2130_PWM_DIV 512 // PWM frequency divider (1024, 683, 512, 410)
|
#define TMC2130_PWM_DIV 512 // PWM frequency divider (1024, 683, 512, 410)
|
||||||
#define TMC2130_PWM_CLK (2 * TMC2130_FCLK / TMC2130_PWM_DIV) // PWM frequency (23.4kHz, 35.1kHz, 46.9kHz, 58.5kHz for 12MHz fclk)
|
#define TMC2130_PWM_CLK (2 * TMC2130_FCLK / TMC2130_PWM_DIV) // PWM frequency (23.4kHz, 35.1kHz, 46.9kHz, 58.5kHz for 12MHz fclk)
|
||||||
|
|
||||||
#define TMC2130_TPWMTHRS 0 // TPWMTHRS - Sets the switching speed threshold based on TSTEP from stealthChop to spreadCycle mode
|
#define TMC2130_TPWMTHRS 0 // TPWMTHRS - Sets the switching speed threshold based on TSTEP from stealthChop to spreadCycle mode
|
||||||
#define TMC2130_THIGH 0 // THIGH - unused
|
#define TMC2130_THIGH 0 // THIGH - unused
|
||||||
|
|
||||||
#define TMC2130_TCOOLTHRS 239 // TCOOLTHRS - coolstep treshold
|
#define TMC2130_TCOOLTHRS 239 // TCOOLTHRS - coolstep treshold
|
||||||
|
|
||||||
#define TMC2130_SG_HOMING 1 // stallguard homing
|
#define TMC2130_SG_HOMING 1 // stallguard homing
|
||||||
#define TMC2130_SG_HOMING_SW 1 // stallguard "software" homing
|
//#define TMC2130_SG_HOMING_SW_XY 1 // stallguard "software" homing for XY axes
|
||||||
#define TMC2130_SG_THRS_X 30 // stallguard sensitivity for X axis
|
#define TMC2130_SG_HOMING_SW_Z 1 // stallguard "software" homing for Z axis
|
||||||
#define TMC2130_SG_THRS_Y 30 // stallguard sensitivity for Y axis
|
#define TMC2130_SG_THRS_X 0 // stallguard sensitivity for X axis
|
||||||
#define TMC2130_SG_DELAY 10 // stallguard delay (temporary solution)
|
#define TMC2130_SG_THRS_Y 0 // stallguard sensitivity for Y axis
|
||||||
|
#define TMC2130_SG_THRS_Z 2 // stallguard sensitivity for Z axis
|
||||||
|
#define TMC2130_SG_DELTA 128 // stallguard delta [usteps] (minimum usteps before stallguard readed - SW homing)
|
||||||
|
|
||||||
//new settings is possible for vsense = 1
|
//new settings is possible for vsense = 1, running current value > 31 set vsense to zero and shift both currents by 1 bit right (Z axis only)
|
||||||
#define TMC2130_CURRENTS_H {3, 3, 5, 8} // default holding currents for all axes
|
#define TMC2130_CURRENTS_H {3, 3, 5, 8} // default holding currents for all axes
|
||||||
#define TMC2130_CURRENTS_R {13, 13, 20, 20} // default running currents for all axes
|
#define TMC2130_CURRENTS_R {13, 18, 20, 22} // default running currents for all axes
|
||||||
|
|
||||||
#define TMC2130_DEBUG
|
//#define TMC2130_DEBUG
|
||||||
//#define TMC2130_DEBUG_WR
|
//#define TMC2130_DEBUG_WR
|
||||||
//#define TMC2130_DEBUG_RD
|
//#define TMC2130_DEBUG_RD
|
||||||
|
|
||||||
|
@ -254,7 +268,7 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
|
||||||
#define DIGIPOT_MOTOR_CURRENT_LOUD {135,135,135,135,135}
|
#define DIGIPOT_MOTOR_CURRENT_LOUD {135,135,135,135,135}
|
||||||
|
|
||||||
// Motor Current settings for RAMBo mini PWM value = MotorCurrentSetting * 255 / range
|
// Motor Current settings for RAMBo mini PWM value = MotorCurrentSetting * 255 / range
|
||||||
#if MOTHERBOARD == 102 || MOTHERBOARD == 302 || MOTHERBOARD == 300 || MOTHERBOARD == 299
|
#if MOTHERBOARD == 200 || MOTHERBOARD == 203 || MOTHERBOARD == 303 || MOTHERBOARD == 304 || MOTHERBOARD == 305
|
||||||
#define MOTOR_CURRENT_PWM_RANGE 2000
|
#define MOTOR_CURRENT_PWM_RANGE 2000
|
||||||
#define DEFAULT_PWM_MOTOR_CURRENT {400, 750, 750} // {XY,Z,E}
|
#define DEFAULT_PWM_MOTOR_CURRENT {400, 750, 750} // {XY,Z,E}
|
||||||
#define DEFAULT_PWM_MOTOR_CURRENT_LOUD {400, 750, 750} // {XY,Z,E}
|
#define DEFAULT_PWM_MOTOR_CURRENT_LOUD {400, 750, 750} // {XY,Z,E}
|
||||||
|
@ -426,6 +440,8 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
|
||||||
#else
|
#else
|
||||||
#define TEMP_SENSOR_BED 1
|
#define TEMP_SENSOR_BED 1
|
||||||
#endif
|
#endif
|
||||||
|
#define TEMP_SENSOR_PINDA 1
|
||||||
|
#define TEMP_SENSOR_AMBIENT 2000
|
||||||
|
|
||||||
#define STACK_GUARD_TEST_VALUE 0xA2A2
|
#define STACK_GUARD_TEST_VALUE 0xA2A2
|
||||||
|
|
||||||
|
@ -464,4 +480,6 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
|
||||||
#define DEFAULT_RETRACTION 1 //used for PINDA temp calibration and pause print
|
#define DEFAULT_RETRACTION 1 //used for PINDA temp calibration and pause print
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#define UVLO_Z_AXIS_SHIFT 2
|
||||||
|
|
||||||
#endif //__CONFIGURATION_PRUSA_H
|
#endif //__CONFIGURATION_PRUSA_H
|
||||||
|
|
|
@ -17,7 +17,6 @@
|
||||||
|
|
||||||
// Electronics
|
// Electronics
|
||||||
#define MOTHERBOARD BOARD_EINY_0_4a
|
#define MOTHERBOARD BOARD_EINY_0_4a
|
||||||
//#define MOTHERBOARD BOARD_EINY_0_3a
|
|
||||||
|
|
||||||
|
|
||||||
// Uncomment the below for the E3D PT100 temperature sensor (with or without PT100 Amplifier)
|
// Uncomment the below for the E3D PT100 temperature sensor (with or without PT100 Amplifier)
|
||||||
|
@ -33,7 +32,7 @@
|
||||||
|
|
||||||
// Steps per unit {X,Y,Z,E}
|
// Steps per unit {X,Y,Z,E}
|
||||||
//#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,140}
|
//#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,140}
|
||||||
#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,280*4}
|
#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,280} //Extruder motor changed back to 200step type
|
||||||
|
|
||||||
// Endstop inverting
|
// Endstop inverting
|
||||||
const bool X_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
const bool X_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||||
|
@ -42,14 +41,14 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
|
||||||
|
|
||||||
// Home position
|
// Home position
|
||||||
#define MANUAL_X_HOME_POS 0
|
#define MANUAL_X_HOME_POS 0
|
||||||
#define MANUAL_Y_HOME_POS -13
|
#define MANUAL_Y_HOME_POS -2.2
|
||||||
#define MANUAL_Z_HOME_POS 0.2
|
#define MANUAL_Z_HOME_POS 0.2
|
||||||
|
|
||||||
// Travel limits after homing
|
// Travel limits after homing
|
||||||
#define X_MAX_POS 255
|
#define X_MAX_POS 255
|
||||||
#define X_MIN_POS 0
|
#define X_MIN_POS 0
|
||||||
#define Y_MAX_POS 210
|
#define Y_MAX_POS 210
|
||||||
#define Y_MIN_POS -13
|
#define Y_MIN_POS -12 //orig -4
|
||||||
#define Z_MAX_POS 210
|
#define Z_MAX_POS 210
|
||||||
#define Z_MIN_POS 0.15
|
#define Z_MIN_POS 0.15
|
||||||
|
|
||||||
|
@ -67,11 +66,10 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
|
||||||
|
|
||||||
//#define DEFAULT_MAX_FEEDRATE {400, 400, 12, 120} // (mm/sec)
|
//#define DEFAULT_MAX_FEEDRATE {400, 400, 12, 120} // (mm/sec)
|
||||||
#define DEFAULT_MAX_FEEDRATE {500, 500, 12, 120} // (mm/sec)
|
#define DEFAULT_MAX_FEEDRATE {500, 500, 12, 120} // (mm/sec)
|
||||||
#define DEFAULT_MAX_ACCELERATION {2000, 2000, 250, 5000} // 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_MAX_ACCELERATION {1000, 1000, 200, 5000} // 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 1500 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
|
|
||||||
#define DEFAULT_RETRACT_ACCELERATION 1500 // X, Y, Z and E max acceleration in mm/s^2 for retracts
|
|
||||||
|
|
||||||
|
#define DEFAULT_ACCELERATION 1250 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
|
||||||
|
#define DEFAULT_RETRACT_ACCELERATION 1250 // X, Y, Z and E max acceleration in mm/s^2 for retracts
|
||||||
|
|
||||||
#define MANUAL_FEEDRATE {2700, 2700, 1000, 100} // set the speeds for manual moves (mm/min)
|
#define MANUAL_FEEDRATE {2700, 2700, 1000, 100} // set the speeds for manual moves (mm/min)
|
||||||
//#define MAX_SILENT_FEEDRATE 2700 //
|
//#define MAX_SILENT_FEEDRATE 2700 //
|
||||||
|
@ -80,11 +78,20 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
|
||||||
|
|
||||||
//DEBUG
|
//DEBUG
|
||||||
#if 0
|
#if 0
|
||||||
|
#define DEBUG_DCODES //D codes
|
||||||
|
#define DEBUG_DISABLE_XMINLIMIT //x min limit ignored
|
||||||
|
#define DEBUG_DISABLE_XMAXLIMIT //x max limit ignored
|
||||||
|
#define DEBUG_DISABLE_YMINLIMIT //y min limit ignored
|
||||||
|
#define DEBUG_DISABLE_YMAXLIMIT //y max limit ignored
|
||||||
|
#define DEBUG_DISABLE_ZMINLIMIT //z min limit ignored
|
||||||
|
#define DEBUG_DISABLE_ZMAXLIMIT //z max limit ignored
|
||||||
#define DEBUG_DISABLE_STARTMSGS //no startup messages
|
#define DEBUG_DISABLE_STARTMSGS //no startup messages
|
||||||
#define DEBUG_DISABLE_MINTEMP //mintemp error ignored
|
#define DEBUG_DISABLE_MINTEMP //mintemp error ignored
|
||||||
#define DEBUG_DISABLE_SWLIMITS //sw limits ignored
|
#define DEBUG_DISABLE_SWLIMITS //sw limits ignored
|
||||||
|
#define DEBUG_DISABLE_LCD_STATUS_LINE //empty four lcd line
|
||||||
#define DEBUG_DISABLE_PREVENT_EXTRUDER //cold extrusion and long extrusion allowed
|
#define DEBUG_DISABLE_PREVENT_EXTRUDER //cold extrusion and long extrusion allowed
|
||||||
#define DEBUG_XSTEP_DUP_PIN 21 //duplicate x-step output to pin 21 (SCL on P3)
|
#define DEBUG_DISABLE_PRUSA_STATISTICS //disable prusa_statistics() mesages
|
||||||
|
//#define DEBUG_XSTEP_DUP_PIN 21 //duplicate x-step output to pin 21 (SCL on P3)
|
||||||
//#define DEBUG_YSTEP_DUP_PIN 21 //duplicate y-step output to pin 21 (SCL on P3)
|
//#define DEBUG_YSTEP_DUP_PIN 21 //duplicate y-step output to pin 21 (SCL on P3)
|
||||||
//#define DEBUG_BLINK_ACTIVE
|
//#define DEBUG_BLINK_ACTIVE
|
||||||
#endif
|
#endif
|
||||||
|
@ -97,15 +104,20 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
|
||||||
|
|
||||||
#define TMC2130_USTEPS_XY 16 // microstep resolution for XY axes
|
#define TMC2130_USTEPS_XY 16 // microstep resolution for XY axes
|
||||||
#define TMC2130_USTEPS_Z 16 // microstep resolution for Z axis
|
#define TMC2130_USTEPS_Z 16 // microstep resolution for Z axis
|
||||||
#define TMC2130_USTEPS_E 64 // microstep resolution for E axis
|
#define TMC2130_USTEPS_E 32 // microstep resolution for E axis (increased from 16 to 32)
|
||||||
#define TMC2130_INTPOL_XY 1 // extrapolate 256 for XY axes
|
#define TMC2130_INTPOL_XY 1 // extrapolate 256 for XY axes
|
||||||
#define TMC2130_INTPOL_Z 1 // extrapolate 256 for Z axis
|
#define TMC2130_INTPOL_Z 1 // extrapolate 256 for Z axis
|
||||||
#define TMC2130_INTPOL_E 1 // extrapolate 256 for E axis
|
#define TMC2130_INTPOL_E 1 // extrapolate 256 for E axis
|
||||||
|
|
||||||
#define TMC2130_PWM_GRAD_XY 15 // PWMCONF
|
#define TMC2130_PWM_GRAD_X 4 // PWMCONF
|
||||||
#define TMC2130_PWM_AMPL_XY 200 // PWMCONF
|
#define TMC2130_PWM_AMPL_X 200 // PWMCONF
|
||||||
#define TMC2130_PWM_AUTO_XY 1 // PWMCONF
|
#define TMC2130_PWM_AUTO_X 1 // PWMCONF
|
||||||
#define TMC2130_PWM_FREQ_XY 2 // PWMCONF
|
#define TMC2130_PWM_FREQ_X 2 // PWMCONF
|
||||||
|
|
||||||
|
#define TMC2130_PWM_GRAD_Y 4 // PWMCONF
|
||||||
|
#define TMC2130_PWM_AMPL_Y 210 // PWMCONF
|
||||||
|
#define TMC2130_PWM_AUTO_Y 1 // PWMCONF
|
||||||
|
#define TMC2130_PWM_FREQ_Y 2 // PWMCONF
|
||||||
|
|
||||||
/* //not used
|
/* //not used
|
||||||
#define TMC2130_PWM_GRAD_Z 4 // PWMCONF
|
#define TMC2130_PWM_GRAD_Z 4 // PWMCONF
|
||||||
|
@ -118,28 +130,30 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
|
||||||
#define TMC2130_PWM_FREQ_E 2 // PWMCONF
|
#define TMC2130_PWM_FREQ_E 2 // PWMCONF
|
||||||
*/
|
*/
|
||||||
|
|
||||||
//#define TMC2130_PWM_DIV 683 // PWM frequency divider (1024, 683, 512, 410)
|
//#define TMC2130_PWM_DIV 683 // PWM frequency divider (1024, 683, 512, 410)
|
||||||
#define TMC2130_PWM_DIV 512 // PWM frequency divider (1024, 683, 512, 410)
|
#define TMC2130_PWM_DIV 512 // PWM frequency divider (1024, 683, 512, 410)
|
||||||
#define TMC2130_PWM_CLK (2 * TMC2130_FCLK / TMC2130_PWM_DIV) // PWM frequency (23.4kHz, 35.1kHz, 46.9kHz, 58.5kHz for 12MHz fclk)
|
#define TMC2130_PWM_CLK (2 * TMC2130_FCLK / TMC2130_PWM_DIV) // PWM frequency (23.4kHz, 35.1kHz, 46.9kHz, 58.5kHz for 12MHz fclk)
|
||||||
|
|
||||||
#define TMC2130_TPWMTHRS 0 // TPWMTHRS - Sets the switching speed threshold based on TSTEP from stealthChop to spreadCycle mode
|
#define TMC2130_TPWMTHRS 0 // TPWMTHRS - Sets the switching speed threshold based on TSTEP from stealthChop to spreadCycle mode
|
||||||
#define TMC2130_THIGH 0 // THIGH - unused
|
#define TMC2130_THIGH 0 // THIGH - unused
|
||||||
|
|
||||||
#define TMC2130_TCOOLTHRS 239 // TCOOLTHRS - coolstep treshold
|
#define TMC2130_TCOOLTHRS 239 // TCOOLTHRS - coolstep treshold
|
||||||
|
|
||||||
#define TMC2130_SG_HOMING 1 // stallguard homing
|
#define TMC2130_SG_HOMING 1 // stallguard homing
|
||||||
#define TMC2130_SG_HOMING_SW 1 // stallguard "software" homing
|
//#define TMC2130_SG_HOMING_SW_XY 1 // stallguard "software" homing for XY axes
|
||||||
#define TMC2130_SG_THRS_X 40 // stallguard sensitivity for X axis
|
#define TMC2130_SG_HOMING_SW_Z 1 // stallguard "software" homing for Z axis
|
||||||
#define TMC2130_SG_THRS_Y 40 // stallguard sensitivity for Y axis
|
#define TMC2130_SG_THRS_X 0 // stallguard sensitivity for X axis
|
||||||
#define TMC2130_SG_DELAY 10 // stallguard delay (temporary solution)
|
#define TMC2130_SG_THRS_Y 0 // stallguard sensitivity for Y axis
|
||||||
|
#define TMC2130_SG_THRS_Z 2 // stallguard sensitivity for Z axis
|
||||||
|
#define TMC2130_SG_DELTA 128 // stallguard delta [usteps] (minimum usteps before stallguard readed - SW homing)
|
||||||
|
|
||||||
//new settings is possible for vsense = 1
|
//new settings is possible for vsense = 1, running current value > 31 set vsense to zero and shift both currents by 1 bit right (Z axis only)
|
||||||
#define TMC2130_CURRENTS_H {15, 15, 20, 28} // default holding currents for all axes
|
#define TMC2130_CURRENTS_H {3, 3, 5, 8} // default holding currents for all axes
|
||||||
#define TMC2130_CURRENTS_R {15, 15, 40, 28} // default running currents for all axes
|
#define TMC2130_CURRENTS_R {13, 18, 20, 22} // default running currents for all axes
|
||||||
|
|
||||||
//#define TMC2130_DEBUG
|
//#define TMC2130_DEBUG
|
||||||
//#define TMC2130_DEBUG_WR
|
//#define TMC2130_DEBUG_WR
|
||||||
#define TMC2130_DEBUG_RD
|
//#define TMC2130_DEBUG_RD
|
||||||
|
|
||||||
|
|
||||||
/*------------------------------------
|
/*------------------------------------
|
||||||
|
@ -254,7 +268,7 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
|
||||||
#define DIGIPOT_MOTOR_CURRENT_LOUD {135,135,135,135,135}
|
#define DIGIPOT_MOTOR_CURRENT_LOUD {135,135,135,135,135}
|
||||||
|
|
||||||
// Motor Current settings for RAMBo mini PWM value = MotorCurrentSetting * 255 / range
|
// Motor Current settings for RAMBo mini PWM value = MotorCurrentSetting * 255 / range
|
||||||
#if MOTHERBOARD == 102 || MOTHERBOARD == 302 || MOTHERBOARD == 300 || MOTHERBOARD == 299
|
#if MOTHERBOARD == 200 || MOTHERBOARD == 203 || MOTHERBOARD == 303 || MOTHERBOARD == 304 || MOTHERBOARD == 305
|
||||||
#define MOTOR_CURRENT_PWM_RANGE 2000
|
#define MOTOR_CURRENT_PWM_RANGE 2000
|
||||||
#define DEFAULT_PWM_MOTOR_CURRENT {400, 750, 750} // {XY,Z,E}
|
#define DEFAULT_PWM_MOTOR_CURRENT {400, 750, 750} // {XY,Z,E}
|
||||||
#define DEFAULT_PWM_MOTOR_CURRENT_LOUD {400, 750, 750} // {XY,Z,E}
|
#define DEFAULT_PWM_MOTOR_CURRENT_LOUD {400, 750, 750} // {XY,Z,E}
|
||||||
|
@ -273,7 +287,7 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
|
||||||
// Mesh definitions
|
// Mesh definitions
|
||||||
#define MESH_MIN_X 35
|
#define MESH_MIN_X 35
|
||||||
#define MESH_MAX_X 238
|
#define MESH_MAX_X 238
|
||||||
#define MESH_MIN_Y 8
|
#define MESH_MIN_Y 6
|
||||||
#define MESH_MAX_Y 202
|
#define MESH_MAX_Y 202
|
||||||
|
|
||||||
// Mesh upsample definition
|
// Mesh upsample definition
|
||||||
|
@ -287,7 +301,7 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
|
||||||
#define MESH_HOME_Z_SEARCH 5 //Z lift for homing, mesh bed leveling etc.
|
#define MESH_HOME_Z_SEARCH 5 //Z lift for homing, mesh bed leveling etc.
|
||||||
|
|
||||||
#define X_PROBE_OFFSET_FROM_EXTRUDER 23 // Z probe to nozzle X offset: -left +right
|
#define X_PROBE_OFFSET_FROM_EXTRUDER 23 // Z probe to nozzle X offset: -left +right
|
||||||
#define Y_PROBE_OFFSET_FROM_EXTRUDER 8 // Z probe to nozzle Y offset: -front +behind
|
#define Y_PROBE_OFFSET_FROM_EXTRUDER 9 // Z probe to nozzle Y offset: -front +behind
|
||||||
#define Z_PROBE_OFFSET_FROM_EXTRUDER -0.4 // Z probe to nozzle Z offset: -below (always!)
|
#define Z_PROBE_OFFSET_FROM_EXTRUDER -0.4 // Z probe to nozzle Z offset: -below (always!)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -426,6 +440,8 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
|
||||||
#else
|
#else
|
||||||
#define TEMP_SENSOR_BED 1
|
#define TEMP_SENSOR_BED 1
|
||||||
#endif
|
#endif
|
||||||
|
#define TEMP_SENSOR_PINDA 1
|
||||||
|
#define TEMP_SENSOR_AMBIENT 2000
|
||||||
|
|
||||||
#define STACK_GUARD_TEST_VALUE 0xA2A2
|
#define STACK_GUARD_TEST_VALUE 0xA2A2
|
||||||
|
|
||||||
|
@ -464,7 +480,6 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
|
||||||
#define DEFAULT_RETRACTION 1 //used for PINDA temp calibration and pause print
|
#define DEFAULT_RETRACTION 1 //used for PINDA temp calibration and pause print
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
#define UVLO_Z_AXIS_SHIFT 2
|
#define UVLO_Z_AXIS_SHIFT 2
|
||||||
|
|
||||||
#endif //__CONFIGURATION_PRUSA_H
|
#endif //__CONFIGURATION_PRUSA_H
|
||||||
|
|
Loading…
Reference in a new issue