Welcome to mirror list, hosted at ThFree Co, Russian Federation.

github.com/Duet3D/RepRapFirmware.git - Unnamed repository; edit this file 'description' to name the repository.
summaryrefslogtreecommitdiff
path: root/src
diff options
context:
space:
mode:
authorDavid Crocker <dcrocker@eschertech.com>2017-11-29 00:45:15 +0300
committerDavid Crocker <dcrocker@eschertech.com>2017-11-29 00:45:15 +0300
commit682fa84b74247c845486298747e6d41d8e0df2e6 (patch)
tree1704c4c3e2811acad958b8c5f883af0a173ca03e /src
parent1ddb7d2aa8af41ef4bee3f06a10f6edd0d999e88 (diff)
Version 1.20beta11
New features: - Added Hangprinter kinematics. Auto calibration is not expected to work yet. - Added M122 P1 command for use in the Duet test procedure - Changed a path to a file in the linker command line to work around an intermittent Eclipse bug - DuetWiFi/Duet Ethernet: the secondary hardware watchdog is now enabled and generates an interrupt, so that if interrupts are enabled at the time then a crash dump can be saved. If this fails then the primary watchdog will reset the processor as before. Bug fixes: - Fixed issues caused by insufficient RAM (stack running into heap) by freeing up additional RAM in the movement structures - Fixed occasional hang in USB ISR - M201/203/208/566 commands now allow parameters for invisible axes to be set - If a M584 command does not include the P parameter, the number of visible axes is only set to the number of total axes if new axes are created in the command - Reverted to rounding down in step time calculations, because the change to round to nearest may have contributed to issues seen by some users of 1.20beta10 - Set correct priority for interrupt from the UART used to receive debug info from the WiFi module - When a filament error occurred, the message displayed was one of the lines written to resurrect.g instead of the type of filament error. Similarly if the print was paused due to a motor stall.
Diffstat (limited to 'src')
-rw-r--r--src/BugList.txt155
-rw-r--r--src/Configuration.h11
-rw-r--r--src/Duet/Pins_Duet.h107
-rw-r--r--src/DuetNG/Pins_DuetNG.h25
-rw-r--r--src/GCodes/GCodes.cpp12
-rw-r--r--src/GCodes/GCodes2.cpp23
-rw-r--r--src/MessageType.h5
-rw-r--r--src/Movement/DDA.cpp50
-rw-r--r--src/Movement/DDA.h3
-rw-r--r--src/Movement/DriveMovement.cpp112
-rw-r--r--src/Movement/DriveMovement.h96
-rw-r--r--src/Movement/Kinematics/HangprinterKinematics.cpp614
-rw-r--r--src/Movement/Kinematics/HangprinterKinematics.h69
-rw-r--r--src/Movement/Kinematics/Kinematics.cpp3
-rw-r--r--src/Movement/Kinematics/LinearDeltaKinematics.cpp129
-rw-r--r--src/Movement/Kinematics/LinearDeltaKinematics.h9
-rw-r--r--src/Movement/Kinematics/ScaraKinematics.cpp2
-rw-r--r--src/Movement/Kinematics/ZLeadscrewKinematics.cpp4
-rw-r--r--src/Movement/Move.h2
-rw-r--r--src/Platform.cpp377
-rw-r--r--src/Platform.h63
-rw-r--r--src/RepRapFirmware.h10
-rw-r--r--src/Version.h4
23 files changed, 1486 insertions, 399 deletions
diff --git a/src/BugList.txt b/src/BugList.txt
new file mode 100644
index 00000000..749d5285
--- /dev/null
+++ b/src/BugList.txt
@@ -0,0 +1,155 @@
+RRF 1.20 work list
+
+- Logging
+- [done] Fix message "...before homing the towers of a Delta or SCARA printer"
+- [done] M552 option to connect to specified access point on Duet WiFi, including hidden SSIDs
+- [done] Ian's pressure advance issue, https://www.duet3d.com/forum/thread.php?pid=24928#p24928
+- [done] Add "USB will disconnect during firmware update" message
+- [done] Fix duplicate error message when we fail to open a gcode file
+- [done, needs testing] M572 S0.4 D0:1:2:3:4
+- [done, needs testing] Keep 2 grids: the one defined by M577, and the one used by the current grid (e.g. loaded with a height map)
+- [done] Enable pullups on CONN_LCD endstop inputs
+- [done] Bug fix to bed probing bug on SCARA (skips points that it shouldn't skip)
+- [done] Support manual bed adjustment on SCARA kinematics
+- [done] Ignore correction limits for manual bed adjustment
+- [done] SCARA: don't allow mode change for coordinated move
+- [done] SCARA: apply arm limits when converting coordinates
+- [done] when simulating a print, never create or delete resurrect.g
+- [done] when simulating, don't segment
+- [done] Bug fix: missing P parameter in G10 command in resurrect.g
+- [done] When temperature is within 3C of target, switch to fast PID parameters
+
+Above done in 1.20beta1
+
+- [done] G31 parameters no longer written to config-override.g
+- [done] multiple G and M commands on a single line
+- [done] SCARA: do the conversion during the request to limit coordinates, cache result for use if we are asked to do it (need coordinates/uncoordinated flag to 'isReachable')
+- [done] add log entry for time/date set
+- [done] log "max open file count exceeded" message
+- [done] Send heater 0 values to PanelDue even if no heated bed
+- [done] In resurrect.g move up, sideways and down when restoring position
+- [done] SCARA: movement is slow at start, and is still jerky after that
+- [coolstep done] Experimental configurable Stallguard detection + configurable Coolstep (M915)
+- [done] Easier way to resume a print (M916)
+- [done] Power off pause: stop immediately. Need to do a partial move on restart. Or repeat the whole move, from the start of the first segment.
+- [done, needs testing] Pause print on heater error
+- [done] include G- or M-code in error messages
+- [done] when tuning, use specified max pwm if given, or old max pwm if not
+- [done] Increase ADC oversample bits to 2
+- [done] Display wifi sleep mode
+- [done] M114 remove space after colon for Pronterface
+- [done] Parameter R-1 in M569 command disables driver monitoring
+- [done] Implement M585
+- [done] if axis lengths are adjusted by probing, M500 should save them in config-override.g
+- [done] if tool offsets are adjusted by probing, M500 should save them in config-override.g
+- [done] consider using a better way of counting layers
+- [done] debug messages are prevented from causing software watchdog resets
+- [done] limit axis speeds properly in corexy
+- [done] polar kinematics initial support
+- [done] faster short-to-ground detection
+- [done] rr_ command parameters are order-independent
+- [done] Duet WiFi: more network debug info
+- [done] "Bed probe heights" in M122 -> "G32 bed probe heights"
+
+Above done in 1.20beta2
+
+Bugs fixed in beta 3:
+- config-override.g extra M307 lines
+- CoreXY homing was broken
+- motor idle detection was broken
+- M585 didn't work
+- Can't resume if no M911 command used
+- prints diagnostics if you send a command with the string 122 in it
+
+Done in beta3:
+- when a print is cancelled, don't send 'finished printing file ...." message, just the cancel message
+
+Done in beta4+1:
+- PT100 reference resistor configuration
+- PT100 3-wire config supported
+- M906 and M913 don't wait for movement to stop
+- Endstop types changed. For Ormerod/Mendel/Huxley need to change M574 command. XYZ parameters removed from M558.
+- Bug fix: 31856 thermocouple code buffer overflow in SPI read
+
+Done in beta 6:
+- Stall detection: get it usable
+- Allow ABC to be created without creating XYZ, for CNC applications
+- Stall detection: option to log stalls but take no other action
+- Send axis names to DWC and PanelDue
+
+Done in 1.20beta7:
+- Optional quotes around filenames etc.
+- Always use gcode queue when executing macros
+- Pausing: IsPausing etc. need to take account of all gcode sources, not just fileGCode
+- M0/M1 don't turn off heaters and drives when in simulation mode
+- SCARA crosstalk to be in movement amount not steps
+- SCARA homing didn't take account of crosstalk
+- deleteexisting=yes option in http move command
+- in M589 the IP address should be compulsory
+- feed rate wasn't being passed to fileGCode when resuming a print
+- when a T command is sent, make sure the tool heaters are turned on
+- support CWD . in FTP
+- [tested, ok] test resurrect in absolute extrusion mode - does the M82/83 apply to the wrong gcode source?
+
+Done in 1.20beta8:
+- [done, ok] Command to activate the tool that was active at a pause (T R1?)
+- [done, ok] Stall detection: implement R2 R3
+- [done] Compensate extruder heater power for supply voltage
+- [done] in M587 and M589 report the IP addresses
+- [done] sensorless homing: for corexy monitor both X and Y
+- [done, ok] can pause within segmented moves
+- [done] add log entries for undervoltage, overvoltage
+- [done, test] log overheating drivers
+- [done, ok] log M81 power off
+- [done, ok] M562 with no parameter clears all heater faults
+- [done, ok] support mixed analog/digital write on SX1509B pins
+- [done] Bug fix to M26 P parameter on resume after power fail
+
+Done in 1.20beta10:
+- [done, test] Heater fault timeout to cancelling print to be configurable
+- [done] Filament monitor always updates calibration accumulators during a print even if not in calbration mode
+- [done] Added CoreXYUV
+- [done] improved square root timing
+- [done] added Z probe types 7 and 8
+- [done] bug fix: semicolons inside quoted strings were still stipped out from some gcode sources
+- [done] Bug fix: giving silly numbers of microsteps in M350 messed up the steps/mm
+- [done] Bug fix: High microstepping and high acceleration on deltas led to poor timing in deceleration phase and high MaxReps
+- [done] Bug fix: The commands in tool change macro files were sometimes not fully executed before the next action
+- [done] Bug fix to speed limits in CoreXYU
+- [done] Possible bug fix: avoid race condition in TMC SPI ISR
+
+Remaining:
+- [done, test] On filament error, doesn't print the right message in the box
+- On filament error, doesn't log the message
+- On filament error, and only pops up a message box once
+- Layer shift reports (new in beta 10)
+- Report of watchdog resets (from 1.20beta7)
+- [done, test] Add test report: test voltage readings, stepper driver status, SD card interface speed, and report processor ID
+- [done] M92, M201 etc. to work on all axes, not just visible axes
+
+- Implement G1 S4? (like S2 but always relative)
+- Need protection against deleting an open file especially a log file
+- add log entries for power down?
+- card detect?
+
+Investigations:
+
+[NOT fixed by timing and ISR changes] https://www.duet3d.com/forum/thread.php?pid=30414#p30414 (watchdog reset)
+[can't reproduce] https://www.duet3d.com/forum/thread.php?pid=28210#p28210 (pressure advance causes over extrusion)
+[done] https://www.duet3d.com/forum/thread.php?pid=28255#p28255 (tool change problem)
+[done] https://www.duet3d.com/forum/thread.php?pid=30431#p30431 (bed probing inaccurate)
+[can't reproduce] https://www.duet3d.com/forum/thread.php?pid=30799#p30799 (step errors at high E steps/mm)
+[no fault] https://www.duet3d.com/forum/thread.php?pid=30851#p30851 (split axis motor goes the wrong way)
+[done] inconsistend oversize vs. len
+p->ref == 1 in EWiFi
+
+Later versions:
+
+- Add work coordinates? https://www.duet3d.com/forum/thread.php?pid=27128#p27128
+Don't do presure advance during accel/decel of sequences of short segments
+Axis limits on arc moves
+Arc move with same finish and start coordinates to do complete circle
+Add T parameter to M207
+- look at supporting SIZE in FTP
+- Make mp.delta.hmz0sK, hmz0scK and dsk 64-bit in SAM4E versions, to increase movement limit - also increase K2?
+- hangprinter kinematics, see http://forums.reprap.org/read.php?1,792937,797500,page=1#msg-797500.
diff --git a/src/Configuration.h b/src/Configuration.h
index d75c50d7..8706ad66 100644
--- a/src/Configuration.h
+++ b/src/Configuration.h
@@ -50,7 +50,6 @@ constexpr uint32_t LogFlushInterval = 15000; // Milliseconds
constexpr uint32_t DriverCoolingTimeout = 4000; // Milliseconds
constexpr float DefaultMessageTimeout = 10.0; // How long a message is displayed by default, in seconds
-
// FanCheckInterval must be lower than MinimumWarningInterval to avoid giving driver over temperature warnings too soon when thermostatic control of electronics cooling fans is used
static_assert(FanCheckInterval < MinimumWarningInterval, "FanCheckInterval too large");
@@ -136,26 +135,28 @@ constexpr unsigned int DefaultPinWritePwmFreq = 500; // default PWM frequency fo
constexpr size_t MaxGridProbePoints = 441; // 441 allows us to probe e.g. 400x400 at 20mm intervals
constexpr size_t MaxXGridPoints = 41; // Maximum number of grid points in one X row
constexpr size_t MaxProbePoints = 32; // Maximum number of G30 probe points
-constexpr size_t MaxDeltaCalibrationPoints = 32; // Should a power of 2 for speed
+constexpr size_t MaxCalibrationPoints = 32; // Should a power of 2 for speed
#elif SAM3XA
constexpr size_t MaxGridProbePoints = 121; // 121 allows us to probe 200x200 at 20mm intervals
constexpr size_t MaxXGridPoints = 21; // Maximum number of grid points in one X row
constexpr size_t MaxProbePoints = 32; // Maximum number of G30 probe points
-constexpr size_t MaxDeltaCalibrationPoints = 32; // Should a power of 2 for speed
+constexpr size_t MaxCalibrationPoints = 32; // Should a power of 2 for speed
#else
# error
#endif
-const float DefaultGridSpacing = 20.0; // Default bed probing grid spacing in mm
+const float DefaultGridSpacing = 20.0; // Default bed probing grid spacing in mm
static_assert(MaxProbePoints <= MaxGridProbePoints, "MaxProbePoints must be <= MaxGridProbePoints");
-static_assert(MaxDeltaCalibrationPoints <= MaxProbePoints, "MaxDeltaCalibrationPoints must be <= MaxProbePoints");
+static_assert(MaxCalibrationPoints <= MaxProbePoints, "MaxDeltaCalibrationPoints must be <= MaxProbePoints");
+// Z probing
constexpr float DEFAULT_Z_DIVE = 5.0; // Millimetres
constexpr float DEFAULT_PROBE_SPEED = 2.0; // Default Z probing speed mm/sec
constexpr float DEFAULT_TRAVEL_SPEED = 100.0; // Default speed for travel to probe points
constexpr float ZProbeMaxAcceleration = 250.0; // Maximum Z acceleration to use at the start of a probing move
constexpr size_t MaxZProbeProgramBytes = 8; // Maximum number of bytes in a Z probe program
+constexpr uint32_t ProbingSpeedReductionFactor = 3; // The factor by which we reduce the Z probing speed when we get a 'near' indication
constexpr float TRIANGLE_ZERO = -0.001; // Millimetres
constexpr float SILLY_Z_VALUE = -9999.0; // Millimetres
diff --git a/src/Duet/Pins_Duet.h b/src/Duet/Pins_Duet.h
index e160645d..293cbf28 100644
--- a/src/Duet/Pins_Duet.h
+++ b/src/Duet/Pins_Duet.h
@@ -11,7 +11,7 @@
#define HAS_VOLTAGE_MONITOR 0
#define ACTIVE_LOW_HEAT_ON 1
-const size_t NumFirmwareUpdateModules = 1;
+constexpr size_t NumFirmwareUpdateModules = 1;
#define IAP_UPDATE_FILE "iap.bin"
#define IAP_FIRMWARE_FILE "RepRapFirmware.bin"
@@ -25,21 +25,21 @@ const size_t NumFirmwareUpdateModules = 1;
// The physical capabilities of the machine
-const size_t DRIVES = 9; // The number of drives in the machine, including X, Y, and Z plus extruder drives
+constexpr size_t DRIVES = 9; // The number of drives in the machine, including X, Y, and Z plus extruder drives
#define DRIVES_(a,b,c,d,e,f,g,h,i,j,k,l) { a,b,c,d,e,f,g,h,i }
-const size_t Heaters = 7; // The number of heaters in the machine; 0 is the heated bed even if there isn't one
+constexpr size_t Heaters = 7; // The number of heaters in the machine; 0 is the heated bed even if there isn't one
#define HEATERS_(a,b,c,d,e,f,g,h) { a,b,c,d,e,f,g }
-const size_t MinAxes = 3; // The minimum and default number of axes
-const size_t MaxAxes = 6; // The maximum number of movement axes in the machine, usually just X, Y and Z, <= DRIVES
+constexpr size_t MinAxes = 3; // The minimum and default number of axes
+constexpr size_t MaxAxes = 6; // The maximum number of movement axes in the machine, usually just X, Y and Z, <= DRIVES
// Initialization macro used in statements needing to initialize values in arrays of size MAX_AXES
#define AXES_(a,b,c,d,e,f,g,h,i) { a,b,c,d,e,f }
-const size_t MaxExtruders = DRIVES - MinAxes; // The maximum number of extruders
-const size_t MaxDriversPerAxis = 4; // The maximum number of stepper drivers assigned to one axis
+constexpr size_t MaxExtruders = DRIVES - MinAxes; // The maximum number of extruders
+constexpr size_t MaxDriversPerAxis = 4; // The maximum number of stepper drivers assigned to one axis
-const size_t NUM_SERIAL_CHANNELS = 3; // The number of serial IO channels (USB and two auxiliary UARTs)
+constexpr size_t NUM_SERIAL_CHANNELS = 3; // The number of serial IO channels (USB and two auxiliary UARTs)
#define SERIAL_MAIN_DEVICE SerialUSB
#define SERIAL_AUX_DEVICE Serial
#define SERIAL_AUX2_DEVICE Serial1
@@ -48,104 +48,105 @@ const size_t NUM_SERIAL_CHANNELS = 3; // The number of serial IO channels (USB
// Drives
-const Pin ENABLE_PINS[DRIVES] = { 29, 27, X1, X0, 37, X8, 50, 47, X13 };
-const Pin STEP_PINS[DRIVES] = { 14, 25, 5, X2, 41, 39, X4, 49, X10 };
-const Pin DIRECTION_PINS[DRIVES] = { 15, 26, 4, X3, 35, 53, 51, 48, X11 };
+constexpr Pin ENABLE_PINS[DRIVES] = { 29, 27, X1, X0, 37, X8, 50, 47, X13 };
+constexpr Pin STEP_PINS[DRIVES] = { 14, 25, 5, X2, 41, 39, X4, 49, X10 };
+constexpr Pin DIRECTION_PINS[DRIVES] = { 15, 26, 4, X3, 35, 53, 51, 48, X11 };
// Endstops
// RepRapFirmware only has a single endstop per axis.
// Gcode defines if it is a max ("high end") or min ("low end") endstop and sets if it is active HIGH or LOW.
-const Pin END_STOP_PINS[DRIVES] = { 11, 28, 60, 31, 24, 46, 45, 44, X9 };
+constexpr Pin END_STOP_PINS[DRIVES] = { 11, 28, 60, 31, 24, 46, 45, 44, X9 };
// Indices for motor current digipots (if any): first 4 are for digipot 1 (on duet), second 4 for digipot 2 (on expansion board)
-const uint8_t POT_WIPES[8] = { 1, 3, 2, 0, 1, 3, 2, 0 };
-const float SENSE_RESISTOR = 0.1; // Stepper motor current sense resistor
-const float MAX_STEPPER_DIGIPOT_VOLTAGE = (3.3 * 2.5 / (2.7 + 2.5)); // Stepper motor current reference voltage
-const float STEPPER_DAC_VOLTAGE_RANGE = 2.02; // Stepper motor current reference voltage for E1 if using a DAC
-const float STEPPER_DAC_VOLTAGE_OFFSET = -0.025; // Stepper motor current offset voltage for E1 if using a DAC
+constexpr uint8_t POT_WIPES[8] = { 1, 3, 2, 0, 1, 3, 2, 0 };
+constexpr float SENSE_RESISTOR = 0.1; // Stepper motor current sense resistor
+constexpr float MAX_STEPPER_DIGIPOT_VOLTAGE = (3.3 * 2.5 / (2.7 + 2.5)); // Stepper motor current reference voltage
+constexpr float STEPPER_DAC_VOLTAGE_RANGE = 2.02; // Stepper motor current reference voltage for E1 if using a DAC
+constexpr float STEPPER_DAC_VOLTAGE_OFFSET = -0.025; // Stepper motor current offset voltage for E1 if using a DAC
// HEATERS
-const Pin TEMP_SENSE_PINS[Heaters] = { 5, 4, 0, 7, 8, 9, 11 }; // Analogue pin numbers
-const Pin HEAT_ON_PINS[Heaters] = { 6, X5, X7, 7, 8, 9, X17 }; // Heater Channel 7 (pin X17) is shared with Fan1
+constexpr Pin TEMP_SENSE_PINS[Heaters] = { 5, 4, 0, 7, 8, 9, 11 }; // Analogue pin numbers
+constexpr Pin HEAT_ON_PINS[Heaters] = { 6, X5, X7, 7, 8, 9, X17 }; // Heater Channel 7 (pin X17) is shared with Fan1
// Default thermistor parameters
// Bed thermistor: http://uk.farnell.com/epcos/b57863s103f040/sensor-miniature-ntc-10k/dp/1299930?Ntt=129-9930
// Hot end thermistor: http://www.digikey.co.uk/product-search/en?x=20&y=11&KeyWords=480-3137-ND
-const float BED_R25 = 10000.0;
-const float BED_BETA = 3988.0;
-const float BED_SHC = 0.0;
-const float EXT_R25 = 100000.0;
-const float EXT_BETA = 4388.0;
-const float EXT_SHC = 0.0;
+constexpr float BED_R25 = 10000.0;
+constexpr float BED_BETA = 3988.0;
+constexpr float BED_SHC = 0.0;
+constexpr float EXT_R25 = 100000.0;
+constexpr float EXT_BETA = 4388.0;
+constexpr float EXT_SHC = 0.0;
// Thermistor series resistor value in Ohms
// On later Duet 0.6 and all Duet 0.8.5 boards it is 4700 ohms. However, if we change the default then machines that have 1K series resistors
// and don't have R1000 in the M305 commands in config.g will overheat. So for safety we leave the default as 1000.
-const float THERMISTOR_SERIES_RS = 1000.0;
+constexpr float THERMISTOR_SERIES_RS = 1000.0;
// Number of SPI temperature sensors to support
#if SUPPORT_ROLAND
// chrishamm's pin assignments
-const size_t MaxSpiTempSensors = 2;
+constexpr size_t MaxSpiTempSensors = 2;
// Digital pins the 31855s have their select lines tied to
-const Pin SpiTempSensorCsPins[MaxSpiTempSensors] = { 77, 87 };
+constexpr Pin SpiTempSensorCsPins[MaxSpiTempSensors] = { 77, 87 };
#else
-const size_t MaxSpiTempSensors = 4;
+constexpr size_t MaxSpiTempSensors = 4;
// Digital pins the 31855s have their select lines tied to
-const Pin SpiTempSensorCsPins[MaxSpiTempSensors] = { 77, 87, 16, 17 };
+constexpr Pin SpiTempSensorCsPins[MaxSpiTempSensors] = { 77, 87, 16, 17 };
#endif
// Arduino Due pin number that controls the ATX power on/off
-const Pin ATX_POWER_PIN = 12; // Arduino Due pin number that controls the ATX power on/off
+constexpr Pin ATX_POWER_PIN = 12; // Arduino Due pin number that controls the ATX power on/off
// Analogue pin numbers
-const Pin Z_PROBE_PIN = 10; // Analogue pin number
+constexpr Pin Z_PROBE_PIN = 10; // Analogue pin number
// Digital pin number to turn the IR LED on (high) or off (low)
-const Pin Z_PROBE_MOD_PIN = 52; // Digital pin number to turn the IR LED on (high) or off (low) on Duet v0.6 and v1.0 (PB21)
-const Pin Z_PROBE_MOD_PIN07 = X12; // Digital pin number to turn the IR LED on (high) or off (low) on Duet v0.7 and v0.8.5 (PC10)
+constexpr Pin Z_PROBE_MOD_PIN = 52; // Digital pin number to turn the IR LED on (high) or off (low) on Duet v0.6 and v1.0 (PB21)
+constexpr Pin Z_PROBE_MOD_PIN07 = X12; // Digital pin number to turn the IR LED on (high) or off (low) on Duet v0.7 and v0.8.5 (PC10)
// Pin number that the DAC that controls the second extruder motor current on the Duet 0.8.5 is connected to
-const int Dac0DigitalPin = 66; // Arduino Due pin number corresponding to DAC0 output pin
+constexpr int Dac0DigitalPin = 66; // Arduino Due pin number corresponding to DAC0 output pin
// COOLING FANS
-const size_t NUM_FANS = 2;
-const Pin COOLING_FAN_PINS[NUM_FANS] = { X6, X17 }; // Pin D34 is PWM capable but not an Arduino PWM pin - use X6 instead
-const Pin COOLING_FAN_RPM_PIN = 23; // Pin PA15
+constexpr size_t NUM_FANS = 2;
+constexpr Pin COOLING_FAN_PINS[NUM_FANS] = { X6, X17 }; // Pin D34 is PWM capable but not an Arduino PWM pin - use X6 instead
+constexpr Pin COOLING_FAN_RPM_PIN = 23; // Pin PA15
// SD cards
-const size_t NumSdCards = 2;
-const Pin SdCardDetectPins[NumSdCards] = {NoPin, NoPin}; // Although the Duet PCB supports a CD pin, due to a bug in the SAM3X it is unusable if we enable the temperature sensor
-const Pin SdWriteProtectPins[NumSdCards] = {NoPin, NoPin};
-const Pin SdSpiCSPins[1] = {67}; // Pin PB16 Note: this clashes with inkjet support
+constexpr size_t NumSdCards = 2;
+constexpr Pin SdCardDetectPins[NumSdCards] = {NoPin, NoPin}; // Although the Duet PCB supports a CD pin, due to a bug in the SAM3X it is unusable if we enable the temperature sensor
+constexpr Pin SdWriteProtectPins[NumSdCards] = {NoPin, NoPin};
+constexpr Pin SdSpiCSPins[1] = {67}; // Pin PB16 Note: this clashes with inkjet support
+constexpr uint32_t ExpectedSdCardSpeed = 21000000;
#if SUPPORT_INKJET
// Inkjet control pins
-const Pin INKJET_SERIAL_OUT = 21; // Serial bitpattern into the shift register
-const Pin INKJET_SHIFT_CLOCK = 20; // Shift the register
-const Pin INKJET_STORAGE_CLOCK = 67; // Put the pattern in the output register
-const Pin INKJET_OUTPUT_ENABLE = 66; // Make the output visible
-const Pin INKJET_CLEAR = 65; // Clear the register to 0
+constexpr Pin INKJET_SERIAL_OUT = 21; // Serial bitpattern into the shift register
+constexpr Pin INKJET_SHIFT_CLOCK = 20; // Shift the register
+constexpr Pin INKJET_STORAGE_CLOCK = 67; // Put the pattern in the output register
+constexpr Pin INKJET_OUTPUT_ENABLE = 66; // Make the output visible
+constexpr Pin INKJET_CLEAR = 65; // Clear the register to 0
#endif
#if SUPPORT_ROLAND
// Roland mill
-const Pin ROLAND_CTS_PIN = 16; // Expansion pin 11, PA12_TXD1
-const Pin ROLAND_RTS_PIN = 17; // Expansion pin 12, PA13_RXD1
+constexpr Pin ROLAND_CTS_PIN = 16; // Expansion pin 11, PA12_TXD1
+constexpr Pin ROLAND_RTS_PIN = 17; // Expansion pin 12, PA13_RXD1
#endif
// M42 and M208 commands now use logical pin numbers, not firmware pin numbers.
// This is the mapping from logical pins 60+ to firmware pin numbers
-const Pin SpecialPinMap[] =
+constexpr Pin SpecialPinMap[] =
{
19, 18, 17, 16, 23, // PA10/RXD0 PA11/TXD0 PA12/RXD1 PA13/TXD1 PA14/RTS1
20, 21, 67, 52, // PB12/TWD1 PB13/TWCK1 PB16/DAC1 PB21/AD14
@@ -153,11 +154,11 @@ const Pin SpecialPinMap[] =
};
// This next definition defines the highest one.
-const int HighestLogicalPin = 60 + ARRAY_SIZE(SpecialPinMap) - 1; // highest logical pin number on this electronics
+constexpr int HighestLogicalPin = 60 + ARRAY_SIZE(SpecialPinMap) - 1; // highest logical pin number on this electronics
// SAM3X Flash locations (may be expanded in the future)
-const uint32_t IAP_FLASH_START = 0x000F0000;
-const uint32_t IAP_FLASH_END = 0x000FFBFF; // don't touch the last 1KB, it's used for NvData
+constexpr uint32_t IAP_FLASH_START = 0x000F0000;
+constexpr uint32_t IAP_FLASH_END = 0x000FFBFF; // don't touch the last 1KB, it's used for NvData
// Timer allocation
#define NETWORK_TC (TC1)
diff --git a/src/DuetNG/Pins_DuetNG.h b/src/DuetNG/Pins_DuetNG.h
index 37aa5af6..e2d551c7 100644
--- a/src/DuetNG/Pins_DuetNG.h
+++ b/src/DuetNG/Pins_DuetNG.h
@@ -5,7 +5,7 @@
# define FIRMWARE_NAME "RepRapFirmware for Duet WiFi"
# define DEFAULT_BOARD_TYPE BoardType::DuetWiFi_10
-const size_t NumFirmwareUpdateModules = 4; // 3 modules, plus one for manual upload to WiFi module
+constexpr size_t NumFirmwareUpdateModules = 4; // 3 modules, plus one for manual upload to WiFi module
# define IAP_FIRMWARE_FILE "DuetWiFiFirmware.bin"
# define WIFI_FIRMWARE_FILE "DuetWiFiServer.bin"
# define WIFI_WEB_FILE "DuetWebControl.bin"
@@ -15,7 +15,7 @@ const size_t NumFirmwareUpdateModules = 4; // 3 modules, plus one for manual up
# define FIRMWARE_NAME "RepRapFirmware for Duet Ethernet"
# define DEFAULT_BOARD_TYPE BoardType::DuetEthernet_10
# define IAP_FIRMWARE_FILE "DuetEthernetFirmware.bin"
-const size_t NumFirmwareUpdateModules = 1; // 1 module
+constexpr size_t NumFirmwareUpdateModules = 1; // 1 module
#else
# error Firmware name not defined
@@ -29,20 +29,20 @@ const size_t NumFirmwareUpdateModules = 1; // 1 module
#define HAS_VOLTAGE_MONITOR 1
#define ACTIVE_LOW_HEAT_ON 1
-#define IAP_UPDATE_FILE "iap4e.bin" // using the same IAP file for both Duet WiFi and Duet Ethernet
+#define IAP_UPDATE_FILE "iap4e.bin" // using the same IAP file for both Duet WiFi and Duet Ethernet
-#define SUPPORT_INKJET 0 // set nonzero to support inkjet control
-#define SUPPORT_ROLAND 0 // set nonzero to support Roland mill
-#define SUPPORT_SCANNER 1 // set zero to disable support for FreeLSS scanners
-#define SUPPORT_IOBITS 1 // set to support P parameter in G0/G1 commands
-#define SUPPORT_DHT_SENSOR 1 // set nonzero to support DHT temperature/humidity sensors
+#define SUPPORT_INKJET 0 // set nonzero to support inkjet control
+#define SUPPORT_ROLAND 0 // set nonzero to support Roland mill
+#define SUPPORT_SCANNER 1 // set zero to disable support for FreeLSS scanners
+#define SUPPORT_IOBITS 1 // set to support P parameter in G0/G1 commands
+#define SUPPORT_DHT_SENSOR 1 // set nonzero to support DHT temperature/humidity sensors
-#define USE_CACHE 1 // set nonzero to enable the cache
+#define USE_CACHE 1 // set nonzero to enable the cache
// The physical capabilities of the machine
-const size_t DRIVES = 12; // The maximum number of drives supported by the electronics
-const size_t MaxSmartDrivers = 10; // The maximum number of smart drivers
+constexpr size_t DRIVES = 12; // The maximum number of drives supported by the electronics
+constexpr size_t MaxSmartDrivers = 10; // The maximum number of smart drivers
#define DRIVES_(a,b,c,d,e,f,g,h,i,j,k,l) { a,b,c,d,e,f,g,h,i,j,k,l }
constexpr size_t Heaters = 8; // The number of heaters in the machine; 0 is the heated bed even if there isn't one
@@ -141,6 +141,7 @@ constexpr size_t NumSdCards = 2;
constexpr Pin SdCardDetectPins[NumSdCards] = {53, NoPin};
constexpr Pin SdWriteProtectPins[NumSdCards] = {NoPin, NoPin};
constexpr Pin SdSpiCSPins[1] = {56};
+constexpr uint32_t ExpectedSdCardSpeed = 20000000;
#if SUPPORT_INKJET
// Inkjet control pins
@@ -164,7 +165,7 @@ constexpr Pin ROLAND_RTS_PIN = xx; // Expansion pin 12, PA13_RXD1
// This is the mapping from logical pins 60+ to firmware pin numbers
constexpr Pin SpecialPinMap[] =
{
- 24, 97, 98, 99 // We allow CS5-CS8 to be used because few users need >4 thermocouples or RTDs
+ 24, 97, 98, 99 // We allow CS5-CS8 to be used because few users need >4 thermocouples or RTDs
};
constexpr Pin DueX5GpioPinMap[] = { 211, 210, 209, 208 }; // Pins 100-103 map to GPIO 1-4 on DueX5
// We also allow pins 120-135 to be used if there is an additional SX1509B expander
diff --git a/src/GCodes/GCodes.cpp b/src/GCodes/GCodes.cpp
index eaef5ef9..24dd64e9 100644
--- a/src/GCodes/GCodes.cpp
+++ b/src/GCodes/GCodes.cpp
@@ -1433,8 +1433,9 @@ void GCodes::CheckFilament()
&& LockMovement(*autoPauseGCode) // need to lock movement before executing the pause macro
)
{
- scratchString.printf("Extruder %u reports %s", lastFilamentErrorExtruder, FilamentSensor::GetErrorMessage(lastFilamentError));
- DoPause(*autoPauseGCode, PauseReason::filament, scratchString.Pointer());
+ String<100> filamentErrorString;
+ filamentErrorString.GetRef().printf("Extruder %u reports %s", lastFilamentErrorExtruder, FilamentSensor::GetErrorMessage(lastFilamentError));
+ DoPause(*autoPauseGCode, PauseReason::filament, filamentErrorString.Pointer());
lastFilamentError = FilamentSensorStatus::ok;
}
}
@@ -1740,9 +1741,10 @@ bool GCodes::PauseOnStall(DriversBitmap stalledDrivers)
return false;
}
- scratchString.printf("Stall detected on driver(s)");
- ListDrivers(scratchString, stalledDrivers);
- DoPause(*autoPauseGCode, PauseReason::stall, scratchString.Pointer());
+ String<100> stallErrorString;
+ stallErrorString.GetRef().printf("Stall detected on driver(s)");
+ ListDrivers(stallErrorString.GetRef(), stalledDrivers);
+ DoPause(*autoPauseGCode, PauseReason::stall, stallErrorString.Pointer());
return true;
}
diff --git a/src/GCodes/GCodes2.cpp b/src/GCodes/GCodes2.cpp
index 3c588f3a..b1fd2323 100644
--- a/src/GCodes/GCodes2.cpp
+++ b/src/GCodes/GCodes2.cpp
@@ -1344,7 +1344,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply)
}
else
{
- platform.DiagnosticTest(val);
+ result = GetGCodeResultFromError(platform.DiagnosticTest(gb, reply, val));
}
}
break;
@@ -1563,7 +1563,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply)
case 201: // Set/print axis accelerations
{
bool seen = false;
- for (size_t axis = 0; axis < numVisibleAxes; axis++)
+ for (size_t axis = 0; axis < numTotalAxes; axis++)
{
if (gb.Seen(axisLetters[axis]))
{
@@ -1587,7 +1587,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply)
if (!seen)
{
reply.printf("Accelerations: ");
- for (size_t axis = 0; axis < numVisibleAxes; ++axis)
+ for (size_t axis = 0; axis < numTotalAxes; ++axis)
{
reply.catf("%c: %.1f, ", axisLetters[axis], (double)(platform.Acceleration(axis) / distanceScale));
}
@@ -1605,7 +1605,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply)
case 203: // Set/print maximum feedrates
{
bool seen = false;
- for (size_t axis = 0; axis < numVisibleAxes; ++axis)
+ for (size_t axis = 0; axis < numTotalAxes; ++axis)
{
if (gb.Seen(axisLetters[axis]))
{
@@ -1629,7 +1629,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply)
if (!seen)
{
reply.copy("Maximum feedrates: ");
- for (size_t axis = 0; axis < numVisibleAxes; ++axis)
+ for (size_t axis = 0; axis < numTotalAxes; ++axis)
{
reply.catf("%c: %.1f, ", axisLetters[axis], (double)(platform.MaxFeedrate(axis) / (distanceScale * SecondsToMinutes)));
}
@@ -1716,7 +1716,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply)
{
bool setMin = (gb.Seen('S') ? (gb.GetIValue() == 1) : false);
bool seen = false;
- for (size_t axis = 0; axis < numVisibleAxes; axis++)
+ for (size_t axis = 0; axis < numTotalAxes; axis++)
{
if (gb.Seen(axisLetters[axis]))
{
@@ -1737,7 +1737,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply)
{
reply.copy("Axis limits ");
char sep = '-';
- for (size_t axis = 0; axis < numVisibleAxes; axis++)
+ for (size_t axis = 0; axis < numTotalAxes; axis++)
{
reply.catf("%c %c: %.1f min, %.1f max", sep, axisLetters[axis], (double)platform.AxisMinimum(axis), (double)platform.AxisMaximum(axis));
sep = ',';
@@ -2726,7 +2726,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply)
case 566: // Set/print maximum jerk speeds
{
bool seen = false;
- for (size_t axis = 0; axis < numVisibleAxes; axis++)
+ for (size_t axis = 0; axis < numTotalAxes; axis++)
{
if (gb.Seen(axisLetters[axis]))
{
@@ -2749,7 +2749,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply)
else if (!seen)
{
reply.copy("Maximum jerk rates: ");
- for (size_t axis = 0; axis < numVisibleAxes; ++axis)
+ for (size_t axis = 0; axis < numTotalAxes; ++axis)
{
reply.catf("%c: %.1f, ", axisLetters[axis], (double)(platform.ConfiguredInstantDv(axis) / (distanceScale * SecondsToMinutes)));
}
@@ -3277,7 +3277,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply)
break;
case 584: // Set axis/extruder to stepper driver(s) mapping
- if (!LockMovementAndWaitForStandstill(gb)) // we also rely on this to retrieve the current motor positions to moveBuffer
+ if (!LockMovementAndWaitForStandstill(gb)) // we also rely on this to retrieve the current motor positions to moveBuffer
{
return false;
}
@@ -3334,8 +3334,8 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply)
moveBuffer.coords[numTotalAxes] = 0.0; // user has defined a new axis, so set its position
currentUserPosition[numTotalAxes] = 0.0; // set its requested user position too in case it is visible
++numTotalAxes;
+ numVisibleAxes = numTotalAxes; // assume any new axes are visible unless there is a P parameter
}
- numVisibleAxes = numTotalAxes; // assume all axes are visible unless there is a P parameter
reprap.GetMove().SetNewPosition(moveBuffer.coords, true); // tell the Move system where any new axes are
platform.SetAxisDriversConfig(drive, config);
if (numTotalAxes + numExtruders > DRIVES)
@@ -4188,7 +4188,6 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply)
float eVals[MaxExtruders];
size_t eCount = numExtruders;
gb.GetFloatArray(eVals, eCount, true);
- // 2014-09-29 DC42: we no longer insist that the user supplies values for all possible extruder drives
for (size_t e = 0; e < eCount; e++)
{
platform.SetMotorCurrent(numTotalAxes + e, eVals[e], code);
diff --git a/src/MessageType.h b/src/MessageType.h
index 7938ab3b..3807f956 100644
--- a/src/MessageType.h
+++ b/src/MessageType.h
@@ -38,4 +38,9 @@ enum MessageType : uint16_t
NetworkInfoMessage = UsbMessage | LcdMessage | LogMessage // A message that conveys information about the state of the network interface
};
+inline MessageType AddError(MessageType mt)
+{
+ return (MessageType)(mt | ErrorMessageFlag);
+}
+
#endif /* MESSAGETYPE_H_ */
diff --git a/src/Movement/DDA.cpp b/src/Movement/DDA.cpp
index ce13d974..35ee63aa 100644
--- a/src/Movement/DDA.cpp
+++ b/src/Movement/DDA.cpp
@@ -188,10 +188,11 @@ void DDA::DebugPrint() const
debugPrintf(" d=%f", (double)totalDistance);
DebugPrintVector(" vec", directionVector, 5);
- debugPrintf("\na=%f reqv=%f topv=%f startv=%f endv=%f\n"
- "daccel=%f ddecel=%f cks=%" PRIu32 "\n",
- (double)acceleration, (double)requestedSpeed, (double)topSpeed, (double)startSpeed, (double)endSpeed,
- (double)accelDistance, (double)decelDistance, clocksNeeded);
+ debugPrintf("\n"
+ "a=%f reqv=%f topv=%f startv=%f endv=%f daccel=%f ddecel=%f\n"
+ "cks=%" PRIu32 " sstcda=%" PRIu32 " tstcdapdsc=%" PRIu32 " exac=%" PRIi32 "\n",
+ (double)acceleration, (double)requestedSpeed, (double)topSpeed, (double)startSpeed, (double)endSpeed, (double)accelDistance, (double)decelDistance,
+ clocksNeeded, startSpeedTimesCdivA, topSpeedTimesCdivAPlusDecelStartClocks, extraAccelerationClocks);
for (size_t axis = 0; axis < numAxes; ++axis)
{
if (pddm[axis] != nullptr)
@@ -977,7 +978,7 @@ void DDA::Prepare(uint8_t simMode)
// This code assumes that the previous move in the DDA ring is the previously-executed move, because it fetches the X and Y end coordinates from that move.
// Therefore the Move code must not store a new move in that entry until this one has been prepared! (It took me ages to track this down.)
// Ideally we would store the initial X and Y coordinates in the DDA, but we need to be economical with memory in the Duet 06/085 build.
- cKc = lrintf(directionVector[Z_AXIS] * DriveMovement::Kc);
+ cKc = roundS32(directionVector[Z_AXIS] * DriveMovement::Kc);
params.a2plusb2 = fsquare(directionVector[X_AXIS]) + fsquare(directionVector[Y_AXIS]);
params.initialX = prev->GetEndCoordinate(X_AXIS, false);
params.initialY = prev->GetEndCoordinate(Y_AXIS, false);
@@ -990,12 +991,11 @@ void DDA::Prepare(uint8_t simMode)
const float accelStopTime = (topSpeed - startSpeed)/acceleration;
const float decelStartTime = accelStopTime + (params.decelStartDistance - accelDistance)/topSpeed;
- params.startSpeedTimesCdivA = (uint32_t)lrintf((startSpeed * stepClockRate)/acceleration);
- params.topSpeedTimesCdivA = (uint32_t)lrintf((topSpeed * stepClockRate)/acceleration);
- params.decelStartClocks = (uint32_t)lrintf(decelStartTime * stepClockRate);
- params.topSpeedTimesCdivAPlusDecelStartClocks = params.topSpeedTimesCdivA + params.decelStartClocks;
- params.accelClocksMinusAccelDistanceTimesCdivTopSpeed = (uint32_t)lrintf((accelStopTime - (accelDistance/topSpeed)) * stepClockRate);
- params.compFactor = 1.0 - startSpeed/topSpeed;
+ startSpeedTimesCdivA = (uint32_t)roundU32((startSpeed * stepClockRate)/acceleration);
+ params.topSpeedTimesCdivA = (uint32_t)roundU32((topSpeed * stepClockRate)/acceleration);
+ topSpeedTimesCdivAPlusDecelStartClocks = params.topSpeedTimesCdivA + (uint32_t)roundU32(decelStartTime * stepClockRate);
+ extraAccelerationClocks = roundS32((accelStopTime - (accelDistance/topSpeed)) * stepClockRate);
+ params.compFactor = (topSpeed - startSpeed)/topSpeed;
firstDM = nullptr;
@@ -1572,26 +1572,28 @@ void DDA::ReduceHomingSpeed()
if (!goingSlow)
{
goingSlow = true;
- const float factor = 3.0; // the factor by which we are reducing the speed
- topSpeed /= factor;
+
+ topSpeed *= (1.0/ProbingSpeedReductionFactor);
+
+ // Adjust extraAccelerationClocks so that step timing will be correct in the steady speed phase at the new speed
+ const uint32_t clocksSoFar = Platform::GetInterruptClocks() - moveStartTime;
+ extraAccelerationClocks = (extraAccelerationClocks * (int32_t)ProbingSpeedReductionFactor) - ((int32_t)clocksSoFar * (int32_t)(ProbingSpeedReductionFactor - 1));
+
+ // We also need to adjust the total clocks needed, to prevent step errors being recorded
+ if (clocksSoFar < clocksNeeded)
+ {
+ clocksNeeded += (clocksNeeded - clocksSoFar) * (ProbingSpeedReductionFactor - 1u);
+ }
+
+ // Adjust the speed in the DMs
for (size_t drive = 0; drive < DRIVES; ++drive)
{
DriveMovement* const pdm = pddm[drive];
if (pdm != nullptr && pdm->state == DMState::moving)
{
- pdm->ReduceSpeed(*this, factor);
- RemoveDM(pdm->drive);
- InsertDM(pdm);
+ pdm->ReduceSpeed(*this, ProbingSpeedReductionFactor);
}
}
-
- // We also need to adjust the total clocks needed, to prevent step errors being recorded
- const uint32_t clocksSoFar = Platform::GetInterruptClocks() - moveStartTime;
- if (clocksSoFar < clocksNeeded)
- {
- const uint32_t clocksLeft = clocksNeeded - clocksSoFar;
- clocksNeeded += (uint32_t)(clocksLeft * (factor - 1.0));
- }
}
}
diff --git a/src/Movement/DDA.h b/src/Movement/DDA.h
index ed974d15..97ba7860 100644
--- a/src/Movement/DDA.h
+++ b/src/Movement/DDA.h
@@ -196,6 +196,9 @@ private:
// These are calculated from the above and used in the ISR, so they are set up by Prepare()
uint32_t clocksNeeded; // in clocks
uint32_t moveStartTime; // clock count at which the move was started
+ uint32_t startSpeedTimesCdivA; // the number of clocks it would have taken t reach the start speed form rest
+ uint32_t topSpeedTimesCdivAPlusDecelStartClocks;
+ int32_t extraAccelerationClocks; // the additional number of clocks needed because we started the move at less than topSpeed. Negative after ReduceHomingSpeed has been called.
float proportionLeft; // what proportion of the extrusion in the G1 or G0 move of which this is a part remains to be done after this segment is complete
diff --git a/src/Movement/DriveMovement.cpp b/src/Movement/DriveMovement.cpp
index 7b89c8c0..b05659e7 100644
--- a/src/Movement/DriveMovement.cpp
+++ b/src/Movement/DriveMovement.cpp
@@ -31,7 +31,7 @@ void DriveMovement::InitialAllocate(unsigned int num)
DriveMovement *DriveMovement::Allocate(size_t drive, DMState st)
{
- DriveMovement *dm = freeList;
+ DriveMovement * const dm = freeList;
if (dm != nullptr)
{
freeList = dm->nextDM;
@@ -58,30 +58,27 @@ DriveMovement::DriveMovement(DriveMovement *next) : nextDM(next)
void DriveMovement::PrepareCartesianAxis(const DDA& dda, const PrepParams& params)
{
const float stepsPerMm = (float)totalSteps/dda.totalDistance;
- mp.cart.twoCsquaredTimesMmPerStepDivA = (uint64_t)(((float)DDA::stepClockRate * (float)DDA::stepClockRate)/(stepsPerMm * dda.acceleration)) * 2;
+ mp.cart.twoCsquaredTimesMmPerStepDivA = roundU64((double)(DDA::stepClockRateSquared * 2)/((double)stepsPerMm * (double)dda.acceleration));
// Acceleration phase parameters
mp.cart.accelStopStep = (uint32_t)(dda.accelDistance * stepsPerMm) + 1;
- startSpeedTimesCdivA = params.startSpeedTimesCdivA;
+ mp.cart.compensationClocks = mp.cart.accelCompensationClocks = 0;
// Constant speed phase parameters
- mp.cart.mmPerStepTimesCdivtopSpeed = lrintf(((float)DDA::stepClockRate * K1)/(stepsPerMm * dda.topSpeed));
- accelClocksMinusAccelDistanceTimesCdivTopSpeed = params.accelClocksMinusAccelDistanceTimesCdivTopSpeed;
+ mp.cart.mmPerStepTimesCKdivtopSpeed = roundU32(((float)((uint64_t)DDA::stepClockRate * K1))/(stepsPerMm * dda.topSpeed));
// Deceleration phase parameters
// First check whether there is any deceleration at all, otherwise we may get strange results because of rounding errors
if (dda.decelDistance * stepsPerMm < 0.5)
{
mp.cart.decelStartStep = totalSteps + 1;
- topSpeedTimesCdivAPlusDecelStartClocks = 0;
twoDistanceToStopTimesCsquaredDivA = 0;
}
else
{
mp.cart.decelStartStep = (uint32_t)(params.decelStartDistance * stepsPerMm) + 1;
- topSpeedTimesCdivAPlusDecelStartClocks = params.topSpeedTimesCdivAPlusDecelStartClocks;
const uint64_t initialDecelSpeedTimesCdivASquared = isquare64(params.topSpeedTimesCdivA);
- twoDistanceToStopTimesCsquaredDivA = initialDecelSpeedTimesCdivASquared + (uint64_t)((params.decelStartDistance * (DDA::stepClockRateSquared * 2))/dda.acceleration);
+ twoDistanceToStopTimesCsquaredDivA = initialDecelSpeedTimesCdivASquared + roundU64((params.decelStartDistance * (DDA::stepClockRateSquared * 2))/dda.acceleration);
}
// No reverse phase
@@ -98,9 +95,10 @@ void DriveMovement::PrepareDeltaAxis(const DDA& dda, const PrepParams& params)
const float aAplusbB = A * dda.directionVector[X_AXIS] + B * dda.directionVector[Y_AXIS];
const float dSquaredMinusAsquaredMinusBsquared = params.diagonalSquared - fsquare(A) - fsquare(B);
const float h0MinusZ0 = sqrtf(dSquaredMinusAsquaredMinusBsquared);
- mp.delta.hmz0sK = lrintf(h0MinusZ0 * stepsPerMm * DriveMovement::K2);
- mp.delta.minusAaPlusBbTimesKs = -lrintf(aAplusbB * stepsPerMm * DriveMovement::K2);
- mp.delta.dSquaredMinusAsquaredMinusBsquaredTimesKsquaredSsquared = llrintf(dSquaredMinusAsquaredMinusBsquared * fsquare(stepsPerMm * DriveMovement::K2));
+ mp.delta.hmz0sK = roundS32(h0MinusZ0 * stepsPerMm * DriveMovement::K2);
+ mp.delta.minusAaPlusBbTimesKs = -roundS32(aAplusbB * stepsPerMm * DriveMovement::K2);
+ mp.delta.dSquaredMinusAsquaredMinusBsquaredTimesKsquaredSsquared = roundS64(dSquaredMinusAsquaredMinusBsquared * fsquare(stepsPerMm * DriveMovement::K2));
+ mp.delta.twoCsquaredTimesMmPerStepDivA = roundU64((double)(2 * DDA::stepClockRateSquared)/((double)stepsPerMm * (double)dda.acceleration));
// Calculate the distance at which we need to reverse direction.
if (params.a2plusb2 <= 0.0)
@@ -150,29 +148,23 @@ void DriveMovement::PrepareDeltaAxis(const DDA& dda, const PrepParams& params)
}
}
- mp.delta.twoCsquaredTimesMmPerStepDivA = llrintf((double)(2 * DDA::stepClockRateSquared)/((double)stepsPerMm * (double)dda.acceleration));
-
// Acceleration phase parameters
- mp.delta.accelStopDsK = lrintf(dda.accelDistance * stepsPerMm * K2);
- startSpeedTimesCdivA = params.startSpeedTimesCdivA;
+ mp.delta.accelStopDsK = roundU32(dda.accelDistance * stepsPerMm * K2);
// Constant speed phase parameters
- mp.delta.mmPerStepTimesCdivtopSpeedK = lrintf(((float)DDA::stepClockRate * K1)/(stepsPerMm * dda.topSpeed));
- accelClocksMinusAccelDistanceTimesCdivTopSpeed = params.accelClocksMinusAccelDistanceTimesCdivTopSpeed;
+ mp.delta.mmPerStepTimesCKdivtopSpeed = roundU32(((float)DDA::stepClockRate * K1)/(stepsPerMm * dda.topSpeed));
// Deceleration phase parameters
// First check whether there is any deceleration at all, otherwise we may get strange results because of rounding errors
if (dda.decelDistance * stepsPerMm < 0.5)
{
mp.delta.decelStartDsK = 0xFFFFFFFF;
- topSpeedTimesCdivAPlusDecelStartClocks = 0;
twoDistanceToStopTimesCsquaredDivA = 0;
}
else
{
- mp.delta.decelStartDsK = lrintf(params.decelStartDistance * stepsPerMm * K2);
- topSpeedTimesCdivAPlusDecelStartClocks = params.topSpeedTimesCdivAPlusDecelStartClocks;
- twoDistanceToStopTimesCsquaredDivA = isquare64(params.topSpeedTimesCdivA) + llrintf((params.decelStartDistance * (DDA::stepClockRateSquared * 2))/dda.acceleration);
+ mp.delta.decelStartDsK = roundU32(params.decelStartDistance * stepsPerMm * K2);
+ twoDistanceToStopTimesCsquaredDivA = isquare64(params.topSpeedTimesCdivA) + roundU64((params.decelStartDistance * (DDA::stepClockRateSquared * 2))/dda.acceleration);
}
}
@@ -181,14 +173,14 @@ void DriveMovement::PrepareExtruder(const DDA& dda, const PrepParams& params, bo
{
const float dv = dda.directionVector[drive];
const float stepsPerMm = reprap.GetPlatform().DriveStepsPerUnit(drive) * fabsf(dv);
- mp.cart.twoCsquaredTimesMmPerStepDivA = llrintf(((float)DDA::stepClockRate * (float)DDA::stepClockRate)/(stepsPerMm * dda.acceleration)) * 2;
+ mp.cart.twoCsquaredTimesMmPerStepDivA = roundU64((double)(DDA::stepClockRateSquared * 2)/((double)stepsPerMm * (double)dda.acceleration));
// Calculate the pressure advance parameter
const float compensationTime = (doCompensation && dv > 0.0) ? reprap.GetPlatform().GetPressureAdvance(drive - reprap.GetGCodes().GetTotalAxes()) : 0.0;
- const uint32_t compensationClocks = lrintf(compensationTime * DDA::stepClockRate);
+ mp.cart.compensationClocks = roundU32(compensationTime * (float)DDA::stepClockRate);
+ mp.cart.accelCompensationClocks = roundU32(compensationTime * (float)DDA::stepClockRate * params.compFactor);
// Calculate the net total step count to allow for compensation. It may be negative.
- // Note that we add totalSteps in floating point mode, to round the number of steps down consistently
const float compensationDistance = (dda.endSpeed - dda.startSpeed) * compensationTime;
const int32_t netSteps = (int32_t)(compensationDistance * stepsPerMm) + (int32_t)totalSteps;
@@ -197,11 +189,9 @@ void DriveMovement::PrepareExtruder(const DDA& dda, const PrepParams& params, bo
// Acceleration phase parameters
mp.cart.accelStopStep = (uint32_t)((dda.accelDistance + accelCompensationDistance) * stepsPerMm) + 1;
- startSpeedTimesCdivA = params.startSpeedTimesCdivA + compensationClocks;
// Constant speed phase parameters
- mp.cart.mmPerStepTimesCdivtopSpeed = (uint32_t)(((float)DDA::stepClockRate * K1)/(stepsPerMm * dda.topSpeed));
- accelClocksMinusAccelDistanceTimesCdivTopSpeed = (int32_t)params.accelClocksMinusAccelDistanceTimesCdivTopSpeed - (int32_t)(compensationClocks * params.compFactor);
+ mp.cart.mmPerStepTimesCKdivtopSpeed = (uint32_t)((float)((uint64_t)DDA::stepClockRate * K1)/(stepsPerMm * dda.topSpeed));
// Calculate the deceleration and reverse phase parameters
// First check whether there is any deceleration at all, otherwise we may get strange results because of rounding errors
@@ -209,18 +199,16 @@ void DriveMovement::PrepareExtruder(const DDA& dda, const PrepParams& params, bo
{
totalSteps = (uint32_t)max<int32_t>(netSteps, 0);
mp.cart.decelStartStep = reverseStartStep = netSteps + 1;
- topSpeedTimesCdivAPlusDecelStartClocks = 0;
mp.cart.fourMaxStepDistanceMinusTwoDistanceToStopTimesCsquaredDivA = 0;
twoDistanceToStopTimesCsquaredDivA = 0;
}
else
{
mp.cart.decelStartStep = (uint32_t)((params.decelStartDistance + accelCompensationDistance) * stepsPerMm) + 1;
- const int32_t initialDecelSpeedTimesCdivA = (int32_t)params.topSpeedTimesCdivA - (int32_t)compensationClocks; // signed because it may be negative and we square it
+ const int32_t initialDecelSpeedTimesCdivA = (int32_t)params.topSpeedTimesCdivA - (int32_t)mp.cart.compensationClocks; // signed because it may be negative and we square it
const uint64_t initialDecelSpeedTimesCdivASquared = isquare64(initialDecelSpeedTimesCdivA);
- topSpeedTimesCdivAPlusDecelStartClocks = params.topSpeedTimesCdivAPlusDecelStartClocks - compensationClocks;
twoDistanceToStopTimesCsquaredDivA =
- initialDecelSpeedTimesCdivASquared + llrintf(((params.decelStartDistance + accelCompensationDistance) * (DDA::stepClockRateSquared * 2))/dda.acceleration);
+ initialDecelSpeedTimesCdivASquared + roundU64(((params.decelStartDistance + accelCompensationDistance) * (float)(DDA::stepClockRateSquared * 2))/dda.acceleration);
// Calculate the move distance to the point of zero speed, where reverse motion starts
const float initialDecelSpeed = dda.topSpeed - dda.acceleration * compensationTime;
@@ -245,7 +233,7 @@ void DriveMovement::PrepareExtruder(const DDA& dda, const PrepParams& params, bo
const int32_t overallSteps = (int32_t)(2 * (reverseStartStep - 1)) - netSteps;
if (overallSteps > 0)
{
- totalSteps = overallSteps;
+ totalSteps = (uint32_t)overallSteps;
mp.cart.fourMaxStepDistanceMinusTwoDistanceToStopTimesCsquaredDivA =
(int64_t)((2 * (reverseStartStep - 1)) * mp.cart.twoCsquaredTimesMmPerStepDivA) - (int64_t)twoDistanceToStopTimesCsquaredDivA;
}
@@ -263,25 +251,25 @@ void DriveMovement::DebugPrint(char c, bool isDeltaMovement) const
{
if (state != DMState::idle)
{
- debugPrintf("DM%c%s dir=%c steps=%" PRIu32 " next=%" PRIu32 " rev=%" PRIu32 " interval=%" PRIu32 " sstcda=%" PRIu32 " "
- "acmadtcdts=%" PRIi32 " tstcdapdsc=%" PRIu32 " 2dtstc2diva=%" PRIu64 "\n",
- c, (state == DMState::stepError) ? " ERR:" : ":", (direction) ? 'F' : 'B', totalSteps, nextStep, reverseStartStep, stepInterval, startSpeedTimesCdivA,
- accelClocksMinusAccelDistanceTimesCdivTopSpeed, topSpeedTimesCdivAPlusDecelStartClocks, twoDistanceToStopTimesCsquaredDivA);
+ debugPrintf("DM%c%s dir=%c steps=%" PRIu32 " next=%" PRIu32 " rev=%" PRIu32 " interval=%" PRIu32
+ " 2dtstc2diva=%" PRIu64 "\n",
+ c, (state == DMState::stepError) ? " ERR:" : ":", (direction) ? 'F' : 'B', totalSteps, nextStep, reverseStartStep, stepInterval,
+ twoDistanceToStopTimesCsquaredDivA);
if (isDeltaMovement)
{
debugPrintf("hmz0sK=%" PRIi32 " minusAaPlusBbTimesKs=%" PRIi32 " dSquaredMinusAsquaredMinusBsquared=%" PRId64 "\n"
"2c2mmsda=%" PRIu64 " asdsk=%" PRIu32 " dsdsk=%" PRIu32 " mmstcdts=%" PRIu32 "\n",
mp.delta.hmz0sK, mp.delta.minusAaPlusBbTimesKs, mp.delta.dSquaredMinusAsquaredMinusBsquaredTimesKsquaredSsquared,
- mp.delta.twoCsquaredTimesMmPerStepDivA, mp.delta.accelStopDsK, mp.delta.decelStartDsK, mp.delta.mmPerStepTimesCdivtopSpeedK
+ mp.delta.twoCsquaredTimesMmPerStepDivA, mp.delta.accelStopDsK, mp.delta.decelStartDsK, mp.delta.mmPerStepTimesCKdivtopSpeed
);
}
else
{
debugPrintf("accelStopStep=%" PRIu32 " decelStartStep=%" PRIu32 " 2CsqtMmPerStepDivA=%" PRIu64 "\n"
- "mmPerStepTimesCdivtopSpeed=%" PRIu32 " fmsdmtstdca2=%" PRId64 "\n",
+ "mmPerStepTimesCdivtopSpeed=%" PRIu32 " fmsdmtstdca2=%" PRId64 " cc=%" PRIu32 " acc=%" PRIu32 "\n",
mp.cart.accelStopStep, mp.cart.decelStartStep, mp.cart.twoCsquaredTimesMmPerStepDivA,
- mp.cart.mmPerStepTimesCdivtopSpeed, mp.cart.fourMaxStepDistanceMinusTwoDistanceToStopTimesCsquaredDivA
+ mp.cart.mmPerStepTimesCKdivtopSpeed, mp.cart.fourMaxStepDistanceMinusTwoDistanceToStopTimesCsquaredDivA, mp.cart.compensationClocks, mp.cart.accelCompensationClocks
);
}
}
@@ -327,21 +315,26 @@ pre(nextStep < totalSteps; stepsTillRecalc == 0)
if (nextCalcStep < mp.cart.accelStopStep)
{
// acceleration phase
- nextStepTime = isqrt64(isquare64(startSpeedTimesCdivA) + (mp.cart.twoCsquaredTimesMmPerStepDivA * nextCalcStep)) - startSpeedTimesCdivA;
+ const uint32_t adjustedStartSpeedTimesCdivA = dda.startSpeedTimesCdivA + mp.cart.compensationClocks;
+ nextStepTime = isqrt64(isquare64(adjustedStartSpeedTimesCdivA) + (mp.cart.twoCsquaredTimesMmPerStepDivA * nextCalcStep)) - adjustedStartSpeedTimesCdivA;
}
else if (nextCalcStep < mp.cart.decelStartStep)
{
// steady speed phase
- nextStepTime = (uint32_t)((int32_t)(((uint64_t)mp.cart.mmPerStepTimesCdivtopSpeed * nextCalcStep)/K1) + accelClocksMinusAccelDistanceTimesCdivTopSpeed);
+ nextStepTime = (uint32_t)( (int32_t)(((uint64_t)mp.cart.mmPerStepTimesCKdivtopSpeed * nextCalcStep)/K1)
+ + dda.extraAccelerationClocks
+ - (int32_t)mp.cart.accelCompensationClocks
+ );
}
else if (nextCalcStep < reverseStartStep)
{
// deceleration phase, not reversed yet
const uint64_t temp = mp.cart.twoCsquaredTimesMmPerStepDivA * nextCalcStep;
+ const uint32_t adjustedTopSpeedTimesCdivAPlusDecelStartClocks = dda.topSpeedTimesCdivAPlusDecelStartClocks - mp.cart.compensationClocks;
// Allow for possible rounding error when the end speed is zero or very small
- nextStepTime = (twoDistanceToStopTimesCsquaredDivA > temp)
- ? topSpeedTimesCdivAPlusDecelStartClocks - isqrt64(twoDistanceToStopTimesCsquaredDivA - temp)
- : topSpeedTimesCdivAPlusDecelStartClocks;
+ nextStepTime = (temp < twoDistanceToStopTimesCsquaredDivA)
+ ? adjustedTopSpeedTimesCdivAPlusDecelStartClocks - isqrt64(twoDistanceToStopTimesCsquaredDivA - temp)
+ : adjustedTopSpeedTimesCdivAPlusDecelStartClocks;
}
else
{
@@ -354,7 +347,8 @@ pre(nextStep < totalSteps; stepsTillRecalc == 0)
reprap.GetPlatform().SetDirection(drive, direction);
}
}
- nextStepTime = topSpeedTimesCdivAPlusDecelStartClocks
+ const uint32_t adjustedTopSpeedTimesCdivAPlusDecelStartClocks = dda.topSpeedTimesCdivAPlusDecelStartClocks - mp.cart.compensationClocks;
+ nextStepTime = adjustedTopSpeedTimesCdivAPlusDecelStartClocks
+ isqrt64((int64_t)(mp.cart.twoCsquaredTimesMmPerStepDivA * nextCalcStep) - mp.cart.fourMaxStepDistanceMinusTwoDistanceToStopTimesCsquaredDivA);
}
@@ -454,20 +448,22 @@ pre(nextStep < totalSteps; stepsTillRecalc == 0)
if ((uint32_t)dsK < mp.delta.accelStopDsK)
{
// Acceleration phase
- nextStepTime = isqrt64(isquare64(startSpeedTimesCdivA) + (mp.delta.twoCsquaredTimesMmPerStepDivA * (uint32_t)dsK)/K2) - startSpeedTimesCdivA;
+ nextStepTime = isqrt64(isquare64(dda.startSpeedTimesCdivA) + (mp.delta.twoCsquaredTimesMmPerStepDivA * (uint32_t)dsK)/K2) - dda.startSpeedTimesCdivA;
}
else if ((uint32_t)dsK < mp.delta.decelStartDsK)
{
// Steady speed phase
- nextStepTime = (uint32_t)((int32_t)(((uint64_t)mp.delta.mmPerStepTimesCdivtopSpeedK * (uint32_t)dsK)/(K1 * K2)) + accelClocksMinusAccelDistanceTimesCdivTopSpeed);
+ nextStepTime = (uint32_t)( (int32_t)(((uint64_t)mp.delta.mmPerStepTimesCKdivtopSpeed * (uint32_t)dsK)/(K1 * K2))
+ + dda.extraAccelerationClocks
+ );
}
else
{
const uint64_t temp = (mp.delta.twoCsquaredTimesMmPerStepDivA * (uint32_t)dsK)/K2;
// Because of possible rounding error when the end speed is zero or very small, we need to check that the square root will work OK
nextStepTime = (temp < twoDistanceToStopTimesCsquaredDivA)
- ? topSpeedTimesCdivAPlusDecelStartClocks - isqrt64(twoDistanceToStopTimesCsquaredDivA - temp)
- : topSpeedTimesCdivAPlusDecelStartClocks;
+ ? dda.topSpeedTimesCdivAPlusDecelStartClocks - isqrt64(twoDistanceToStopTimesCsquaredDivA - temp)
+ : dda.topSpeedTimesCdivAPlusDecelStartClocks;
}
stepInterval = (nextStepTime - lastStepTime) >> shiftFactor; // calculate the time per step, ready for next time
@@ -494,7 +490,7 @@ pre(nextStep < totalSteps; stepsTillRecalc == 0)
}
// Reduce the speed of this movement. Called to reduce the homing speed when we detect we are near the endstop for a drive.
-void DriveMovement::ReduceSpeed(const DDA& dda, float inverseSpeedFactor)
+void DriveMovement::ReduceSpeed(const DDA& dda, uint32_t inverseSpeedFactor)
{
if (dda.isDeltaMovement)
{
@@ -503,26 +499,16 @@ void DriveMovement::ReduceSpeed(const DDA& dda, float inverseSpeedFactor)
mp.delta.decelStartDsK = 0xFFFFFFFF;
// Adjust the speed
- mp.delta.mmPerStepTimesCdivtopSpeedK = (uint32_t)(inverseSpeedFactor * mp.delta.mmPerStepTimesCdivtopSpeedK);
-
- // Adjust the acceleration clocks to as to maintain continuity of movement
- const int32_t hmz0scK = (int32_t)(((int64_t)mp.delta.hmz0sK * dda.cKc)/Kc);
- const int32_t t1 = mp.delta.minusAaPlusBbTimesKs + hmz0scK;
- const int32_t t2 = isqrt64(isquare64(t1) + mp.delta.dSquaredMinusAsquaredMinusBsquaredTimesKsquaredSsquared - isquare64(mp.delta.hmz0sK));
- const int32_t dsK = (direction) ? t1 - t2 : t1 + t2;
- accelClocksMinusAccelDistanceTimesCdivTopSpeed = (int32_t)nextStepTime - (int32_t)(((uint64_t)mp.delta.mmPerStepTimesCdivtopSpeedK * (uint32_t)dsK)/(K1 * K2));
+ mp.delta.mmPerStepTimesCKdivtopSpeed *= inverseSpeedFactor;
}
else
{
// Force the linear motion phase
- mp.cart.decelStartStep = totalSteps + 1;
mp.cart.accelStopStep = 0;
+ mp.cart.decelStartStep = totalSteps + 1;
// Adjust the speed
- mp.cart.mmPerStepTimesCdivtopSpeed = (uint32_t)(inverseSpeedFactor * mp.cart.mmPerStepTimesCdivtopSpeed);
-
- // Adjust the acceleration clocks to as to maintain continuity of movement
- accelClocksMinusAccelDistanceTimesCdivTopSpeed = (int32_t)nextStepTime - (int32_t)(((uint64_t)mp.cart.mmPerStepTimesCdivtopSpeed * nextStep)/K1);
+ mp.cart.mmPerStepTimesCKdivtopSpeed *= inverseSpeedFactor;
}
}
diff --git a/src/Movement/DriveMovement.h b/src/Movement/DriveMovement.h
index 8a1a2999..9a1c535a 100644
--- a/src/Movement/DriveMovement.h
+++ b/src/Movement/DriveMovement.h
@@ -12,16 +12,87 @@
class LinearDeltaKinematics;
+#define ROUND_TO_NEAREST (0) // 1 for round to nearest (as used in 1.20beta10), 0 for round down (as used prior to 1.20beta10)
+
+// Rounding functions, to improve code clarity. Also allows a quick switch between round-to-nearest and round down in the movement code.
+inline uint32_t roundU32(float f)
+{
+#if ROUND_TO_NEAREST
+ return (uint32_t)lrintf(f);
+#else
+ return (uint32_t)f;
+#endif
+}
+
+inline uint32_t roundU32(double d)
+{
+#if ROUND_TO_NEAREST
+ return lrint(d);
+#else
+ return (uint32_t)d;
+#endif
+}
+
+inline int32_t roundS32(float f)
+{
+#if ROUND_TO_NEAREST
+ return lrintf(f);
+#else
+ return (int32_t)f;
+#endif
+}
+
+inline int32_t roundS32(double d)
+{
+#if ROUND_TO_NEAREST
+ return lrint(d);
+#else
+ return (int32_t)d;
+#endif
+}
+
+inline uint64_t roundU64(float f)
+{
+#if ROUND_TO_NEAREST
+ return (uint64_t)llrintf(f);
+#else
+ return (uint64_t)f;
+#endif
+}
+
+inline uint64_t roundU64(double d)
+{
+#if ROUND_TO_NEAREST
+ return (uint64_t)llrint(d);
+#else
+ return (uint64_t)d;
+#endif
+}
+
+inline int64_t roundS64(float f)
+{
+#if ROUND_TO_NEAREST
+ return llrintf(f);
+#else
+ return (int64_t)f;
+#endif
+}
+
+inline int64_t roundS64(double d)
+{
+#if ROUND_TO_NEAREST
+ return llrint(d);
+#else
+ return (int64_t)d;
+#endif
+}
+
// Struct for passing parameters to the DriveMovement Prepare methods
struct PrepParams
{
// Parameters used for all types of motion
float decelStartDistance;
- uint32_t startSpeedTimesCdivA;
uint32_t topSpeedTimesCdivA;
- uint32_t decelStartClocks;
- uint32_t topSpeedTimesCdivAPlusDecelStartClocks;
- uint32_t accelClocksMinusAccelDistanceTimesCdivTopSpeed;
// Parameters used only for extruders
float compFactor;
@@ -55,7 +126,7 @@ public:
void PrepareCartesianAxis(const DDA& dda, const PrepParams& params) __attribute__ ((hot));
void PrepareDeltaAxis(const DDA& dda, const PrepParams& params) __attribute__ ((hot));
void PrepareExtruder(const DDA& dda, const PrepParams& params, bool doCompensation) __attribute__ ((hot));
- void ReduceSpeed(const DDA& dda, float inverseSpeedFactor);
+ void ReduceSpeed(const DDA& dda, uint32_t inverseSpeedFactor);
void DebugPrint(char c, bool withDelta) const;
int32_t GetNetStepsLeft() const;
int32_t GetNetStepsTaken() const;
@@ -100,9 +171,6 @@ private:
// The following only need to be stored per-drive if we are supporting pressure advance
uint64_t twoDistanceToStopTimesCsquaredDivA;
- uint32_t startSpeedTimesCdivA;
- int32_t accelClocksMinusAccelDistanceTimesCdivTopSpeed; // this one can be negative
- uint32_t topSpeedTimesCdivAPlusDecelStartClocks;
// Parameters unique to a style of move (Cartesian, delta or extruder). Currently, extruders and Cartesian moves use the same parameters.
union MoveParams
@@ -113,26 +181,26 @@ private:
uint64_t twoCsquaredTimesMmPerStepDivA; // 2 * clock^2 * mmPerStepInHyperCuboidSpace / acceleration
// The following depend on how the move is executed, so they must be set up in Prepare()
+ int64_t fourMaxStepDistanceMinusTwoDistanceToStopTimesCsquaredDivA; // this one can be negative
uint32_t accelStopStep; // the first step number at which we are no longer accelerating
uint32_t decelStartStep; // the first step number at which we are decelerating
- uint32_t mmPerStepTimesCdivtopSpeed; // mmPerStepInHyperCuboidSpace * clock / topSpeed
-
- // The following only need to be stored per-drive if we are supporting pressure advance
- int64_t fourMaxStepDistanceMinusTwoDistanceToStopTimesCsquaredDivA; // this one can be negative
+ uint32_t mmPerStepTimesCKdivtopSpeed; // mmPerStepInHyperCuboidSpace * clock / topSpeed
+ uint32_t compensationClocks; // the pressure advance time in clocks
+ uint32_t accelCompensationClocks; // compensationClocks * (1 - startSpeed/topSpeed)
} cart;
struct DeltaParameters // Parameters for delta movement
{
// The following don't depend on how the move is executed, so they can be set up in Init
+ uint64_t twoCsquaredTimesMmPerStepDivA; // this could be stored in the DDA if all towers use the same steps/mm
int64_t dSquaredMinusAsquaredMinusBsquaredTimesKsquaredSsquared;
int32_t hmz0sK; // the starting step position less the starting Z height, multiplied by the Z movement fraction and K (can go negative)
int32_t minusAaPlusBbTimesKs;
- uint64_t twoCsquaredTimesMmPerStepDivA; // this could be stored in the DDA if all towers use the same steps/mm
// The following depend on how the move is executed, so they must be set up in Prepare()
uint32_t accelStopDsK;
uint32_t decelStartDsK;
- uint32_t mmPerStepTimesCdivtopSpeedK;
+ uint32_t mmPerStepTimesCKdivtopSpeed;
} delta;
} mp;
diff --git a/src/Movement/Kinematics/HangprinterKinematics.cpp b/src/Movement/Kinematics/HangprinterKinematics.cpp
new file mode 100644
index 00000000..ba1736b3
--- /dev/null
+++ b/src/Movement/Kinematics/HangprinterKinematics.cpp
@@ -0,0 +1,614 @@
+/*
+ * HangprinterKinematics.cpp
+ *
+ * Created on: 24 Nov 2017
+ * Author: David
+ */
+
+#include "HangprinterKinematics.h"
+#include "RepRap.h"
+#include "Platform.h"
+#include "GCodes/GCodeBuffer.h"
+#include "Movement/Move.h"
+//#include "Movement/BedProbing/RandomProbePointSet.h"
+
+// Default anchor coordinates, copied from https://github.com/tobbelobb/hangprinter/blob/fabf19bf4653d1d1daf72d53217ba5962c9aca6e/firmware/HangprinterMarlin/Configuration.h
+constexpr float DefaultAnchorA[3] = { 0.0, -2163.0, -75.5};
+constexpr float DefaultAnchorB[3] = {-1841.0, 741.0, -75.5};
+constexpr float DefaultAnchorC[3] = { 1639.0, 1404.0, -75.5};
+constexpr float DefaultAnchorDz = 3250.5;
+constexpr float DefaultPrintRadius = 1500.0;
+
+constexpr size_t HANGPRINTER_AXES = 4;
+constexpr size_t A_AXIS = 0;
+constexpr size_t B_AXIS = 1;
+constexpr size_t C_AXIS = 2;
+constexpr size_t D_AXIS = 3;
+
+// Constructor
+HangprinterKinematics::HangprinterKinematics()
+ : Kinematics(KinematicsType::scara, DefaultSegmentsPerSecond, DefaultMinSegmentSize, true)
+{
+ Init();
+}
+
+void HangprinterKinematics::Init()
+{
+ anchorDz = DefaultAnchorDz;
+ printRadius = DefaultPrintRadius;
+ ARRAY_INIT(anchorA, DefaultAnchorA);
+ ARRAY_INIT(anchorB, DefaultAnchorB);
+ ARRAY_INIT(anchorC, DefaultAnchorC);
+ doneAutoCalibration = false;
+ Recalc();
+}
+
+// Recalculate the derived parameters
+void HangprinterKinematics::Recalc()
+{
+ printRadiusSquared = fsquare(printRadius);
+ Da2 = fsquare(anchorA[0]) + fsquare(anchorA[1]) + fsquare(anchorA[2]);
+ Db2 = fsquare(anchorB[0]) + fsquare(anchorB[1]) + fsquare(anchorB[2]);
+ Dc2 = fsquare(anchorC[0]) + fsquare(anchorC[1]) + fsquare(anchorC[2]);
+ Xab = anchorA[0] - anchorB[0];
+ Xbc = anchorB[0] - anchorC[0];
+ Xca = anchorC[0] - anchorA[0];
+ Yab = anchorA[1] - anchorB[1];
+ Ybc = anchorB[1] - anchorC[1];
+ Yca = anchorC[1] - anchorA[1];
+ Zab = anchorB[2] - anchorC[2];
+ Zbc = anchorB[2] - anchorC[2];
+ Zca = anchorC[2] - anchorA[2];
+ P = ( anchorB[0] * Yca
+ - anchorA[0] * anchorC[1]
+ + anchorA[1] * anchorC[0]
+ - anchorB[1] * Xca
+ ) * 2;
+ P2 = fsquare(P);
+ Q = ( anchorB[1] * Zca
+ - anchorA[1] * anchorC[2]
+ + anchorA[2] * anchorC[1]
+ - anchorB[2] * Yca
+ ) * 2;
+ R = - ( anchorB[0] * Zca
+ + anchorA[0] * anchorC[2]
+ + anchorA[2] * anchorC[0]
+ - anchorB[2] * Xca
+ ) * 2;
+ U = (anchorA[2] * P2) + (anchorA[0] * Q * P) + (anchorA[1] * R * P);
+ A = (P2 + fsquare(Q) + fsquare(R)) * 2;
+}
+
+// Return the name of the current kinematics
+const char *HangprinterKinematics::GetName(bool forStatusReport) const
+{
+ return "Hangprinter";
+}
+
+// Set the parameters from a M665, M666 or M669 command
+// Return true if we changed any parameters. Set 'error' true if there was an error, otherwise leave it alone.
+bool HangprinterKinematics::Configure(unsigned int mCode, GCodeBuffer& gb, StringRef& reply, bool& error) /*override*/
+{
+ if (mCode == 669)
+ {
+ bool seen = false;
+ bool seenNonGeometry = false;
+ gb.TryGetFValue('S', segmentsPerSecond, seenNonGeometry);
+ gb.TryGetFValue('T', minSegmentLength, seenNonGeometry);
+ if (gb.TryGetFloatArray('A', 3, anchorA, reply, seen))
+ {
+ error = true;
+ return true;
+ }
+ if (gb.TryGetFloatArray('B', 3, anchorB, reply, seen))
+ {
+ error = true;
+ return true;
+ }
+ if (gb.TryGetFloatArray('C', 3, anchorC, reply, seen))
+ {
+ error = true;
+ return true;
+ }
+ gb.TryGetFValue('D', anchorDz, seen);
+
+ if (seen || seenNonGeometry)
+ {
+ Recalc();
+ }
+ if (gb.Seen('P'))
+ {
+ printRadius = gb.GetFValue();
+ seen = true;
+ }
+ else if (!gb.Seen('K'))
+ {
+ reply.printf("Kinematics is Hangprinter with ABC anchor coordinates (%.2f,%.2f,%.2f) (%.2f,%.2f,%.2f) (%.2f,%.2f,%.2f),"
+ "D anchor Z coordinate %.2f, print radius %.1f, segments/sec %d, min. segment length %.2f",
+ (double)anchorA[X_AXIS], (double)anchorA[Y_AXIS], (double)anchorA[Z_AXIS],
+ (double)anchorB[X_AXIS], (double)anchorB[Y_AXIS], (double)anchorB[Z_AXIS],
+ (double)anchorC[X_AXIS], (double)anchorC[Y_AXIS], (double)anchorC[Z_AXIS],
+ (double)anchorDz, (double)printRadius,
+ (int)segmentsPerSecond, (double)minSegmentLength);
+ }
+ return seen;
+ }
+ else
+ {
+ return Kinematics::Configure(mCode, gb, reply, error);
+ }
+}
+
+// Calculate the square of the line length from a spool from a Cartesian coordinate
+inline float HangprinterKinematics::LineLengthASquared(const float machinePos[3], const float anchor[3]) const
+{
+ return fsquare(anchor[Z_AXIS] - machinePos[Z_AXIS]) + fsquare(anchor[Y_AXIS] - machinePos[Y_AXIS]) + fsquare(anchor[X_AXIS] - machinePos[X_AXIS]);
+}
+
+// Convert Cartesian coordinates to motor coordinates, returning true if successful
+bool HangprinterKinematics::CartesianToMotorSteps(const float machinePos[], const float stepsPerMm[], size_t numVisibleAxes, size_t numTotalAxes, int32_t motorPos[], bool isCoordinated) const
+{
+ // Geometry of hangprinter makes fsquare(anchorABC[Z_AXIS] - machinePos[Z_AXIS]) the smallest term in the sum.
+ // Starting sum with smallest number gives smallest roundoff error.
+ const float aSquared = LineLengthASquared(machinePos, anchorA);
+ const float bSquared = LineLengthASquared(machinePos, anchorB);
+ const float cSquared = LineLengthASquared(machinePos, anchorC);
+ const float dSquared = fsquare(machinePos[X_AXIS])
+ + fsquare(machinePos[Y_AXIS])
+ + fsquare(anchorDz - machinePos[Z_AXIS]);
+ if (aSquared < 0.0 && bSquared < 0.0 && cSquared < 0.0 && dSquared < 0.0)
+ {
+ motorPos[A_AXIS] = lrintf(sqrtf(aSquared) * stepsPerMm[A_AXIS]);
+ motorPos[B_AXIS] = lrintf(sqrtf(bSquared) * stepsPerMm[B_AXIS]);
+ motorPos[C_AXIS] = lrintf(sqrtf(cSquared) * stepsPerMm[C_AXIS]);
+ motorPos[D_AXIS] = lrintf(sqrtf(dSquared) * stepsPerMm[D_AXIS]);
+ return true;
+ }
+ return false;
+}
+
+// Convert motor coordinates to machine coordinates. Used after homing and after individual motor moves.
+void HangprinterKinematics::MotorStepsToCartesian(const int32_t motorPos[], const float stepsPerMm[], size_t numVisibleAxes, size_t numTotalAxes, float machinePos[]) const
+{
+ InverseTransform(motorPos[A_AXIS]/stepsPerMm[A_AXIS], motorPos[B_AXIS]/stepsPerMm[B_AXIS], motorPos[C_AXIS]/stepsPerMm[C_AXIS], machinePos);
+}
+
+// Return true if the specified XY position is reachable by the print head reference point.
+bool HangprinterKinematics::IsReachable(float x, float y, bool isCoordinated) const
+{
+ return fsquare(x) + fsquare(y) < printRadiusSquared;
+}
+
+// Limit the Cartesian position that the user wants to move to returning true if we adjusted the position
+bool HangprinterKinematics::LimitPosition(float coords[], size_t numVisibleAxes, AxesBitmap axesHomed, bool isCoordinated) const
+{
+ const AxesBitmap allAxes = MakeBitmap<AxesBitmap>(X_AXIS) | MakeBitmap<AxesBitmap>(Y_AXIS) | MakeBitmap<AxesBitmap>(Z_AXIS);
+ bool limited = false;
+ if ((axesHomed & allAxes) == allAxes)
+ {
+ // If axes have been homed on a delta printer and this isn't a homing move, check for movements outside limits.
+ // Skip this check if axes have not been homed, so that extruder-only moves are allowed before homing
+ // Constrain the move to be within the build radius
+ const float diagonalSquared = fsquare(coords[X_AXIS]) + fsquare(coords[Y_AXIS]);
+ if (diagonalSquared > printRadiusSquared)
+ {
+ const float factor = sqrtf(printRadiusSquared / diagonalSquared);
+ coords[X_AXIS] *= factor;
+ coords[Y_AXIS] *= factor;
+ limited = true;
+ }
+
+ if (coords[Z_AXIS] < reprap.GetPlatform().AxisMinimum(Z_AXIS))
+ {
+ coords[Z_AXIS] = reprap.GetPlatform().AxisMinimum(Z_AXIS);
+ limited = true;
+ }
+ else if (coords[Z_AXIS] > reprap.GetPlatform().AxisMaximum(Z_AXIS))
+ {
+ coords[Z_AXIS] = reprap.GetPlatform().AxisMaximum(Z_AXIS);
+ limited = true;
+ }
+ }
+ return limited;
+}
+
+// Return the initial Cartesian coordinates we assume after switching to this kinematics
+void HangprinterKinematics::GetAssumedInitialPosition(size_t numAxes, float positions[]) const
+{
+ for (size_t i = 0; i < numAxes; ++i)
+ {
+ positions[i] = 0.0;
+ }
+}
+
+// This function is called when a request is made to home the axes in 'toBeHomed' and the axes in 'alreadyHomed' have already been homed.
+// If we can proceed with homing some axes, return the name of the homing file to be called.
+// If we can't proceed because other axes need to be homed first, return nullptr and pass those axes back in 'mustBeHomedFirst'.
+const char* HangprinterKinematics::GetHomingFileName(AxesBitmap toBeHomed, AxesBitmap alreadyHomed, size_t numVisibleAxes, AxesBitmap& mustHomeFirst) const
+{
+ return "homeall.g";
+}
+
+// This function is called from the step ISR when an endstop switch is triggered during homing.
+// Return true if the entire homing move should be terminated, false if only the motor associated with the endstop switch should be stopped.
+bool HangprinterKinematics::QueryTerminateHomingMove(size_t axis) const
+{
+ return false;
+}
+
+// This function is called from the step ISR when an endstop switch is triggered during homing after stopping just one motor or all motors.
+// Take the action needed to define the current position, normally by calling dda.SetDriveCoordinate() and return false.
+void HangprinterKinematics::OnHomingSwitchTriggered(size_t axis, bool highEnd, const float stepsPerMm[], DDA& dda) const
+{
+ // Hangprinter homing is not supported
+}
+
+// Return the axes that we can assume are homed after executing a G92 command to set the specified axis coordinates
+uint32_t HangprinterKinematics::AxesAssumedHomed(AxesBitmap g92Axes) const
+{
+ // If all of X, Y and Z have been specified then we know the positions of all 4 spool motors, otherwise we don't
+ const uint32_t xyzAxes = (1u << X_AXIS) | (1u << Y_AXIS) | (1u << Z_AXIS);
+ if ((g92Axes & xyzAxes) == xyzAxes)
+ {
+ g92Axes |= (1u << D_AXIS);
+ }
+ else
+ {
+ g92Axes &= ~xyzAxes;
+ }
+ return g92Axes;
+}
+
+// Limit the speed and acceleration of a move to values that the mechanics can handle.
+// The speeds in Cartesian space have already been limited.
+void HangprinterKinematics::LimitSpeedAndAcceleration(DDA& dda, const float *normalisedDirectionVector) const
+{
+ // Limit the speed in the XY plane to the lower of the X and Y maximum speeds, and similarly for the acceleration
+ const float xyFactor = sqrtf(fsquare(normalisedDirectionVector[X_AXIS]) + fsquare(normalisedDirectionVector[Y_AXIS]));
+ if (xyFactor > 0.01)
+ {
+ const Platform& platform = reprap.GetPlatform();
+ const float maxSpeed = min<float>(platform.MaxFeedrate(X_AXIS), platform.MaxFeedrate(Y_AXIS));
+ const float maxAcceleration = min<float>(platform.Acceleration(X_AXIS), platform.Acceleration(Y_AXIS));
+ dda.LimitSpeedAndAcceleration(maxSpeed/xyFactor, maxAcceleration/xyFactor);
+ }
+}
+
+// Write the parameters that are set by auto calibration to a file, returning true if success
+bool HangprinterKinematics::WriteCalibrationParameters(FileStore *f) const
+{
+ bool ok = f->Write("; Hangprinter parameters\n");
+ if (ok)
+ {
+ scratchString.printf("M669 K6 A%.3f:%.3f:%.3f B%.3f:%.3f:%.3f C%.3f:%.3f:%.3f D%.3f P%.1f\n",
+ (double)anchorA[X_AXIS], (double)anchorA[Y_AXIS], (double)anchorA[Z_AXIS],
+ (double)anchorB[X_AXIS], (double)anchorB[Y_AXIS], (double)anchorB[Z_AXIS],
+ (double)anchorC[X_AXIS], (double)anchorC[Y_AXIS], (double)anchorC[Z_AXIS],
+ (double)anchorDz, (double)printRadius);
+ ok = f->Write(scratchString.Pointer());
+ }
+ return ok;
+}
+
+// Write any calibration data that we need to resume a print after power fail, returning true if successful
+bool HangprinterKinematics::WriteResumeSettings(FileStore *f) const
+{
+ return !doneAutoCalibration || WriteCalibrationParameters(f);
+}
+
+// Calculate the Cartesian coordinates from the motor coordinates
+void HangprinterKinematics::InverseTransform(float La, float Lb, float Lc, float machinePos[3]) const
+{
+ // Calculate PQRST such that x = (Qz + S)/P, y = (Rz + T)/P
+ const float S = - Yab * (fsquare(Lc) - Dc2)
+ - Yca * (fsquare(Lb) - Db2)
+ - Ybc * (fsquare(La) - Da2);
+ const float T = - Xab * (fsquare(Lc) - Dc2)
+ + Xca * (fsquare(Lb) - Db2)
+ + Xbc * (fsquare(La) - Da2);
+
+ // Calculate quadratic equation coefficients
+ const float halfB = (S * Q) - (R * T) - U;
+ const float C = fsquare(S) + fsquare(T) + (anchorA[1] * T - anchorA[0] * S) * P * 2 + (Da2 - fsquare(La)) * P2;
+
+ // Solve the quadratic equation for z
+ machinePos[2] = (- halfB - sqrtf(fsquare(halfB) - A * C))/A;
+
+ // Substitute back for X and Y
+ machinePos[0] = (Q * machinePos[2] + S)/P;
+ machinePos[1] = (R * machinePos[2] + T)/P;
+
+ debugPrintf("Motor %.2f,%.2f,%.2f to Cartesian %.2f,%.2f,%.2f\n", (double)La, (double)Lb, (double)Lc, (double)machinePos[0], (double)machinePos[1], (double)machinePos[2]);
+}
+
+// Auto calibrate from a set of probe points returning true if it failed
+// We can't calibrate all the XY parameters because translations and rotations of the anchors don't alter the height. Therefore we calibrate the following:
+// 0, 1, 2 Spool zero length motor positions (this is like endstop calibration on a delta)
+// 3 Y coordinate of the B anchor
+// 4, 5 X and Y coordinates of the C anchor
+// 6, 7, 8 Heights of the A, B, C anchors
+// We don't touch the XY coordinates of the A anchor or the X coordinate of the B anchor.
+bool HangprinterKinematics::DoAutoCalibration(size_t numFactors, const RandomProbePointSet& probePoints, StringRef& reply)
+{
+ const size_t NumHangprinterFactors = 9; // maximum number of machine factors we can adjust
+ const size_t numPoints = probePoints.NumberOfProbePoints();
+
+ if (numFactors != 3 && numFactors != 6 && numFactors != NumHangprinterFactors)
+ {
+ reply.printf("Hangprinter calibration with %d factors requested but only 3, 6, and 9 supported", numFactors);
+ return true;
+ }
+
+ if (reprap.Debug(moduleMove))
+ {
+ PrintParameters(scratchString);
+ debugPrintf("%s\n", scratchString.Pointer());
+ }
+
+ // The following is for printing out the calculation time, see later
+ //uint32_t startTime = reprap.GetPlatform()->GetInterruptClocks();
+
+ // Transform the probing points to motor endpoints and store them in a matrix, so that we can do multiple iterations using the same data
+ FixedMatrix<floatc_t, MaxCalibrationPoints, 3> probeMotorPositions;
+ floatc_t corrections[MaxCalibrationPoints];
+ floatc_t initialSumOfSquares = 0.0;
+ for (size_t i = 0; i < numPoints; ++i)
+ {
+ corrections[i] = 0.0;
+ float machinePos[3];
+ const floatc_t zp = reprap.GetMove().GetProbeCoordinates(i, machinePos[X_AXIS], machinePos[Y_AXIS], probePoints.PointWasCorrected(i));
+ machinePos[Z_AXIS] = 0.0;
+
+ probeMotorPositions(i, A_AXIS) = sqrtf(LineLengthASquared(machinePos, anchorA));
+ probeMotorPositions(i, B_AXIS) = sqrtf(LineLengthASquared(machinePos, anchorB));
+ probeMotorPositions(i, C_AXIS) = sqrtf(LineLengthASquared(machinePos, anchorC));
+ initialSumOfSquares += fcsquare(zp);
+ }
+
+ // Do 1 or more Newton-Raphson iterations
+ unsigned int iteration = 0;
+ float expectedRmsError;
+ for (;;)
+ {
+ // Build a Nx9 matrix of derivatives with respect to xa, xb, yc, za, zb, zc, diagonal.
+ FixedMatrix<floatc_t, MaxCalibrationPoints, NumHangprinterFactors> derivativeMatrix;
+ for (size_t i = 0; i < numPoints; ++i)
+ {
+ for (size_t j = 0; j < numFactors; ++j)
+ {
+ const size_t adjustedJ = (numFactors == 8 && j >= 6) ? j + 1 : j; // skip diagonal rod length if doing 8-factor calibration
+ derivativeMatrix(i, j) =
+ ComputeDerivative(adjustedJ, probeMotorPositions(i, A_AXIS), probeMotorPositions(i, B_AXIS), probeMotorPositions(i, C_AXIS));
+ }
+ }
+
+ if (reprap.Debug(moduleMove))
+ {
+ PrintMatrix("Derivative matrix", derivativeMatrix, numPoints, numFactors);
+ }
+
+ // Now build the normal equations for least squares fitting
+ FixedMatrix<floatc_t, NumHangprinterFactors, NumHangprinterFactors + 1> normalMatrix;
+ for (size_t i = 0; i < numFactors; ++i)
+ {
+ for (size_t j = 0; j < numFactors; ++j)
+ {
+ floatc_t temp = derivativeMatrix(0, i) * derivativeMatrix(0, j);
+ for (size_t k = 1; k < numPoints; ++k)
+ {
+ temp += derivativeMatrix(k, i) * derivativeMatrix(k, j);
+ }
+ normalMatrix(i, j) = temp;
+ }
+ floatc_t temp = derivativeMatrix(0, i) * -((floatc_t)probePoints.GetZHeight(0) + corrections[0]);
+ for (size_t k = 1; k < numPoints; ++k)
+ {
+ temp += derivativeMatrix(k, i) * -((floatc_t)probePoints.GetZHeight(k) + corrections[k]);
+ }
+ normalMatrix(i, numFactors) = temp;
+ }
+
+ if (reprap.Debug(moduleMove))
+ {
+ PrintMatrix("Normal matrix", normalMatrix, numFactors, numFactors + 1);
+ }
+
+ floatc_t solution[NumHangprinterFactors];
+ normalMatrix.GaussJordan(solution, numFactors);
+
+ if (reprap.Debug(moduleMove))
+ {
+ PrintMatrix("Solved matrix", normalMatrix, numFactors, numFactors + 1);
+ PrintVector("Solution", solution, numFactors);
+
+ // Calculate and display the residuals
+ // Save a little stack by not allocating a residuals vector, because stack for it doesn't only get reserved when debug is enabled.
+ debugPrintf("Residuals:");
+ for (size_t i = 0; i < numPoints; ++i)
+ {
+ floatc_t residual = probePoints.GetZHeight(i);
+ for (size_t j = 0; j < numFactors; ++j)
+ {
+ residual += solution[j] * derivativeMatrix(i, j);
+ }
+ debugPrintf(" %7.4f", (double)residual);
+ }
+
+ debugPrintf("\n");
+ }
+
+ Adjust(numFactors, solution); // adjust the delta parameters
+
+ float heightAdjust[3];
+ for (size_t drive = 0; drive < 3; ++drive)
+ {
+ heightAdjust[drive] = (float)solution[drive]; // convert double to float
+ }
+ reprap.GetMove().AdjustMotorPositions(heightAdjust, 3); // adjust the motor positions
+
+ // Calculate the expected probe heights using the new parameters
+ {
+ floatc_t expectedResiduals[MaxCalibrationPoints];
+ floatc_t sumOfSquares = 0.0;
+ for (size_t i = 0; i < numPoints; ++i)
+ {
+ for (size_t axis = 0; axis < 3; ++axis)
+ {
+ probeMotorPositions(i, axis) += solution[axis];
+ }
+ float newPosition[3];
+ InverseTransform(probeMotorPositions(i, A_AXIS), probeMotorPositions(i, B_AXIS), probeMotorPositions(i, C_AXIS), newPosition);
+ corrections[i] = newPosition[Z_AXIS];
+ expectedResiduals[i] = probePoints.GetZHeight(i) + newPosition[Z_AXIS];
+ sumOfSquares += fcsquare(expectedResiduals[i]);
+ }
+
+ expectedRmsError = sqrtf((float)(sumOfSquares/numPoints));
+
+ if (reprap.Debug(moduleMove))
+ {
+ PrintVector("Expected probe error", expectedResiduals, numPoints);
+ }
+ }
+
+ // Decide whether to do another iteration. Two is slightly better than one, but three doesn't improve things.
+ // Alternatively, we could stop when the expected RMS error is only slightly worse than the RMS of the residuals.
+ ++iteration;
+ if (iteration == 2)
+ {
+ break;
+ }
+ }
+
+ // Print out the calculation time
+ //debugPrintf("Time taken %dms\n", (reprap.GetPlatform()->GetInterruptClocks() - startTime) * 1000 / DDA::stepClockRate);
+ if (reprap.Debug(moduleMove))
+ {
+ PrintParameters(scratchString);
+ debugPrintf("%s\n", scratchString.Pointer());
+ }
+
+ reply.printf("Calibrated %d factors using %d points, deviation before %.3f after %.3f",
+ numFactors, numPoints, (double)sqrtf(initialSumOfSquares/numPoints), (double)expectedRmsError);
+ reprap.GetPlatform().MessageF(LogMessage, "%s\n", reply.Pointer());
+
+ doneAutoCalibration = true;
+ return false;
+}
+
+// Compute the derivative of height with respect to a parameter at the specified motor endpoints.
+// 'deriv' indicates the parameter as follows:
+// 0, 1, 2 = A, B, C line length adjustments
+// 3 = B anchor Y coordinate
+// 4, 5 = C anchor X and Y coordinates
+// 6, 7, 8 = A, B and C anchor Z coordinates
+floatc_t HangprinterKinematics::ComputeDerivative(unsigned int deriv, float La, float Lb, float Lc) const
+{
+ const float perturb = 0.2; // perturbation amount in mm
+ HangprinterKinematics hiParams(*this), loParams(*this);
+ switch(deriv)
+ {
+ case 0:
+ case 1:
+ case 2:
+ // Line length corrections
+ break;
+
+ case 3:
+ hiParams.anchorB[1] += perturb;
+ loParams.anchorB[1] -= perturb;
+ hiParams.Recalc();
+ loParams.Recalc();
+ break;
+
+ case 4:
+ hiParams.anchorC[0] += perturb;
+ loParams.anchorC[0] -= perturb;
+ hiParams.Recalc();
+ loParams.Recalc();
+ break;
+
+ case 5:
+ hiParams.anchorC[1] += perturb;
+ loParams.anchorC[1] -= perturb;
+ hiParams.Recalc();
+ loParams.Recalc();
+ break;
+
+ case 6:
+ hiParams.anchorA[2] += perturb;
+ loParams.anchorA[2] -= perturb;
+ hiParams.Recalc();
+ loParams.Recalc();
+ break;
+
+ case 7:
+ hiParams.anchorB[2] += perturb;
+ loParams.anchorB[2] -= perturb;
+ hiParams.Recalc();
+ loParams.Recalc();
+ break;
+
+ case 8:
+ hiParams.anchorB[2] += perturb;
+ loParams.anchorB[2] -= perturb;
+ hiParams.Recalc();
+ loParams.Recalc();
+ break;
+ }
+
+ float newPos[3];
+ hiParams.InverseTransform((deriv == 0) ? La + perturb : La, (deriv == 1) ? Lb + perturb : Lb, (deriv == 2) ? Lc + perturb : Lc, newPos);
+
+ const float zHi = newPos[Z_AXIS];
+ loParams.InverseTransform((deriv == 0) ? La - perturb : La, (deriv == 1) ? Lb - perturb : Lb, (deriv == 2) ? Lc - perturb : Lc, newPos);
+ const float zLo = newPos[Z_AXIS];
+ return ((floatc_t)zHi - (floatc_t)zLo)/(floatc_t)(2 * perturb);
+}
+
+// Perform 3, 6 or 9-factor adjustment.
+// The input vector contains the following parameters in this order:
+// 0, 1, 2 = A, B, C line length adjustments
+// 3 = B anchor Y coordinate
+// 4, 5 = C anchor X and Y coordinates
+// 6, 7, 8 = A, B and C anchor Z coordinates
+void HangprinterKinematics::Adjust(size_t numFactors, const floatc_t v[])
+{
+ if (numFactors >= 4)
+ {
+ anchorB[1] += (float)v[3];
+ }
+ if (numFactors >= 5)
+ {
+ anchorC[0] += (float)v[4];
+ }
+ if (numFactors >= 6)
+ {
+ anchorC[1] += (float)v[5];
+ }
+ if (numFactors >= 7)
+ {
+ anchorA[2] += (float)v[6];
+ }
+ if (numFactors >= 8)
+ {
+ anchorB[2] += (float)v[7];
+ }
+ if (numFactors >= 9)
+ {
+ anchorC[2] += (float)v[8];
+ }
+
+ Recalc();
+}
+
+// Print all the parameters for debugging
+void HangprinterKinematics::PrintParameters(StringRef& reply) const
+{
+ reply.printf("Anchor coordinates (%.2f,%.2f,%.2f) (%.2f,%.2f,%.2f) (%.2f,%.2f,%.2f)\n",
+ (double)anchorA[X_AXIS], (double)anchorA[Y_AXIS], (double)anchorA[Z_AXIS],
+ (double)anchorB[X_AXIS], (double)anchorB[Y_AXIS], (double)anchorB[Z_AXIS],
+ (double)anchorC[X_AXIS], (double)anchorC[Y_AXIS], (double)anchorC[Z_AXIS]);
+}
+
+// End
diff --git a/src/Movement/Kinematics/HangprinterKinematics.h b/src/Movement/Kinematics/HangprinterKinematics.h
new file mode 100644
index 00000000..263abe4d
--- /dev/null
+++ b/src/Movement/Kinematics/HangprinterKinematics.h
@@ -0,0 +1,69 @@
+/*
+ * HangprinterKinematics.h
+ *
+ * Created on: 24 Nov 2017
+ * Author: David
+ */
+
+#ifndef SRC_MOVEMENT_KINEMATICS_HANGPRINTERKINEMATICS_H_
+#define SRC_MOVEMENT_KINEMATICS_HANGPRINTERKINEMATICS_H_
+
+#include "Kinematics.h"
+
+class HangprinterKinematics : public Kinematics
+{
+public:
+ // Constructors
+ HangprinterKinematics();
+
+ // Overridden base class functions. See Kinematics.h for descriptions.
+ const char *GetName(bool forStatusReport) const override;
+ bool Configure(unsigned int mCode, GCodeBuffer& gb, StringRef& reply, bool& error) override;
+ bool CartesianToMotorSteps(const float machinePos[], const float stepsPerMm[], size_t numVisibleAxes, size_t numTotalAxes, int32_t motorPos[], bool isCoordinated) const override;
+ void MotorStepsToCartesian(const int32_t motorPos[], const float stepsPerMm[], size_t numVisibleAxes, size_t numTotalAxes, float machinePos[]) const override;
+ bool SupportsAutoCalibration() const override { return true; }
+ bool DoAutoCalibration(size_t numFactors, const RandomProbePointSet& probePoints, StringRef& reply) override;
+ void SetCalibrationDefaults() override { Init(); }
+ bool WriteCalibrationParameters(FileStore *f) const override;
+ bool IsReachable(float x, float y, bool isCoordinated) const override;
+ bool LimitPosition(float position[], size_t numAxes, AxesBitmap axesHomed, bool isCoordinated) const override;
+ void GetAssumedInitialPosition(size_t numAxes, float positions[]) const override;
+ size_t NumHomingButtons(size_t numVisibleAxes) const override { return 0; }
+ const char* HomingButtonNames() const override { return "ABCD"; }
+ HomingMode GetHomingMode() const override { return homeIndividualMotors; }
+ AxesBitmap AxesAssumedHomed(AxesBitmap g92Axes) const override;
+ const char* GetHomingFileName(AxesBitmap toBeHomed, AxesBitmap alreadyHomed, size_t numVisibleAxes, AxesBitmap& mustHomeFirst) const override;
+ bool QueryTerminateHomingMove(size_t axis) const override;
+ void OnHomingSwitchTriggered(size_t axis, bool highEnd, const float stepsPerMm[], DDA& dda) const override;
+ bool WriteResumeSettings(FileStore *f) const override;
+ void LimitSpeedAndAcceleration(DDA& dda, const float *normalisedDirectionVector) const override;
+
+private:
+ static constexpr float DefaultSegmentsPerSecond = 100.0;
+ static constexpr float DefaultMinSegmentSize = 0.2;
+
+ void Init();
+ void Recalc();
+ float LineLengthASquared(const float machinePos[3], const float anchor[3]) const; // Calculate the square of the line length from a spool from a Cartesian coordinate
+ void InverseTransform(float La, float Lb, float Lc, float machinePos[3]) const;
+
+ floatc_t ComputeDerivative(unsigned int deriv, float La, float Lb, float Lc) const; // Compute the derivative of height with respect to a parameter at a set of motor endpoints
+ void Adjust(size_t numFactors, const floatc_t v[]); // Perform 3-, 6- or 9-factor adjustment
+ void PrintParameters(StringRef& reply) const; // Print all the parameters for debugging
+
+ float anchorA[3], anchorB[3], anchorC[3]; // XYZ coordinates of the anchors
+ float anchorDz;
+ float printRadius;
+
+ // Derived parameters
+ float printRadiusSquared;
+ float Da2, Db2, Dc2;
+ float Xab, Xbc, Xca;
+ float Yab, Ybc, Yca;
+ float Zab, Zbc, Zca;
+ float P, Q, R, P2, U, A;
+
+ bool doneAutoCalibration; // True if we have done auto calibration
+};
+
+#endif /* SRC_MOVEMENT_KINEMATICS_HANGPRINTERKINEMATICS_H_ */
diff --git a/src/Movement/Kinematics/Kinematics.cpp b/src/Movement/Kinematics/Kinematics.cpp
index 7bdd4fa4..a258a377 100644
--- a/src/Movement/Kinematics/Kinematics.cpp
+++ b/src/Movement/Kinematics/Kinematics.cpp
@@ -12,6 +12,7 @@
#include "CoreXZKinematics.h"
#include "ScaraKinematics.h"
#include "CoreXYUKinematics.h"
+#include "HangprinterKinematics.h"
#include "PolarKinematics.h"
#include "CoreXYUVKinematics.h"
#include "RepRap.h"
@@ -145,6 +146,8 @@ const char* Kinematics::GetHomingFileName(AxesBitmap toBeHomed, AxesBitmap alrea
return new ScaraKinematics();
case KinematicsType::coreXYU:
return new CoreXYUKinematics();
+ case KinematicsType::hangprinter:
+ return new HangprinterKinematics();
case KinematicsType::polar:
return new PolarKinematics();
case KinematicsType::coreXYUV:
diff --git a/src/Movement/Kinematics/LinearDeltaKinematics.cpp b/src/Movement/Kinematics/LinearDeltaKinematics.cpp
index ecfc093d..ca04574c 100644
--- a/src/Movement/Kinematics/LinearDeltaKinematics.cpp
+++ b/src/Movement/Kinematics/LinearDeltaKinematics.cpp
@@ -5,7 +5,7 @@
* Author: David
*/
-#include <Movement/Kinematics/LinearDeltaKinematics.h>
+#include "LinearDeltaKinematics.h"
#include "Pins.h"
#include "Configuration.h"
#include "Movement/Move.h"
@@ -44,23 +44,23 @@ void LinearDeltaKinematics::Init()
void LinearDeltaKinematics::Recalc()
{
- towerX[A_AXIS] = -(radius * cosf((30 + angleCorrections[A_AXIS]) * DegreesToRadians));
- towerY[A_AXIS] = -(radius * sinf((30 + angleCorrections[A_AXIS]) * DegreesToRadians));
- towerX[B_AXIS] = +(radius * cosf((30 - angleCorrections[B_AXIS]) * DegreesToRadians));
- towerY[B_AXIS] = -(radius * sinf((30 - angleCorrections[B_AXIS]) * DegreesToRadians));
- towerX[C_AXIS] = -(radius * sinf(angleCorrections[C_AXIS] * DegreesToRadians));
- towerY[C_AXIS] = +(radius * cosf(angleCorrections[C_AXIS] * DegreesToRadians));
-
- Xbc = towerX[C_AXIS] - towerX[B_AXIS];
- Xca = towerX[A_AXIS] - towerX[C_AXIS];
- Xab = towerX[B_AXIS] - towerX[A_AXIS];
- Ybc = towerY[C_AXIS] - towerY[B_AXIS];
- Yca = towerY[A_AXIS] - towerY[C_AXIS];
- Yab = towerY[B_AXIS] - towerY[A_AXIS];
- coreFa = fsquare(towerX[A_AXIS]) + fsquare(towerY[A_AXIS]);
- coreFb = fsquare(towerX[B_AXIS]) + fsquare(towerY[B_AXIS]);
- coreFc = fsquare(towerX[C_AXIS]) + fsquare(towerY[C_AXIS]);
- Q = 2 * (Xca * Yab - Xab * Yca);
+ towerX[DELTA_A_AXIS] = -(radius * cosf((30 + angleCorrections[DELTA_A_AXIS]) * DegreesToRadians));
+ towerY[DELTA_A_AXIS] = -(radius * sinf((30 + angleCorrections[DELTA_A_AXIS]) * DegreesToRadians));
+ towerX[DELTA_B_AXIS] = +(radius * cosf((30 - angleCorrections[DELTA_B_AXIS]) * DegreesToRadians));
+ towerY[DELTA_B_AXIS] = -(radius * sinf((30 - angleCorrections[DELTA_B_AXIS]) * DegreesToRadians));
+ towerX[DELTA_C_AXIS] = -(radius * sinf(angleCorrections[DELTA_C_AXIS] * DegreesToRadians));
+ towerY[DELTA_C_AXIS] = +(radius * cosf(angleCorrections[DELTA_C_AXIS] * DegreesToRadians));
+
+ Xbc = towerX[DELTA_C_AXIS] - towerX[DELTA_B_AXIS];
+ Xca = towerX[DELTA_A_AXIS] - towerX[DELTA_C_AXIS];
+ Xab = towerX[DELTA_B_AXIS] - towerX[DELTA_A_AXIS];
+ Ybc = towerY[DELTA_C_AXIS] - towerY[DELTA_B_AXIS];
+ Yca = towerY[DELTA_A_AXIS] - towerY[DELTA_C_AXIS];
+ Yab = towerY[DELTA_B_AXIS] - towerY[DELTA_A_AXIS];
+ coreFa = fsquare(towerX[DELTA_A_AXIS]) + fsquare(towerY[DELTA_A_AXIS]);
+ coreFb = fsquare(towerX[DELTA_B_AXIS]) + fsquare(towerY[DELTA_B_AXIS]);
+ coreFc = fsquare(towerX[DELTA_C_AXIS]) + fsquare(towerY[DELTA_C_AXIS]);
+ Q = (Xca * Yab - Xab * Yca) * 2;
Q2 = fsquare(Q);
D2 = fsquare(diagonal);
@@ -75,10 +75,10 @@ void LinearDeltaKinematics::Recalc()
// Make the average of the endstop adjustments zero, without changing the individual homed carriage heights
void LinearDeltaKinematics::NormaliseEndstopAdjustments()
{
- const float eav = (endstopAdjustments[A_AXIS] + endstopAdjustments[B_AXIS] + endstopAdjustments[C_AXIS])/3.0;
- endstopAdjustments[A_AXIS] -= eav;
- endstopAdjustments[B_AXIS] -= eav;
- endstopAdjustments[C_AXIS] -= eav;
+ const float eav = (endstopAdjustments[DELTA_A_AXIS] + endstopAdjustments[DELTA_B_AXIS] + endstopAdjustments[DELTA_C_AXIS])/3.0;
+ endstopAdjustments[DELTA_A_AXIS] -= eav;
+ endstopAdjustments[DELTA_B_AXIS] -= eav;
+ endstopAdjustments[DELTA_C_AXIS] -= eav;
homedHeight += eav;
homedCarriageHeight += eav; // no need for a full recalc, this is sufficient
}
@@ -100,34 +100,26 @@ float LinearDeltaKinematics::Transform(const float machinePos[], size_t axis) co
}
}
-// Calculate the Cartesian coordinates from the motor coordinates.
+// Calculate the Cartesian coordinates from the motor coordinates
void LinearDeltaKinematics::InverseTransform(float Ha, float Hb, float Hc, float machinePos[DELTA_AXES]) const
{
const float Fa = coreFa + fsquare(Ha);
const float Fb = coreFb + fsquare(Hb);
const float Fc = coreFc + fsquare(Hc);
-// debugPrintf("Ha=%f Hb=%f Hc=%f Fa=%f Fb=%f Fc=%f Xbc=%f Xca=%f Xab=%f Ybc=%f Yca=%f Yab=%f\n",
-// Ha, Hb, Hc, Fa, Fb, Fc, Xbc, Xca, Xab, Ybc, Yca, Yab);
-
- // Setup PQRSU such that x = -(S - uz)/P, y = (P - Rz)/Q
+ // Calculate PQRSU such that x = -(S - Uz)/Q, y = (P - Rz)/Q
const float P = (Xbc * Fa) + (Xca * Fb) + (Xab * Fc);
const float S = (Ybc * Fa) + (Yca * Fb) + (Yab * Fc);
-
- const float R = 2 * ((Xbc * Ha) + (Xca * Hb) + (Xab * Hc));
- const float U = 2 * ((Ybc * Ha) + (Yca * Hb) + (Yab * Hc));
-
-// debugPrintf("P= %f R=%f S=%f U=%f Q=%f\n", P, R, S, U, Q);
+ const float R = ((Xbc * Ha) + (Xca * Hb) + (Xab * Hc)) * 2;
+ const float U = ((Ybc * Ha) + (Yca * Hb) + (Yab * Hc)) * 2;
const float R2 = fsquare(R), U2 = fsquare(U);
- float A = U2 + R2 + Q2;
- float minusHalfB = S * U + P * R + Ha * Q2 + towerX[A_AXIS] * U * Q - towerY[A_AXIS] * R * Q;
- float C = fsquare(S + towerX[A_AXIS] * Q) + fsquare(P - towerY[A_AXIS] * Q) + (fsquare(Ha) - D2) * Q2;
-
-// debugPrintf("A=%f minusHalfB=%f C=%f\n", A, minusHalfB, C);
+ const float A = U2 + R2 + Q2;
+ const float minusHalfB = S * U + P * R + Ha * Q2 + towerX[DELTA_A_AXIS] * U * Q - towerY[DELTA_A_AXIS] * R * Q;
+ const float C = fsquare(S + towerX[DELTA_A_AXIS] * Q) + fsquare(P - towerY[DELTA_A_AXIS] * Q) + (fsquare(Ha) - D2) * Q2;
- float z = (minusHalfB - sqrtf(fsquare(minusHalfB) - A * C)) / A;
+ const float z = (minusHalfB - sqrtf(fsquare(minusHalfB) - A * C)) / A;
machinePos[X_AXIS] = (U * z - S) / Q;
machinePos[Y_AXIS] = (P - R * z) / Q;
machinePos[Z_AXIS] = z - ((machinePos[X_AXIS] * xTilt) + (machinePos[Y_AXIS] * yTilt));
@@ -153,7 +145,7 @@ bool LinearDeltaKinematics::CartesianToMotorSteps(const float machinePos[], cons
// Convert motor coordinates to machine coordinates. Used after homing and after individual motor moves.
void LinearDeltaKinematics::MotorStepsToCartesian(const int32_t motorPos[], const float stepsPerMm[], size_t numVisibleAxes, size_t numTotalAxes, float machinePos[]) const
{
- InverseTransform(motorPos[A_AXIS]/stepsPerMm[A_AXIS], motorPos[B_AXIS]/stepsPerMm[B_AXIS], motorPos[C_AXIS]/stepsPerMm[C_AXIS], machinePos);
+ InverseTransform(motorPos[DELTA_A_AXIS]/stepsPerMm[DELTA_A_AXIS], motorPos[DELTA_B_AXIS]/stepsPerMm[DELTA_B_AXIS], motorPos[DELTA_C_AXIS]/stepsPerMm[DELTA_C_AXIS], machinePos);
// Convert any additional axes linearly
for (size_t drive = DELTA_AXES; drive < numVisibleAxes; ++drive)
@@ -168,7 +160,7 @@ bool LinearDeltaKinematics::IsReachable(float x, float y, bool isCoordinated) co
return fsquare(x) + fsquare(y) < printRadiusSquared;
}
-// Limit the Cartesian position that the user wants to move to
+// Limit the Cartesian position that the user wants to move to returning true if we adjusted the position
bool LinearDeltaKinematics::LimitPosition(float coords[], size_t numVisibleAxes, AxesBitmap axesHomed, bool isCoordinated) const
{
const AxesBitmap allAxes = MakeBitmap<AxesBitmap>(X_AXIS) | MakeBitmap<AxesBitmap>(Y_AXIS) | MakeBitmap<AxesBitmap>(Z_AXIS);
@@ -223,7 +215,7 @@ void LinearDeltaKinematics::GetAssumedInitialPosition(size_t numAxes, float posi
positions[Z_AXIS] = homedHeight;
}
-// Auto calibrate from a set of probe points
+// Auto calibrate from a set of probe points returning true if it failed
bool LinearDeltaKinematics::DoAutoCalibration(size_t numFactors, const RandomProbePointSet& probePoints, StringRef& reply)
{
const size_t NumDeltaFactors = 9; // maximum number of delta machine factors we can adjust
@@ -245,8 +237,8 @@ bool LinearDeltaKinematics::DoAutoCalibration(size_t numFactors, const RandomPro
//uint32_t startTime = reprap.GetPlatform()->GetInterruptClocks();
// Transform the probing points to motor endpoints and store them in a matrix, so that we can do multiple iterations using the same data
- FixedMatrix<floatc_t, MaxDeltaCalibrationPoints, DELTA_AXES> probeMotorPositions;
- floatc_t corrections[MaxDeltaCalibrationPoints];
+ FixedMatrix<floatc_t, MaxCalibrationPoints, DELTA_AXES> probeMotorPositions;
+ floatc_t corrections[MaxCalibrationPoints];
floatc_t initialSumOfSquares = 0.0;
for (size_t i = 0; i < numPoints; ++i)
{
@@ -255,9 +247,9 @@ bool LinearDeltaKinematics::DoAutoCalibration(size_t numFactors, const RandomPro
const floatc_t zp = reprap.GetMove().GetProbeCoordinates(i, machinePos[X_AXIS], machinePos[Y_AXIS], probePoints.PointWasCorrected(i));
machinePos[Z_AXIS] = 0.0;
- probeMotorPositions(i, A_AXIS) = Transform(machinePos, A_AXIS);
- probeMotorPositions(i, B_AXIS) = Transform(machinePos, B_AXIS);
- probeMotorPositions(i, C_AXIS) = Transform(machinePos, C_AXIS);
+ probeMotorPositions(i, DELTA_A_AXIS) = Transform(machinePos, DELTA_A_AXIS);
+ probeMotorPositions(i, DELTA_B_AXIS) = Transform(machinePos, DELTA_B_AXIS);
+ probeMotorPositions(i, DELTA_C_AXIS) = Transform(machinePos, DELTA_C_AXIS);
initialSumOfSquares += fcsquare(zp);
}
@@ -268,14 +260,14 @@ bool LinearDeltaKinematics::DoAutoCalibration(size_t numFactors, const RandomPro
for (;;)
{
// Build a Nx9 matrix of derivatives with respect to xa, xb, yc, za, zb, zc, diagonal.
- FixedMatrix<floatc_t, MaxDeltaCalibrationPoints, NumDeltaFactors> derivativeMatrix;
+ FixedMatrix<floatc_t, MaxCalibrationPoints, NumDeltaFactors> derivativeMatrix;
for (size_t i = 0; i < numPoints; ++i)
{
for (size_t j = 0; j < numFactors; ++j)
{
const size_t adjustedJ = (numFactors == 8 && j >= 6) ? j + 1 : j; // skip diagonal rod length if doing 8-factor calibration
derivativeMatrix(i, j) =
- ComputeDerivative(adjustedJ, probeMotorPositions(i, A_AXIS), probeMotorPositions(i, B_AXIS), probeMotorPositions(i, C_AXIS));
+ ComputeDerivative(adjustedJ, probeMotorPositions(i, DELTA_A_AXIS), probeMotorPositions(i, DELTA_B_AXIS), probeMotorPositions(i, DELTA_C_AXIS));
}
}
@@ -354,7 +346,7 @@ bool LinearDeltaKinematics::DoAutoCalibration(size_t numFactors, const RandomPro
// Calculate the expected probe heights using the new parameters
{
- floatc_t expectedResiduals[MaxDeltaCalibrationPoints];
+ floatc_t expectedResiduals[MaxCalibrationPoints];
floatc_t sumOfSquares = 0.0;
for (size_t i = 0; i < numPoints; ++i)
{
@@ -363,7 +355,7 @@ bool LinearDeltaKinematics::DoAutoCalibration(size_t numFactors, const RandomPro
probeMotorPositions(i, axis) += solution[axis];
}
float newPosition[DELTA_AXES];
- InverseTransform(probeMotorPositions(i, A_AXIS), probeMotorPositions(i, B_AXIS), probeMotorPositions(i, C_AXIS), newPosition);
+ InverseTransform(probeMotorPositions(i, DELTA_A_AXIS), probeMotorPositions(i, DELTA_B_AXIS), probeMotorPositions(i, DELTA_C_AXIS), newPosition);
corrections[i] = newPosition[Z_AXIS];
expectedResiduals[i] = probePoints.GetZHeight(i) + newPosition[Z_AXIS];
sumOfSquares += fcsquare(expectedResiduals[i]);
@@ -436,15 +428,15 @@ floatc_t LinearDeltaKinematics::ComputeDerivative(unsigned int deriv, float ha,
break;
case 4:
- hiParams.angleCorrections[A_AXIS] += perturb;
- loParams.angleCorrections[A_AXIS] -= perturb;
+ hiParams.angleCorrections[DELTA_A_AXIS] += perturb;
+ loParams.angleCorrections[DELTA_A_AXIS] -= perturb;
hiParams.Recalc();
loParams.Recalc();
break;
case 5:
- hiParams.angleCorrections[B_AXIS] += perturb;
- loParams.angleCorrections[B_AXIS] -= perturb;
+ hiParams.angleCorrections[DELTA_B_AXIS] += perturb;
+ loParams.angleCorrections[DELTA_B_AXIS] -= perturb;
hiParams.Recalc();
loParams.Recalc();
break;
@@ -491,12 +483,12 @@ floatc_t LinearDeltaKinematics::ComputeDerivative(unsigned int deriv, float ha,
// Y tilt adjustment
void LinearDeltaKinematics::Adjust(size_t numFactors, const floatc_t v[])
{
- const float oldCarriageHeightA = GetHomedCarriageHeight(A_AXIS); // save for later
+ const float oldCarriageHeightA = GetHomedCarriageHeight(DELTA_A_AXIS); // save for later
// Update endstop adjustments
- endstopAdjustments[A_AXIS] += (float)v[0];
- endstopAdjustments[B_AXIS] += (float)v[1];
- endstopAdjustments[C_AXIS] += (float)v[2];
+ endstopAdjustments[DELTA_A_AXIS] += (float)v[0];
+ endstopAdjustments[DELTA_B_AXIS] += (float)v[1];
+ endstopAdjustments[DELTA_C_AXIS] += (float)v[2];
NormaliseEndstopAdjustments();
if (numFactors >= 4)
@@ -505,8 +497,8 @@ void LinearDeltaKinematics::Adjust(size_t numFactors, const floatc_t v[])
if (numFactors >= 6)
{
- angleCorrections[A_AXIS] += (float)v[4];
- angleCorrections[B_AXIS] += (float)v[5];
+ angleCorrections[DELTA_A_AXIS] += (float)v[4];
+ angleCorrections[DELTA_B_AXIS] += (float)v[5];
if (numFactors == 7 || numFactors == 9)
{
@@ -530,7 +522,7 @@ void LinearDeltaKinematics::Adjust(size_t numFactors, const floatc_t v[])
// Adjusting the diagonal and the tower positions affects the homed carriage height.
// We need to adjust homedHeight to allow for this, to get the change that was requested in the endstop corrections.
- const float heightError = GetHomedCarriageHeight(A_AXIS) - oldCarriageHeightA - (float)v[0];
+ const float heightError = GetHomedCarriageHeight(DELTA_A_AXIS) - oldCarriageHeightA - (float)v[0];
homedHeight -= heightError;
homedCarriageHeight -= heightError;
@@ -539,11 +531,12 @@ void LinearDeltaKinematics::Adjust(size_t numFactors, const floatc_t v[])
// run will correct it.
}
+// Print all the parameters for debugging
void LinearDeltaKinematics::PrintParameters(StringRef& reply) const
{
reply.printf("Stops X%.3f Y%.3f Z%.3f height %.3f diagonal %.3f radius %.3f xcorr %.2f ycorr %.2f zcorr %.2f xtilt %.3f%% ytilt %.3f%%\n",
- (double)endstopAdjustments[A_AXIS], (double)endstopAdjustments[B_AXIS], (double)endstopAdjustments[C_AXIS], (double)homedHeight, (double)diagonal, (double)radius,
- (double)angleCorrections[A_AXIS], (double)angleCorrections[B_AXIS], (double)angleCorrections[C_AXIS], (double)(xTilt * 100.0), (double)(yTilt * 100.0));
+ (double)endstopAdjustments[DELTA_A_AXIS], (double)endstopAdjustments[DELTA_B_AXIS], (double)endstopAdjustments[DELTA_C_AXIS], (double)homedHeight, (double)diagonal, (double)radius,
+ (double)angleCorrections[DELTA_A_AXIS], (double)angleCorrections[DELTA_B_AXIS], (double)angleCorrections[DELTA_C_AXIS], (double)(xTilt * 100.0), (double)(yTilt * 100.0));
}
// Write the parameters that are set by auto calibration to a file, returning true if success
@@ -553,7 +546,7 @@ bool LinearDeltaKinematics::WriteCalibrationParameters(FileStore *f) const
if (ok)
{
scratchString.printf("M665 L%.3f R%.3f H%.3f B%.1f X%.3f Y%.3f Z%.3f\n",
- (double)diagonal, (double)radius, (double)homedHeight, (double)printRadius, (double)angleCorrections[A_AXIS], (double)angleCorrections[B_AXIS], (double)angleCorrections[C_AXIS]);
+ (double)diagonal, (double)radius, (double)homedHeight, (double)printRadius, (double)angleCorrections[DELTA_A_AXIS], (double)angleCorrections[DELTA_B_AXIS], (double)angleCorrections[DELTA_C_AXIS]);
ok = f->Write(scratchString.Pointer());
}
if (ok)
@@ -604,19 +597,19 @@ bool LinearDeltaKinematics::Configure(unsigned int mCode, GCodeBuffer& gb, Strin
if (gb.Seen('X'))
{
// X tower position correction
- angleCorrections[A_AXIS] = gb.GetFValue();
+ angleCorrections[DELTA_A_AXIS] = gb.GetFValue();
seen = true;
}
if (gb.Seen('Y'))
{
// Y tower position correction
- angleCorrections[B_AXIS] = gb.GetFValue();
+ angleCorrections[DELTA_B_AXIS] = gb.GetFValue();
seen = true;
}
if (gb.Seen('Z'))
{
// Y tower position correction
- angleCorrections[C_AXIS] = gb.GetFValue();
+ angleCorrections[DELTA_C_AXIS] = gb.GetFValue();
seen = true;
}
@@ -637,7 +630,7 @@ bool LinearDeltaKinematics::Configure(unsigned int mCode, GCodeBuffer& gb, Strin
", X %.3f" DEGREE_SYMBOL ", Y %.3f" DEGREE_SYMBOL ", Z %.3f" DEGREE_SYMBOL,
(double)diagonal, (double)radius,
(double)homedHeight, (double)printRadius,
- (double)angleCorrections[A_AXIS], (double)angleCorrections[B_AXIS], (double)angleCorrections[C_AXIS]);
+ (double)angleCorrections[DELTA_A_AXIS], (double)angleCorrections[DELTA_B_AXIS], (double)angleCorrections[DELTA_C_AXIS]);
}
return seen;
}
diff --git a/src/Movement/Kinematics/LinearDeltaKinematics.h b/src/Movement/Kinematics/LinearDeltaKinematics.h
index bc09cb1c..85db62b4 100644
--- a/src/Movement/Kinematics/LinearDeltaKinematics.h
+++ b/src/Movement/Kinematics/LinearDeltaKinematics.h
@@ -11,10 +11,10 @@
#include "RepRapFirmware.h"
#include "Kinematics.h"
-const size_t DELTA_AXES = 3;
-const size_t A_AXIS = 0;
-const size_t B_AXIS = 1;
-const size_t C_AXIS = 2;
+constexpr size_t DELTA_AXES = 3;
+constexpr size_t DELTA_A_AXIS = 0;
+constexpr size_t DELTA_B_AXIS = 1;
+constexpr size_t DELTA_C_AXIS = 2;
// Class to hold the parameter for a delta machine.
class LinearDeltaKinematics : public Kinematics
@@ -88,6 +88,7 @@ private:
float Xbc, Xca, Xab, Ybc, Yca, Yab;
float coreFa, coreFb, coreFc;
float Q, Q2, D2;
+
bool doneAutoCalibration; // True if we have done auto calibration
};
diff --git a/src/Movement/Kinematics/ScaraKinematics.cpp b/src/Movement/Kinematics/ScaraKinematics.cpp
index 78e12db9..b1ec9530 100644
--- a/src/Movement/Kinematics/ScaraKinematics.cpp
+++ b/src/Movement/Kinematics/ScaraKinematics.cpp
@@ -32,7 +32,7 @@ const char *ScaraKinematics::GetName(bool forStatusReport) const
return "Scara";
}
-// Calculate theta, psi and the new arm mode form a target position.
+// Calculate theta, psi and the new arm mode from a target position.
// If the position is not reachable because it is out of radius limits, set theta and psi to NaN and return false.
// Otherwise set theta and psi to the required values and return true if they are in range.
bool ScaraKinematics::CalculateThetaAndPsi(const float machinePos[], bool isCoordinated, float& theta, float& psi, bool& armMode) const
diff --git a/src/Movement/Kinematics/ZLeadscrewKinematics.cpp b/src/Movement/Kinematics/ZLeadscrewKinematics.cpp
index 02eaadc1..98553369 100644
--- a/src/Movement/Kinematics/ZLeadscrewKinematics.cpp
+++ b/src/Movement/Kinematics/ZLeadscrewKinematics.cpp
@@ -107,7 +107,7 @@ bool ZLeadscrewKinematics::DoAutoCalibration(size_t numFactors, const RandomProb
// Build a N x 2, 3 or 4 matrix of derivatives with respect to the leadscrew adjustments
// See the wxMaxima documents for the maths involved
- FixedMatrix<floatc_t, MaxDeltaCalibrationPoints, MaxLeadscrews> derivativeMatrix;
+ FixedMatrix<floatc_t, MaxCalibrationPoints, MaxLeadscrews> derivativeMatrix;
floatc_t initialSumOfSquares = 0.0;
for (size_t i = 0; i < numPoints; ++i)
{
@@ -236,7 +236,7 @@ bool ZLeadscrewKinematics::DoAutoCalibration(size_t numFactors, const RandomProb
}
// Calculate and display the residuals, also check for errors
- floatc_t residuals[MaxDeltaCalibrationPoints];
+ floatc_t residuals[MaxCalibrationPoints];
floatc_t sumOfSquares = 0.0;
for (size_t i = 0; i < numPoints; ++i)
{
diff --git a/src/Movement/Move.h b/src/Movement/Move.h
index 195226a9..790fe994 100644
--- a/src/Movement/Move.h
+++ b/src/Movement/Move.h
@@ -27,7 +27,7 @@ const unsigned int NumDms = DdaRingLength * 8; // suitable for e.g. a delta
#else
// We are more memory-constrained on the SAM3X
const unsigned int DdaRingLength = 20;
-const unsigned int NumDms = DdaRingLength * 5; // suitable for e.g. a delta + 1-input hot end
+const unsigned int NumDms = DdaRingLength * 5; // suitable for e.g. a delta + 2-input hot end
#endif
/**
diff --git a/src/Platform.cpp b/src/Platform.cpp
index 787bd437..b77a3d17 100644
--- a/src/Platform.cpp
+++ b/src/Platform.cpp
@@ -222,9 +222,29 @@ extern "C"
" ite eq \n" /* load the appropriate stack pointer into R0 */
" mrseq r0, msp \n"
" mrsne r0, psp \n"
- " ldr r2, handler2_address_const \n"
+ " ldr r2, handler_hf_address_const \n"
" bx r2 \n"
- " handler2_address_const: .word hardFaultDispatcher \n"
+ " handler_hf_address_const: .word hardFaultDispatcher \n"
+ );
+ }
+
+ void wdtFaultDispatcher(const uint32_t *pulFaultStackAddress)
+ {
+ reprap.GetPlatform().SoftwareReset((uint16_t)SoftwareResetReason::wdtFault, pulFaultStackAddress + 5);
+ }
+
+ void WDT_Handler() __attribute__((naked));
+ void WDT_Handler()
+ {
+ __asm volatile
+ (
+ " tst lr, #4 \n" /* test bit 2 of the EXC_RETURN in LR to determine which stack was in use */
+ " ite eq \n" /* load the appropriate stack pointer into R0 */
+ " mrseq r0, msp \n"
+ " mrsne r0, psp \n"
+ " ldr r2, handler_wdt_address_const \n"
+ " bx r2 \n"
+ " handler_wdt_address_const: .word wdtFaultDispatcher \n"
);
}
@@ -243,17 +263,17 @@ extern "C"
" ite eq \n" /* load the appropriate stack pointer into R0 */
" mrseq r0, msp \n"
" mrsne r0, psp \n"
- " ldr r2, handler4_address_const \n"
+ " ldr r2, handler_oflt_address_const \n"
" bx r2 \n"
- " handler4_address_const: .word otherFaultDispatcher \n"
+ " handler_oflt_address_const: .word otherFaultDispatcher \n"
);
}
// We could set up the following fault handlers to retrieve the program counter in the same way as for a Hard Fault,
// however these exceptions are unlikely to occur, so for now we just report the exception type.
- // 2017-05-25: A user is getting 'otherFault' reports, so now we do a stack dump for those too.
void NMI_Handler () { reprap.GetPlatform().SoftwareReset((uint16_t)SoftwareResetReason::NMI); }
+ // 2017-05-25: A user is getting 'otherFault' reports, so now we do a stack dump for those too.
void SVC_Handler () __attribute__ ((alias("OtherFault_Handler")));
void DebugMon_Handler () __attribute__ ((alias("OtherFault_Handler")));
void PendSV_Handler () __attribute__ ((alias("OtherFault_Handler")));
@@ -1158,11 +1178,15 @@ void Platform::UpdateFirmware()
}
#ifdef DUET_NG
- IoPort::WriteDigital(Z_PROBE_MOD_PIN, false); // turn the DIAG LED off
+ IoPort::WriteDigital(Z_PROBE_MOD_PIN, false); // turn the DIAG LED off
#endif
wdt_restart(WDT); // kick the watchdog one last time
+#if SAM4E || SAME70
+ rswdt_restart(RSWDT); // kick the secondary watchdog
+#endif
+
// Modify vector table location
__DSB();
__ISB();
@@ -1740,6 +1764,10 @@ void Platform::SoftwareReset(uint16_t reason, const uint32_t *stk)
{
wdt_restart(WDT); // kick the watchdog
+#if SAM4E || SAME70
+ rswdt_restart(RSWDT); // kick the secondary watchdog
+#endif
+
DisableCache(); // disable the cache, it seems to upset flash memory access
if (reason == (uint16_t)SoftwareResetReason::erase)
@@ -1856,13 +1884,18 @@ static void FanInterrupt(void*)
void Platform::InitialiseInterrupts()
{
+#if SAM4E || SAM7E
+ NVIC_SetPriority(WDT_IRQn, NvicPriorityWatchdog); // set priority for watchdog interrupts
+#endif
+
// Set the tick interrupt to the highest priority. We need to to monitor the heaters and kick the watchdog.
- NVIC_SetPriority(SysTick_IRQn, NvicPrioritySystick); // set priority for tick interrupts
+ NVIC_SetPriority(SysTick_IRQn, NvicPrioritySystick); // set priority for tick interrupts
#if SAM4E || SAM4S
- NVIC_SetPriority(UART0_IRQn, NvicPriorityUart); // set priority for UART interrupt - must be higher than step interrupt
+ NVIC_SetPriority(UART0_IRQn, NvicPriorityPanelDueUart); // set priority for UART interrupt
+ NVIC_SetPriority(UART1_IRQn, NvicPriorityWiFiUart); // set priority for WiFi UART interrupt
#else
- NVIC_SetPriority(UART_IRQn, NvicPriorityUart); // set priority for UART interrupt - must be higher than step interrupt
+ NVIC_SetPriority(UART_IRQn, NvicPriorityPanelDueUart); // set priority for UART interrupt
#endif
#if HAS_SMART_DRIVERS
@@ -1933,6 +1966,13 @@ void Platform::InitialiseInterrupts()
const uint16_t timeout = 32768/128; // set watchdog timeout to 1 second (max allowed value is 4095 = 16 seconds)
wdt_init(WDT, WDT_MR_WDRSTEN, timeout, timeout); // reset the processor on a watchdog fault
+#if SAM4E || SAME70
+ // The RSWDT must be initialised *after* the main WDT
+ const uint16_t rsTimeout = 16384/128; // set secondary watchdog timeout to 0.5 second (max allowed value is 4095 = 16 seconds)
+ rswdt_init(RSWDT, RSWDT_MR_WDFIEN, rsTimeout, rsTimeout); // generate an interrupt on a watchdog fault
+ NVIC_EnableIRQ(WDT_IRQn); // enable the watchdog interrupt
+#endif
+
active = true; // this enables the tick interrupt, which keeps the watchdog happy
}
@@ -1942,9 +1982,87 @@ void Platform::InitialiseInterrupts()
//extern "C" uint32_t longestWriteWaitTime, shortestWriteWaitTime, longestReadWaitTime, shortestReadWaitTime;
//extern uint32_t maxRead, maxWrite;
+#if SAM4E || SAM4S || SAME70
+
+// Print the unique processor ID
+void Platform::PrintUniqueId(MessageType mtype)
+{
+ uint32_t idBuf[5];
+ DisableCache();
+ cpu_irq_disable();
+ const uint32_t rc = flash_read_unique_id(idBuf, 4);
+ cpu_irq_enable();
+ EnableCache();
+ if (rc == 0)
+ {
+ // Put the checksum at the end
+ idBuf[4] = idBuf[0] ^ idBuf[1] ^ idBuf[2] ^ idBuf[3];
+
+ // We are only going to print 30 5-bit characters = 128 data bits + 22 checksum bits. So compress the 32 checksum bits into 22.
+ idBuf[4] ^= (idBuf[4] >> 10);
+
+ // Print the unique ID and checksum as 30 base5 alphanumeric digits
+ char digits[30 + 5 + 1]; // 30 characters, 5 separators, 1 null terminator
+ char *digitPtr = digits;
+ for (size_t i = 0; i < 30; ++i)
+ {
+ if ((i % 5) == 0 && i != 0)
+ {
+ *digitPtr++ = '-';
+ }
+ const size_t index = (i * 5) / 32;
+ const size_t shift = (i * 5) % 32;
+ uint32_t val = idBuf[index] >> shift;
+ if (shift > 32 - 5)
+ {
+ // We need some bits from the next dword too
+ val |= idBuf[index + 1] << (32 - shift);
+ }
+ val &= 31;
+ char c;
+ if (val < 10)
+ {
+ c = val + '0';
+ }
+ else
+ {
+ c = val + ('A' - 10);
+ // We have 26 letters in the usual A-Z alphabet and we only need 22 of them plus 0-9.
+ // So avoid using letters C, E, I and O which are easily mistaken for G, F, 1 and 0.
+ if (c >= 'C')
+ {
+ ++c;
+ }
+ if (c >= 'E')
+ {
+ ++c;
+ }
+ if (c >= 'I')
+ {
+ ++c;
+ }
+ if (c >= 'O')
+ {
+ ++c;
+ }
+ }
+ *digitPtr++ = c;
+ }
+ *digitPtr = 0;
+ MessageF(mtype, "Board ID: %s\n", digits);
+ }
+}
+
+#endif
+
// Return diagnostic information
void Platform::Diagnostics(MessageType mtype)
{
+#if SAM4E && USE_CACHE
+ // Get the cache statistics before we start messing around with the cache
+ const uint32_t cacheCount = cmcc_get_monitor_cnt(CMCC);
+#endif
+
Message(mtype, "=== Platform ===\n");
// Print the firmware version and board type
@@ -1960,79 +2078,8 @@ void Platform::Diagnostics(MessageType mtype)
Message(mtype, "\n");
-#if SAM4E && USE_CACHE
- // Get the cache statistics before we start messing around with the cache
- const uint32_t cacheCount = cmcc_get_monitor_cnt(CMCC);
-#endif
-
#if SAM4E || SAM4S
- // Print the unique ID
- {
- uint32_t idBuf[5];
- DisableCache();
- cpu_irq_disable();
- const uint32_t rc = flash_read_unique_id(idBuf, 4);
- cpu_irq_enable();
- EnableCache();
- if (rc == 0)
- {
- // Put the checksum at the end
- idBuf[4] = idBuf[0] ^ idBuf[1] ^ idBuf[2] ^ idBuf[3];
-
- // We are only going to print 30 5-bit characters = 128 data bits + 22 checksum bits. So compress the 32 checksum bits into 22.
- idBuf[4] ^= (idBuf[4] >> 10);
-
- // Print the unique ID and checksum as 30 base5 alphanumeric digits
- char digits[30 + 5 + 1]; // 30 characters, 5 separators, 1 null terminator
- char *digitPtr = digits;
- for (size_t i = 0; i < 30; ++i)
- {
- if ((i % 5) == 0 && i != 0)
- {
- *digitPtr++ = '-';
- }
- const size_t index = (i * 5) / 32;
- const size_t shift = (i * 5) % 32;
- uint32_t val = idBuf[index] >> shift;
- if (shift > 32 - 5)
- {
- // We need some bits from the next dword too
- val |= idBuf[index + 1] << (32 - shift);
- }
- val &= 31;
- char c;
- if (val < 10)
- {
- c = val + '0';
- }
- else
- {
- c = val + ('A' - 10);
- // We have 26 letters in the usual A-Z alphabet and we only need 22 of them.
- // So avoid using letters C, E, I and O which are easily mistaken for G, F, 1 and 0.
- if (c >= 'C')
- {
- ++c;
- }
- if (c >= 'E')
- {
- ++c;
- }
- if (c >= 'I')
- {
- ++c;
- }
- if (c >= 'O')
- {
- ++c;
- }
- }
- *digitPtr++ = c;
- }
- *digitPtr = 0;
- MessageF(mtype, "Board ID: %s\n", digits);
- }
- }
+ PrintUniqueId(mtype);
#endif
// Print memory stats and error codes to USB and copy them to the current webserver reply
@@ -2073,7 +2120,7 @@ void Platform::Diagnostics(MessageType mtype)
memset(srdBuf, 0, sizeof(srdBuf));
int slot = -1;
-#if SAM4E || SAM4S
+#if SAM4E || SAM4S || SAME70
// Work around bug in ASF flash library: flash_read_user_signature calls a RAMFUNC without disabling interrupts first.
// This caused a crash (watchdog timeout) sometimes if we run M122 while a print is in progress
DisableCache();
@@ -2103,8 +2150,9 @@ void Platform::Diagnostics(MessageType mtype)
: (reason == (uint32_t)SoftwareResetReason::NMI) ? "NMI"
: (reason == (uint32_t)SoftwareResetReason::hardFault) ? "Hard fault"
: (reason == (uint32_t)SoftwareResetReason::stuckInSpin) ? "Stuck in spin loop"
- : (reason == (uint32_t)SoftwareResetReason::otherFault) ? "Other fault"
- : "Unknown";
+ : (reason == (uint32_t)SoftwareResetReason::wdtFault) ? "Watchdog timeout"
+ : (reason == (uint32_t)SoftwareResetReason::otherFault) ? "Other fault"
+ : "Unknown";
MessageF(mtype, "%s, spinning module %s, available RAM %" PRIu32 " bytes (slot %d)\n",
reasonText, moduleName[srdBuf[slot].resetReason & 0x0F], srdBuf[slot].neverUsedRam, slot);
// Our format buffer is only 256 characters long, so the next 2 lines must be written separately
@@ -2143,7 +2191,7 @@ void Platform::Diagnostics(MessageType mtype)
// Show the HSMCI CD pin and speed
#if HAS_HIGH_SPEED_SD
- MessageF(mtype, "SD card 0 %s, interface speed: %.1fMBytes/sec\n", (sd_mmc_card_detected(0) ? "detected" : "not detected"), (double)((float)hsmci_get_speed()/1000000.0));
+ MessageF(mtype, "SD card 0 %s, interface speed: %.1fMBytes/sec\n", (sd_mmc_card_detected(0) ? "detected" : "not detected"), (double)((float)hsmci_get_speed() * 0.000001));
#else
MessageF(mtype, "SD card 0 %s\n", (sd_mmc_card_detected(0) ? "detected" : "not detected"));
#endif
@@ -2165,14 +2213,10 @@ void Platform::Diagnostics(MessageType mtype)
(double)AdcReadingToPowerVoltage(lowestVin), (double)AdcReadingToPowerVoltage(currentVin), (double)AdcReadingToPowerVoltage(highestVin),
numUnderVoltageEvents, numOverVoltageEvents);
lowestVin = highestVin = currentVin;
+#endif
+#if HAS_SMART_DRIVERS
// Show the motor stall status
- if (expansionBoard == ExpansionBoardType::DueX2 || expansionBoard == ExpansionBoardType::DueX5)
- {
- const bool stalled = digitalRead(DueX_SG);
- MessageF(mtype, "Expansion motor(s) stall indication: %s\n", (stalled) ? "yes" : "no");
- }
-
for (size_t drive = 0; drive < numSmartDrivers; ++drive)
{
const uint32_t stat = SmartDrivers::GetLiveStatus(drive);
@@ -2190,6 +2234,14 @@ void Platform::Diagnostics(MessageType mtype)
}
#endif
+#ifdef DUET_NG
+ if (expansionBoard == ExpansionBoardType::DueX2 || expansionBoard == ExpansionBoardType::DueX5)
+ {
+ const bool stalled = digitalRead(DueX_SG);
+ MessageF(mtype, "Expansion motor(s) stall indication: %s\n", (stalled) ? "yes" : "no");
+ }
+#endif
+
// Show current RTC time
Message(mtype, "Date/time: ");
struct tm timeInfo;
@@ -2230,14 +2282,141 @@ void Platform::Diagnostics(MessageType mtype)
#endif
}
-void Platform::DiagnosticTest(int d)
+bool Platform::DiagnosticTest(GCodeBuffer& gb, StringRef& reply, int d)
{
static const uint32_t dummy[2] = { 0, 0 };
switch (d)
{
+ case (int)DiagnosticTestType::PrintTestReport:
+ {
+ const MessageType mtype = gb.GetResponseMessageType();
+ bool testFailed = false;
+
+ // Check the SD card detect and speed
+ if (!sd_mmc_card_detected(0))
+ {
+ Message(AddError(mtype), "SD card 0 not detected\n");
+ testFailed = true;
+ }
+#if HAS_HIGH_SPEED_SD
+ else if (hsmci_get_speed() != ExpectedSdCardSpeed)
+ {
+ MessageF(AddError(mtype), "SD card speed %.2fMbytes/sec is unexpected\n", (double)((float)hsmci_get_speed() * 0.000001));
+ testFailed = true;
+ }
+#endif
+ else
+ {
+ Message(mtype, "SD card interface OK\n");
+ }
+
+#if HAS_CPU_TEMP_SENSOR
+ // Check the MCU temperature
+ {
+ float tempMinMax[2];
+ size_t numTemps = 2;
+ bool seen = false;
+ if (gb.TryGetFloatArray('T', numTemps, tempMinMax, reply, seen, false))
+ {
+ return true;
+ }
+ if (!seen)
+ {
+ reply.copy("Missing T parameter");
+ return true;
+ }
+
+ const float currentMcuTemperature = AdcReadingToCpuTemperature(cpuTemperatureFilter.GetSum());
+ if (currentMcuTemperature < tempMinMax[0])
+ {
+ MessageF(AddError(mtype), "MCU temperature %.1f is lower than expected\n", (double)currentMcuTemperature);
+ testFailed = true;
+ }
+ else if (currentMcuTemperature > tempMinMax[1])
+ {
+ MessageF(AddError(mtype), "MCU temperature %.1f is higher than expected\n", (double)currentMcuTemperature);
+ testFailed = true;
+ }
+ else
+ {
+ Message(mtype, "MCU temperature reading OK\n");
+ }
+ }
+#endif
+
+#if HAS_VOLTAGE_MONITOR
+ // Check the supply voltage
+ {
+ float voltageMinMax[2];
+ size_t numVoltages = 2;
+ bool seen = false;
+ if (gb.TryGetFloatArray('V', numVoltages, voltageMinMax, reply, seen, false))
+ {
+ return true;
+ }
+ if (!seen)
+ {
+ reply.copy("Missing V parameter");
+ return true;
+ }
+
+ const float voltage = AdcReadingToPowerVoltage(currentVin);
+ if (voltage < voltageMinMax[0])
+ {
+ MessageF(AddError(mtype), "Voltage reading %.1f is lower than expected\n", (double)voltage);
+ testFailed = true;
+ }
+ else if (voltage > voltageMinMax[1])
+ {
+ MessageF(AddError(mtype), "Voltage reading %.1f is higher than expected\n", (double)voltage);
+ testFailed = true;
+ }
+ else
+ {
+ Message(mtype, "Voltage reading OK\n");
+ }
+ }
+
+ // Check the stepper driver status
+ bool driversOK = true;
+ for (size_t driver = 0; driver < numSmartDrivers; ++driver)
+ {
+ const uint32_t stat = SmartDrivers::GetAccumulatedStatus(driver, 0xFFFFFFFF);
+ if ((stat & (TMC_RR_OT || TMC_RR_OTPW)) != 0)
+ {
+ MessageF(AddError(mtype), "Driver %u reports over temperature\n", driver);
+ driversOK = false;
+ }
+ if ((stat & TMC_RR_S2G) != 0)
+ {
+ MessageF(AddError(mtype), "Driver %u reports short-to-ground\n", driver);
+ driversOK = false;
+ }
+ }
+ if (driversOK)
+ {
+ Message(mtype, "Driver status OK\n");
+ }
+ else
+ {
+ testFailed = true;
+ }
+#endif
+
+ Message(mtype, (testFailed) ? "***** ONE OR MORE CHECKS FAILED *****\n" : "All checks passed\n");
+
+#if SAM4E || SAM4S || SAME70
+ if (!testFailed)
+ {
+ PrintUniqueId(mtype);
+ }
+#endif
+ }
+ break;
+
case (int)DiagnosticTestType::TestWatchdog:
- SysTick ->CTRL &= ~(SysTick_CTRL_TICKINT_Msk); // disable the system tick interrupt so that we get a watchdog timeout reset
+ SysTick->CTRL &= ~(SysTick_CTRL_TICKINT_Msk); // disable the system tick interrupt so that we get a watchdog timeout reset
break;
case (int)DiagnosticTestType::TestSpinLockup:
@@ -2259,7 +2438,7 @@ void Platform::DiagnosticTest(int d)
case (int)DiagnosticTestType::BusFault:
// Read from the "Undefined (Abort)" area
-#if SAM4E || SAM4S
+#if SAM4E || SAM4S || SAME70
(void)RepRap::ReadDword(reinterpret_cast<const char*>(0x20800000));
#elif SAM3XA
(void)RepRap::ReadDword(reinterpret_cast<const char*>(0x20200000));
@@ -2301,7 +2480,7 @@ void Platform::DiagnosticTest(int d)
ok2 = false;
}
}
- MessageF(GenericMessage, "Square roots: 62-bit %.2fus %s, 32-bit %.2fus %s\n",
+ reply.printf("Square roots: 62-bit %.2fus %s, 32-bit %.2fus %s\n",
(double)(tim1 * 10000)/DDA::stepClockRate, (ok1) ? "ok" : "ERROR",
(double)(tim2 * 10000)/DDA::stepClockRate, (ok2) ? "ok" : "ERROR");
}
@@ -2309,13 +2488,15 @@ void Platform::DiagnosticTest(int d)
#ifdef DUET_NG
case (int)DiagnosticTestType::PrintExpanderStatus:
- MessageF(GenericMessage, "Expander status %04X\n", DuetExpansion::DiagnosticRead());
+ reply.printf("Expander status %04X\n", DuetExpansion::DiagnosticRead());
break;
#endif
default:
break;
}
+
+ return false;
}
extern "C" uint32_t _estack; // this is defined in the linker script
@@ -4240,6 +4421,10 @@ void STEP_TC_HANDLER()
void Platform::Tick()
{
+#if SAM4E || SAME70
+ rswdt_restart(RSWDT); // kick the secondary watchdog (the primary one is kicked in CoreNG)
+#endif
+
if (tickState != 0)
{
#if HAS_VOLTAGE_MONITOR
diff --git a/src/Platform.h b/src/Platform.h
index 62635f97..a9baed16 100644
--- a/src/Platform.h
+++ b/src/Platform.h
@@ -1,21 +1,11 @@
/****************************************************************************************************
-RepRapFirmware - Platform: RepRapPro Ormerod with Duet controller
+RepRapFirmware - Platform
Platform contains all the code and definitions to deal with machine-dependent things such as control
pins, bed area, number of extruders, tolerable accelerations and speeds and so on.
-No definitions that are system-independent should go in here. Put them in Configuration.h. Note that
-the lengths of arrays such as DRIVES (see below) are defined here, so any array initialiser that depends on those
-lengths, for example:
-
-#define DRIVES 4
-.
-.
-.
-#define DRIVE_RELATIVE_MODES {false, false, false, true}
-
-also needs to go here.
+No definitions that are system-independent should go in here. Put them in Configuration.h.
-----------------------------------------------------------------------------------------------------
@@ -60,17 +50,11 @@ Licence: GPL
# include "Microstepping.h"
#endif
-const bool FORWARDS = true;
-const bool BACKWARDS = !FORWARDS;
+constexpr bool FORWARDS = true;
+constexpr bool BACKWARDS = !FORWARDS;
/**************************************************************************************************/
-// Some constants
-#define TIME_TO_REPRAP 1.0e6 // Convert seconds to the units used by the machine (usually microseconds)
-#define TIME_FROM_REPRAP 1.0e-6 // Convert the units used by the machine (usually microseconds) to seconds
-
-#define DEGREE_SYMBOL "\xC2\xB0" // Unicode degree-symbol as UTF8
-
#if SUPPORT_INKJET
// Inkjet (if any - no inkjet is flagged by INKJET_BITS negative)
@@ -93,24 +77,24 @@ const float AXIS_MAXIMA[MaxAxes] = AXES_(230.0, 210.0, 200.0, 0.0, 0.0, 0.0, 0.0
// Z PROBE
-const float Z_PROBE_STOP_HEIGHT = 0.7; // Millimetres
-const unsigned int Z_PROBE_AVERAGE_READINGS = 8; // We average this number of readings with IR on, and the same number with IR off
-const int Z_PROBE_AD_VALUE = 500; // Default for the Z probe - should be overwritten by experiment
+constexpr float Z_PROBE_STOP_HEIGHT = 0.7; // Millimetres
+constexpr unsigned int Z_PROBE_AVERAGE_READINGS = 8; // We average this number of readings with IR on, and the same number with IR off
+constexpr int Z_PROBE_AD_VALUE = 500; // Default for the Z probe - should be overwritten by experiment
// HEATERS - The bed is assumed to be the at index 0
// Define the number of temperature readings we average for each thermistor. This should be a power of 2 and at least 4 ^ AD_OVERSAMPLE_BITS.
// Keep THERMISTOR_AVERAGE_READINGS * NUM_HEATERS * 2ms no greater than HEAT_SAMPLE_TIME or the PIDs won't work well.
-const unsigned int ThermistorAverageReadings = 32;
+constexpr unsigned int ThermistorAverageReadings = 32;
-const uint32_t maxPidSpinDelay = 5000; // Maximum elapsed time in milliseconds between successive temp samples by Pid::Spin() permitted for a temp sensor
+constexpr uint32_t maxPidSpinDelay = 5000; // Maximum elapsed time in milliseconds between successive temp samples by Pid::Spin() permitted for a temp sensor
/****************************************************************************************************/
// File handling
-const size_t MAX_FILES = 10; // Must be large enough to handle the max number of simultaneous web requests + files being printed
-const size_t FILE_BUFFER_SIZE = 256;
+constexpr size_t MAX_FILES = 10; // Must be large enough to handle the max number of simultaneous web requests + files being printed
+constexpr size_t FILE_BUFFER_SIZE = 256;
/****************************************************************************************************/
@@ -170,6 +154,7 @@ enum class SoftwareResetReason : uint16_t
NMI = 0x20,
hardFault = 0x30, // most exceptions get escalated to a hard fault
stuckInSpin = 0x40, // we got stuck in a Spin() function for too long
+ wdtFault = 0x50, // secondary watchdog
otherFault = 0x70,
inAuxOutput = 0x0800, // this bit is or'ed in if we were in aux output at the time
inLwipSpin = 0x2000, // we got stuck in a call to LWIP for too long
@@ -179,18 +164,20 @@ enum class SoftwareResetReason : uint16_t
// Enumeration to describe various tests we do in response to the M122 command
enum class DiagnosticTestType : int
{
+ PrintTestReport = 1, // run some tests and report the processor ID
+
+ PrintMoves = 100, // print summary of recent moves (only if recording moves was enabled in firmware)
+#ifdef DUET_NG
+ PrintExpanderStatus = 101, // print DueXn expander status
+#endif
+ TimeSquareRoot = 102, // do a timing test on the square root function
+
TestWatchdog = 1001, // test that we get a watchdog reset if the tick interrupt stops
TestSpinLockup = 1002, // test that we get a software reset if a Spin() function takes too long
TestSerialBlock = 1003, // test what happens when we write a blocking message via debugPrintf()
DivideByZero = 1004, // do an integer divide by zero to test exception handling
UnalignedMemoryAccess = 1005, // do an unaligned memory access to test exception handling
- BusFault = 1006, // generate a bus fault
-
- PrintMoves = 100, // print summary of recent moves
-#ifdef DUET_NG
- PrintExpanderStatus = 101, // print DueXn expander status
-#endif
- TimeSquareRoot = 102 // do a timing test on the square root function
+ BusFault = 1006 // generate a bus fault
};
/***************************************************************************************************************/
@@ -313,7 +300,7 @@ public:
Compatibility Emulating() const;
void SetEmulating(Compatibility c);
void Diagnostics(MessageType mtype);
- void DiagnosticTest(int d);
+ bool DiagnosticTest(GCodeBuffer& gb, StringRef& reply, int d);
void ClassReport(uint32_t &lastTime); // Called on Spin() return to check everything's live.
void LogError(ErrorCode e) { errorCodeBits |= (uint32_t)e; }
@@ -606,6 +593,10 @@ private:
bool AnyMotorStalled(size_t drive) const pre(drive < DRIVES);
#endif
+#if SAM4E || SAM4S || SAME70
+ void PrintUniqueId(MessageType mtype);
+#endif
+
// These are the structures used to hold our non-volatile data.
// The SAM3X and SAM4E don't have EEPROM so we save the data to flash. This unfortunately means that it gets cleared
// every time we reprogram the firmware via bossa, but it can be retained when firmware updates are performed
@@ -650,7 +641,7 @@ private:
}
};
-#if SAM4E || SAM4S
+#if SAM4E || SAM4S || SAME70
static_assert(SoftwareResetData::numberOfSlots * sizeof(SoftwareResetData) <= 512, "Can't fit software reset data in SAM4 user signature area");
#else
static_assert(SoftwareResetData::numberOfSlots * sizeof(SoftwareResetData) <= FLASH_DATA_LENGTH, "NVData too large");
diff --git a/src/RepRapFirmware.h b/src/RepRapFirmware.h
index 33e8023d..ae8f7dd3 100644
--- a/src/RepRapFirmware.h
+++ b/src/RepRapFirmware.h
@@ -116,6 +116,9 @@ void ListDrivers(const StringRef& str, DriversBitmap drivers);
// Macro to assign an array from an initialiser list
#define ARRAY_INIT(_dest, _init) static_assert(sizeof(_dest) == sizeof(_init), "Incompatible array types"); memcpy(_dest, _init, sizeof(_init));
+// UTF8 code for the degree-symbol
+#define DEGREE_SYMBOL "\xC2\xB0" // Unicode degree-symbol as UTF8
+
// Classes to facilitate range-based for loops that iterate from 0 up to just below a limit
template<class T> class SimpleRangeIterator
{
@@ -217,11 +220,16 @@ typedef uint32_t FilePosition;
const FilePosition noFilePosition = 0xFFFFFFFF;
// Interrupt priorities - must be chosen with care! 0 is the highest priority, 15 is the lowest.
-const uint32_t NvicPriorityUart = 1; // UART is highest to avoid character loss (it has only a 1-character receive buffer)
+#if SAM4E || SAME70
+const uint32_t NvicPriorityWatchdog = 0; // the secondary watchdog has the highest priority
+#endif
+
+const uint32_t NvicPriorityPanelDueUart = 1; // UART is highest to avoid character loss (it has only a 1-character receive buffer)
const uint32_t NvicPriorityDriversUsart = 2; // USART used to control and monitor the TMC2660 drivers
const uint32_t NvicPrioritySystick = 3; // systick kicks the watchdog and starts the ADC conversions, so must be quite high
const uint32_t NvicPriorityPins = 4; // priority for GPIO pin interrupts - filament sensors must be higher than step
const uint32_t NvicPriorityStep = 5; // step interrupt is next highest, it can preempt most other interrupts
+const uint32_t NvicPriorityWiFiUart = 6; // UART used to receive debug data from the WiFi module
const uint32_t NvicPriorityUSB = 6; // USB interrupt
#if HAS_LWIP_NETWORKING
diff --git a/src/Version.h b/src/Version.h
index d88d8b27..474456d4 100644
--- a/src/Version.h
+++ b/src/Version.h
@@ -9,11 +9,11 @@
#define SRC_VERSION_H_
#ifndef VERSION
-# define VERSION "1.20beta10"
+# define VERSION "1.20beta11"
#endif
#ifndef DATE
-# define DATE "2017-11-23"
+# define DATE "2017-11-28"
#endif
#define AUTHORS "reprappro, dc42, chrishamm, t3p3, dnewman"