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
diff options
context:
space:
mode:
authorDavid Crocker <dcrocker@eschertech.com>2018-11-28 15:32:07 +0300
committerDavid Crocker <dcrocker@eschertech.com>2018-11-28 15:32:07 +0300
commit6e457735157a8cb452cc244f866fb1c083c7b48b (patch)
tree94ebb48ba5a7f1541e602bd6b29f607779671770
parent7e8d23525e40ecdc303eb12e474732ef32b926e9 (diff)
Version 2.02RC52.02RC5
Shortened M591 filament monitor reports Added filament detection state to M591 report for simple filament sensor Tool offsets are no longer applied when G54 is in effect M500 saves workplace coordinates Implemented M851 for Marlin compatibility Added check for NaNs when computing derivatives during auto calibration Scara printers can now xo XY moves before Z has been homed Don't allow M291 to create messatge popups that can never time out or be dismissed
-rw-r--r--.cproject1
-rw-r--r--src/BugList.txt41
-rw-r--r--src/Duet/Pins_Duet.h15
-rw-r--r--src/FilamentMonitors/FilamentMonitor.cpp2
-rw-r--r--src/FilamentMonitors/LaserFilamentMonitor.cpp8
-rw-r--r--src/FilamentMonitors/RotatingMagnetFilamentMonitor.cpp8
-rw-r--r--src/FilamentMonitors/SimpleFilamentMonitor.cpp7
-rw-r--r--src/GCodes/GCodeMachineState.h3
-rw-r--r--src/GCodes/GCodes.cpp65
-rw-r--r--src/GCodes/GCodes.h3
-rw-r--r--src/GCodes/GCodes2.cpp31
-rw-r--r--src/GCodes/GCodes3.cpp43
-rw-r--r--src/Movement/Kinematics/LinearDeltaKinematics.cpp8
-rw-r--r--src/Movement/Kinematics/ScaraKinematics.cpp6
-rw-r--r--src/RADDS/Pins_RADDS.h60
-rw-r--r--src/Version.h2
16 files changed, 185 insertions, 118 deletions
diff --git a/.cproject b/.cproject
index 2e255be2..ddebf312 100644
--- a/.cproject
+++ b/.cproject
@@ -99,6 +99,7 @@
<listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/src/Duet}&quot;"/>
<listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/src/Duet/Lwip}&quot;"/>
<listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/src/Duet/EMAC}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/RRFLibraries/src}&quot;"/>
</option>
<option id="gnu.cpp.compiler.option.preprocessor.def.1548770846" name="Defined symbols (-D)" superClass="gnu.cpp.compiler.option.preprocessor.def" useByScannerDiscovery="false" valueType="definedSymbols">
<listOptionValue builtIn="false" value="__SAM3X8E__"/>
diff --git a/src/BugList.txt b/src/BugList.txt
index fb884a97..4d01c50d 100644
--- a/src/BugList.txt
+++ b/src/BugList.txt
@@ -159,33 +159,34 @@ Failed tests:
- [fixed, ok] M557 with even P parameter on circular bed does too few points
- [bad connection on hot end] Crane Quad hot end reads about 60C at room temperature
-To be fixed in 2.02 release:
-- [can't reproduce] Investigate macros causing a hang, https://forum.duet3d.com/topic/7782/issues-with-macros-halting-the-printer/11
+To be investigated for 2.02RC5 or release:
+- [tested, ok] Test error handling when the mesh is badly defined, https://forum.duet3d.com/topic/7759/solved-duet-2-wifi-java-error/10
+- [review M292 handling, even though can't reproduce - I can't see a problem] Investigate macros causing a hang, https://forum.duet3d.com/topic/7782/issues-with-macros-halting-the-printer/11
- [can't reproduce] re-test M226, https://forum.duet3d.com/topic/7747/reprapfirmware-2-02rc4-released/29
-- investigate incorrect layer count, https://forum.duet3d.com/topic/7747/reprapfirmware-2-02rc4-released/31
-- investigate slow movement, https://forum.duet3d.com/topic/6974/problem-with-3-independent-z-axis-motors-and-endstops/32
+- [was caused by spurious E0 in an travel move] investigate incorrect layer count, https://forum.duet3d.com/topic/7747/reprapfirmware-2-02rc4-released/31
+- [probing speed was too high] Multiple G29 commands in succession, https://forum.duet3d.com/topic/7920/bed-compensation-g29-problems
+- [may be fixed by possible fix for for Z and U moving at different speeds] investigate slow movement, https://forum.duet3d.com/topic/6974/problem-with-3-independent-z-axis-motors-and-endstops/32
+
+To be fixed in 2.02RC5:
- [done, ok] 12864 display of speed factor wrong, https://forum.duet3d.com/topic/7747/reprapfirmware-2-02rc4-released/10
- [done, ok] 12864 button menu handling wrong, https://forum.duet3d.com/topic/7747/reprapfirmware-2-02rc4-released/14
-- [tested, ok] Test error handling when the mesh is badly defined, https://forum.duet3d.com/topic/7759/solved-duet-2-wifi-java-error/10
+- [done, ok] 12864 items 510- display user position not machine position
+- [done, ok] M117 on 12864, https://forum.duet3d.com/topic/7826/display-characters-text-in-macro/4
+- [done, ok] M291 and manual Z-probing on 12864, https://forum.duet3d.com/topic/7826/display-characters-text-in-macro/4
+- [done, ok] Live XYZ movement and baby stepping on 12864
- [done, retest] Change "Resume-after-power-fail state saved" message to something appropriate for an ordinary pause, https://forum.duet3d.com/topic/7784/power-fail-triggers-unexpectedly/3
- [done, ok] SCARA: after prox and distal are homed allow XY moves, https://forum.duet3d.com/topic/7747/reprapfirmware-2-02rc4-released/24
-- [done, test] Support M851, offset is negated + using M851 causes M500 to save Z probe parameters
-- [done, test] If G31 parameters were read from config-override.g (m501) then a subsequent M500 command saves them too
-- [done, retest] Save workplace coordinate systems in M500
-- [done, retest] Shorten M591 response by removing unnecessary text
-- [done, test] When delta auto calibration produces NaNs, abort calibration and emit an error message suggesting a smaller probing radius
-- [done, test] M106 Pnn Svv always set full PWM if vv > 1 and there were additional parameters e.g. F, https://forum.duet3d.com/topic/7810/question-about-m106/6
+- [done, ok] Support M851, offset is negated + using M851 causes M500 to save Z probe parameters
+- [done, ok] If G31 parameters were read from config-override.g (m501) then a subsequent M500 command saves them too
+- [done, ok] Save workplace coordinate systems in M500
+- [done, ok] Shorten M591 response by removing unnecessary text
+- [done, can't test] When delta auto calibration produces NaNs, abort calibration and emit an error message suggesting a smaller probing radius
+- [done, ok] M106 Pnn Svv always set full PWM if vv > 1 and there were additional parameters e.g. F, https://forum.duet3d.com/topic/7810/question-about-m106/6
- [done] Possible fix for Z and U moving at different speeds, https://forum.duet3d.com/topic/7755/drive-3-is-slower-as-drive-2-at-homing-in-z-solved/32
-- [done, test] For SimpleFilamentMonitor, include filament present/not present status in M591 report
-- [done, ok] M117 on 12864, https://forum.duet3d.com/topic/7826/display-characters-text-in-macro/4
-- [done, test] M291 and manual Z-probing on 12864? https://forum.duet3d.com/topic/7826/display-characters-text-in-macro/4
+- [done, ok] For SimpleFilamentMonitor, include filament present/not present status in M591 report
- [done, ok] Heater turn on momentarily when Duet is reset
-- [done, test] When G53 is in effect, don't apply tool offsets or axis mapping
-- Don't alow both S0 and T0 in M291, it creates a message that can't be dismissed
-
-Test failures:
-- M291 T"title" P"message" S0 creates a messasge that can't be dismissed
-- M291 not working on 12864, clears rectangular area but that's all
+- [done, ok] When G53 is in effect, don't apply tool offsets or axis mapping
+- [done, ok] Don't alow both S0 and T0 in M291, it creates a message that can't be dismissed
Future:
- Option for an endstop input to trigger an emergency pause
diff --git a/src/Duet/Pins_Duet.h b/src/Duet/Pins_Duet.h
index 322840ae..aee21a07 100644
--- a/src/Duet/Pins_Duet.h
+++ b/src/Duet/Pins_Duet.h
@@ -24,9 +24,8 @@ constexpr size_t NumFirmwareUpdateModules = 1;
#define SUPPORT_DHT_SENSOR 0 // set nonzero to support DHT temperature/humidity sensors
// The physical capabilities of the machine
-
-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 }
+constexpr size_t NumDirectDrivers = 9;
+constexpr size_t MaxTotalDrivers = NumDirectDrivers;
constexpr size_t NumEndstops = 9; // The number of inputs we have for endstops, filament sensors etc.
constexpr size_t NumHeaters = 7; // The number of heaters in the machine; 0 is the heated bed even if there isn't one
@@ -35,10 +34,8 @@ constexpr size_t NumThermistorInputs = 7;
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 }
-constexpr size_t MaxExtruders = DRIVES - MinAxes; // The maximum number of extruders
+constexpr size_t MaxExtruders = NumDirectDrivers - MinAxes; // The maximum number of extruders
constexpr size_t MaxDriversPerAxis = 4; // The maximum number of stepper drivers assigned to one axis
constexpr size_t NUM_SERIAL_CHANNELS = 3; // The number of serial IO channels (USB and two auxiliary UARTs)
@@ -53,9 +50,9 @@ constexpr size_t NUM_SERIAL_CHANNELS = 3; // The number of serial IO channels
// Drives
-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 };
+constexpr Pin ENABLE_PINS[NumDirectDrivers] = { 29, 27, X1, X0, 37, X8, 50, 47, X13 };
+constexpr Pin STEP_PINS[NumDirectDrivers] = { 14, 25, 5, X2, 41, 39, X4, 49, X10 };
+constexpr Pin DIRECTION_PINS[NumDirectDrivers] = { 15, 26, 4, X3, 35, 53, 51, 48, X11 };
// Endstops
// RepRapFirmware only has a single endstop per axis.
diff --git a/src/FilamentMonitors/FilamentMonitor.cpp b/src/FilamentMonitors/FilamentMonitor.cpp
index a9482654..34b05bba 100644
--- a/src/FilamentMonitors/FilamentMonitor.cpp
+++ b/src/FilamentMonitors/FilamentMonitor.cpp
@@ -116,7 +116,7 @@ bool FilamentMonitor::ConfigurePin(GCodeBuffer& gb, const StringRef& reply, Inte
}
else if (!seen)
{
- reply.printf("Extruder drive %u has no filament sensor", extruder);
+ reply.printf("Extruder %u has no filament sensor", extruder);
}
return GCodeResult::ok;
}
diff --git a/src/FilamentMonitors/LaserFilamentMonitor.cpp b/src/FilamentMonitors/LaserFilamentMonitor.cpp
index 7fd72e2f..7ab5ba7e 100644
--- a/src/FilamentMonitors/LaserFilamentMonitor.cpp
+++ b/src/FilamentMonitors/LaserFilamentMonitor.cpp
@@ -75,8 +75,8 @@ bool LaserFilamentMonitor::Configure(GCodeBuffer& gb, const StringRef& reply, bo
}
else
{
- reply.printf("Duet3D laser filament monitor%s on endstop input %u, %s, allowed movement %ld%% to %ld%%, check every %.1fmm, ",
- (switchOpenMask != 0) ? " with microswitch" : "",
+ reply.printf("Duet3D laser filament monitor%s on input %u, %s, allow %ld%% to %ld%%, check every %.1fmm, ",
+ (switchOpenMask != 0) ? " with switch" : "",
GetEndstopNumber(),
(comparisonEnabled) ? "enabled" : "disabled",
lrintf(minMovementAllowed * 100.0),
@@ -93,10 +93,10 @@ bool LaserFilamentMonitor::Configure(GCodeBuffer& gb, const StringRef& reply, bo
}
else
{
- reply.catf("current position %.1f, brightness %u, shutter %u, ", (double)GetCurrentPosition(), qualityWord & 0x00FF, (qualityWord >> 8) & 0x3F);
+ reply.catf("current pos %.1f, brightness %u, shutter %u, ", (double)GetCurrentPosition(), qualityWord & 0x00FF, (qualityWord >> 8) & 0x3F);
if (laserMonitorState != LaserMonitorState::calibrating && totalExtrusionCommanded > 10.0)
{
- reply.catf("measured minimum %ld%%, average %ld%%, maximum %ld%% over %.1fmm",
+ reply.catf("measured min %ld%% avg %ld%% max %ld%% over %.1fmm",
lrintf(100 * minMovementRatio),
lrintf((100 * totalMovementMeasured)/totalExtrusionCommanded),
lrintf(100 * maxMovementRatio),
diff --git a/src/FilamentMonitors/RotatingMagnetFilamentMonitor.cpp b/src/FilamentMonitors/RotatingMagnetFilamentMonitor.cpp
index 1d378d89..6d624509 100644
--- a/src/FilamentMonitors/RotatingMagnetFilamentMonitor.cpp
+++ b/src/FilamentMonitors/RotatingMagnetFilamentMonitor.cpp
@@ -77,8 +77,8 @@ bool RotatingMagnetFilamentMonitor::Configure(GCodeBuffer& gb, const StringRef&
}
else
{
- reply.printf("Duet3D rotating magnet filament monitor%s on endstop input %u, %s, sensitivity %.2fmm/rev, allowed movement %ld%% to %ld%%, check every %.1fmm, ",
- (switchOpenMask != 0) ? " with microswitch" : "",
+ reply.printf("Duet3D rotating magnet filament monitor%s on input %u, %s, sensitivity %.2fmm/rev, allow %ld%% to %ld%%, check every %.1fmm, ",
+ (switchOpenMask != 0) ? " with switch" : "",
GetEndstopNumber(),
(comparisonEnabled) ? "enabled" : "disabled",
(double)mmPerRev,
@@ -95,11 +95,11 @@ bool RotatingMagnetFilamentMonitor::Configure(GCodeBuffer& gb, const StringRef&
}
else
{
- reply.catf("current position %.1f, ", (double)GetCurrentPosition());
+ reply.catf("current pos %.1f, ", (double)GetCurrentPosition());
if (calibrationStarted && fabsf(totalMovementMeasured) > 1.0 && totalExtrusionCommanded > 20.0)
{
const float measuredMmPerRev = totalExtrusionCommanded/totalMovementMeasured;
- reply.catf("measured sensitivity %.2fmm/rev, measured minimum %ld%%, maximum %ld%% over %.1fmm\n",
+ reply.catf("measured sensitivity %.2fmm/rev, min %ld%% max %ld%% over %.1fmm\n",
(double)measuredMmPerRev,
lrintf(100 * minMovementRatio),
lrintf(100 * maxMovementRatio),
diff --git a/src/FilamentMonitors/SimpleFilamentMonitor.cpp b/src/FilamentMonitors/SimpleFilamentMonitor.cpp
index 7b0f1b57..558e3430 100644
--- a/src/FilamentMonitors/SimpleFilamentMonitor.cpp
+++ b/src/FilamentMonitors/SimpleFilamentMonitor.cpp
@@ -35,8 +35,11 @@ bool SimpleFilamentMonitor::Configure(GCodeBuffer& gb, const StringRef& reply, b
}
else
{
- reply.printf("Simple filament sensor on endstop %d, %s, output %s when no filament",
- GetEndstopNumber(), (enabled) ? "enabled" : "disabled", (highWhenNoFilament) ? "high" : "low");
+ reply.printf("Simple filament sensor on endstop %d, %s, output %s when no filament, filament present: %s",
+ GetEndstopNumber(),
+ (enabled) ? "enabled" : "disabled",
+ (highWhenNoFilament) ? "high" : "low",
+ (filamentPresent) ? "yes" : "no");
}
return false;
diff --git a/src/GCodes/GCodeMachineState.h b/src/GCodes/GCodeMachineState.h
index 40351fda..7e015aea 100644
--- a/src/GCodes/GCodeMachineState.h
+++ b/src/GCodes/GCodeMachineState.h
@@ -119,6 +119,9 @@ public:
static GCodeMachineState *Allocate()
post(!result.IsLive(); result.state == GCodeState::normal);
+ // Return true if the G54 command is in effect
+ bool UsingG54() const { return useMachineCoordinates || useMachineCoordinatesSticky; }
+
// Copy values that may have been altered by config.g into this state record
void CopyStateFrom(const GCodeMachineState& other)
{
diff --git a/src/GCodes/GCodes.cpp b/src/GCodes/GCodes.cpp
index e6ef6b65..38590f75 100644
--- a/src/GCodes/GCodes.cpp
+++ b/src/GCodes/GCodes.cpp
@@ -2187,7 +2187,7 @@ void GCodes::SaveResumeInfo(bool wasPowerFailure)
}
if (ok)
{
- platform.Message(LoggedGenericMessage, "Resume-after-power-fail state saved\n");
+ platform.Message(LoggedGenericMessage, "Resume state saved\n");
}
else
{
@@ -2424,17 +2424,20 @@ const char* GCodes::DoStraightMove(GCodeBuffer& gb, bool isCoordinated)
if (gb.Seen('H') || (machineType != MachineType::laser && gb.Seen('S')))
{
const int ival = gb.GetIValue();
- if (ival == 1 || ival == 2 || ival == 3)
+ if (ival >= 1 && ival <= 3)
{
moveBuffer.moveType = ival;
moveBuffer.xAxes = DefaultXAxisMapping;
moveBuffer.yAxes = DefaultYAxisMapping;
}
- else if (ival == 99) // temporary code to log Z probe change positions
- {
- moveBuffer.endStopsToCheck |= LogProbeChanges;
- }
}
+#if SUPPORT_WORKPLACE_COORDINATES
+ else if (gb.MachineState().UsingG54())
+ {
+ moveBuffer.xAxes = DefaultXAxisMapping;
+ moveBuffer.yAxes = DefaultYAxisMapping;
+ }
+#endif
// Check for 'R' parameter to move relative to a restore point
const RestorePoint * rp = nullptr;
@@ -2490,7 +2493,7 @@ const char* GCodes::DoStraightMove(GCodeBuffer& gb, bool isCoordinated)
#endif
#endif
- if (moveBuffer.moveType != 0)
+ if (moveBuffer.moveType != 0 || gb.MachineState().UsingG54())
{
// This may be a raw motor move, in which case we need the current raw motor positions in moveBuffer.coords.
// If it isn't a raw motor move, it will still be applied without axis or bed transform applied,
@@ -2517,7 +2520,7 @@ const char* GCodes::DoStraightMove(GCodeBuffer& gb, bool isCoordinated)
SetBit(axesMentioned, axis);
const float moveArg = gb.GetFValue() * distanceScale;
- if (moveBuffer.moveType != 0)
+ if (moveBuffer.moveType != 0 || gb.MachineState().UsingG54())
{
if (gb.MachineState().axesRelative)
{
@@ -2536,12 +2539,6 @@ const char* GCodes::DoStraightMove(GCodeBuffer& gb, bool isCoordinated)
{
currentUserPosition[axis] += moveArg;
}
-#if SUPPORT_WORKPLACE_COORDINATES
- else if (gb.MachineState().useMachineCoordinates || gb.MachineState().useMachineCoordinatesSticky)
- {
- currentUserPosition[axis] = moveArg - workplaceCoordinates[currentCoordinateSystem][axis];
- }
-#endif
else
{
currentUserPosition[axis] = moveArg;
@@ -2589,12 +2586,20 @@ const char* GCodes::DoStraightMove(GCodeBuffer& gb, bool isCoordinated)
}
else
{
- if (&gb == fileGCode && !gb.IsDoingFileMacro() && moveBuffer.hasExtrusion && (axesMentioned & ((1 << X_AXIS) | (1 << Y_AXIS))) != 0)
+ if (gb.MachineState().UsingG54())
{
- lastPrintingMoveHeight = currentUserPosition[Z_AXIS];
+ gb.SetState(GCodeState::waitingForSpecialMoveToComplete); // we need to update the user coordinates after the move
+ }
+ else
+ {
+ if (&gb == fileGCode && !gb.IsDoingFileMacro() && moveBuffer.hasExtrusion && (axesMentioned & ((1 << X_AXIS) | (1 << Y_AXIS))) != 0)
+ {
+ lastPrintingMoveHeight = currentUserPosition[Z_AXIS];
+ }
+
+ ToolOffsetTransform(currentUserPosition, moveBuffer.coords, axesMentioned); // apply tool offset, axis mapping, baby stepping, Z hop and axis scaling
}
- ToolOffsetTransform(currentUserPosition, moveBuffer.coords, axesMentioned); // apply tool offset, axis mapping, baby stepping, Z hop and axis scaling
AxesBitmap effectiveAxesHomed = axesHomed;
if (doingManualBedProbe)
{
@@ -2629,7 +2634,7 @@ const char* GCodes::DoStraightMove(GCodeBuffer& gb, bool isCoordinated)
const float moveTime = xyLength/moveBuffer.feedRate; // this is a best-case time, often the move will take longer
totalSegments = (unsigned int)max<int>(1, min<int>(rintf(xyLength/kin.GetMinSegmentLength()), rintf(moveTime * kin.GetSegmentsPerSecond())));
}
- else if (reprap.GetMove().IsUsingMesh())
+ else if (reprap.GetMove().IsUsingMesh() && (isCoordinated || machineType == MachineType::fff))
{
const HeightMap& heightMap = reprap.GetMove().AccessHeightMap();
totalSegments = max<unsigned int>(1, heightMap.GetMinimumSegments(currentUserPosition[X_AXIS] - initialX, currentUserPosition[Y_AXIS] - initialY));
@@ -2714,13 +2719,6 @@ const char* GCodes::DoArcMove(GCodeBuffer& gb, bool clockwise)
currentUserPosition[X_AXIS] += xParam;
currentUserPosition[Y_AXIS] += yParam;
}
-#if SUPPORT_WORKPLACE_COORDINATES
- else if (gb.MachineState().useMachineCoordinates || gb.MachineState().useMachineCoordinatesSticky)
- {
- currentUserPosition[X_AXIS] = xParam - workplaceCoordinates[currentCoordinateSystem][X_AXIS];
- currentUserPosition[Y_AXIS] = yParam - workplaceCoordinates[currentCoordinateSystem][Y_AXIS];
- }
-#endif
else
{
currentUserPosition[X_AXIS] = xParam;
@@ -4747,6 +4745,13 @@ GCodeResult GCodes::WriteConfigOverrideFile(GCodeBuffer& gb, const StringRef& re
ok = reprap.WriteToolParameters(f);
}
+#if SUPPORT_WORKPLACE_COORDINATES
+ if (ok)
+ {
+ ok = WriteWorkplaceCoordinates(f);
+ }
+#endif
+
if (!f->Close())
{
ok = false;
@@ -5089,24 +5094,24 @@ void GCodes::CheckHeaterFault()
}
}
-// Return the current speed factor
+// Return the current speed factor as a percentage
float GCodes::GetSpeedFactor() const
{
return speedFactor;
}
-// Return a current extrusion factor
+// Return a current extrusion factor as a percentage
float GCodes::GetExtrusionFactor(size_t extruder)
{
- return (extruder < numExtruders) ? extrusionFactors[extruder] : 0.0;
+ return (extruder < numExtruders) ? extrusionFactors[extruder] * 100.0 : 0.0;
}
-// Set an extrusion factor
+// Set a percentage extrusion factor
void GCodes::SetExtrusionFactor(size_t extruder, float factor)
{
if (extruder < numExtruders)
{
- extrusionFactors[extruder] = constrain<float>(factor, 0.0, 2.0);
+ extrusionFactors[extruder] = constrain<float>(factor, 0.0, 200.0)/100.0;
}
}
diff --git a/src/GCodes/GCodes.h b/src/GCodes/GCodes.h
index 031ba297..059cf400 100644
--- a/src/GCodes/GCodes.h
+++ b/src/GCodes/GCodes.h
@@ -309,6 +309,7 @@ private:
#if SUPPORT_WORKPLACE_COORDINATES
GCodeResult GetSetWorkplaceCoordinates(GCodeBuffer& gb, const StringRef& reply, bool compute); // Set workspace coordinates
+ bool WriteWorkplaceCoordinates(FileStore *f) const;
#endif
GCodeResult SetHeaterProtection(GCodeBuffer &gb, const StringRef &reply); // Configure heater protection (M143)
@@ -504,7 +505,7 @@ private:
float pausedFanSpeeds[NUM_FANS]; // Fan speeds when the print was paused or a tool change started
float lastDefaultFanSpeed; // Last speed given in a M106 command with on fan number
float pausedDefaultFanSpeed; // The speed of the default print cooling fan when the print was paused or a tool change started
- float speedFactor; // speed factor, including the conversion from mm/min to mm/sec, normally 1/60
+ float speedFactor; // speed factor as a percentage (normally 100.0)
float extrusionFactors[MaxExtruders]; // extrusion factors (normally 1.0)
float volumetricExtrusionFactors[MaxExtruders]; // Volumetric extrusion factors
float currentBabyStepZOffset; // The accumulated Z offset due to baby stepping requests
diff --git a/src/GCodes/GCodes2.cpp b/src/GCodes/GCodes2.cpp
index a14c2e49..1ef0c8d1 100644
--- a/src/GCodes/GCodes2.cpp
+++ b/src/GCodes/GCodes2.cpp
@@ -2193,12 +2193,13 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
case 291: // Display message, optionally wait for acknowledgement
{
- String<MaxMessageLength> title;
bool seen = false;
+ String<MaxMessageLength> title;
gb.TryGetQuotedString('R', title.GetRef(), seen);
String<MaxMessageLength> message;
gb.TryGetQuotedString('P', message.GetRef(), seen);
+
if (seen)
{
int32_t sParam = 1;
@@ -2226,6 +2227,13 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
tParam = 0.0;
}
+ if (sParam == 0 && tParam <= 0.0)
+ {
+ reply.copy("Attempt to create a message box that cannot be dismissed");
+ result = GCodeResult::error;
+ break;
+ }
+
AxesBitmap axisControls = 0;
for (size_t axis = 0; axis < numTotalAxes; axis++)
{
@@ -2242,8 +2250,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
gb.MachineState().waitingForAcknowledgement = true; // flag that we are waiting for acknowledgement
}
- // TODO: consider displaying the message box on all relevant devices. Acknowledging any one of them needs to clear them all.
- // Currently, if mt is http or aux or generic, we display the message box both in DWC and on PanelDue.
+ // Display the message box on all relevant devices. Acknowledging any one of them clears them all.
const MessageType mt = GetMessageBoxDevice(gb); // get the display device
platform.SendAlert(mt, message.c_str(), title.c_str(), (int)sParam, tParam, axisControls);
}
@@ -3903,6 +3910,22 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
break;
#endif
+ case 851: // Set Z probe offset, only for Marlin compatibility
+ {
+ ZProbe params = platform.GetCurrentZProbeParameters();
+ if (gb.Seen('Z'))
+ {
+ params.triggerHeight = -gb.GetFValue();
+ params.saveToConfigOverride = true;
+ platform.SetZProbeParameters(platform.GetZProbeType(), params);
+ }
+ else
+ {
+ reply.printf("Z probe offset is %.2fmm", (double)(-params.triggerHeight));
+ }
+ }
+ break;
+
case 905: // Set current RTC date and time
result = SetDateTime(gb, reply);
break;
@@ -4223,7 +4246,7 @@ bool GCodes::HandleResult(GCodeBuffer& gb, GCodeResult rslt, const StringRef& re
{
if (outBuf != nullptr)
{
- // We only have an OutputBuffer when rslt == GCodeResult::ok
+ // We only ever have an OutputBuffer when rslt == GCodeResult::ok
gb.timerRunning = false;
UnlockAll(gb);
HandleReply(gb, outBuf);
diff --git a/src/GCodes/GCodes3.cpp b/src/GCodes/GCodes3.cpp
index bf5f8acd..0eb7120b 100644
--- a/src/GCodes/GCodes3.cpp
+++ b/src/GCodes/GCodes3.cpp
@@ -61,7 +61,11 @@ GCodeResult GCodes::SetPrintZProbe(GCodeBuffer& gb, const StringRef& reply)
gb.TryGetFValue(axisLetters[X_AXIS], params.xOffset, seen);
gb.TryGetFValue(axisLetters[Y_AXIS], params.yOffset, seen);
gb.TryGetFValue(axisLetters[Z_AXIS], params.triggerHeight, seen);
- gb.TryGetIValue('P', params.adcValue, seen);
+ if (gb.Seen('P'))
+ {
+ seen = true;
+ params.adcValue = gb.GetIValue();
+ }
if (gb.Seen('C'))
{
@@ -84,12 +88,16 @@ GCodeResult GCodes::SetPrintZProbe(GCodeBuffer& gb, const StringRef& reply)
{
return GCodeResult::notFinished;
}
+ if (gb.MachineState().runningM501)
+ {
+ params.saveToConfigOverride = true; // we are loading these parameters from config-override.g, so a subsequent M500 should save them to config-override.g
+ }
platform.SetZProbeParameters(probeType, params);
}
else if (seenT)
{
// Don't bother printing temperature coefficient and calibration temperature because we will probably remove them soon
- reply.printf("Threshold %" PRIi32 ", trigger height %.2f, offsets X%.1f Y%.1f", params.adcValue, (double)params.triggerHeight, (double)params.xOffset, (double)params.yOffset);
+ reply.printf("Threshold %d, trigger height %.2f, offsets X%.1f Y%.1f", params.adcValue, (double)params.triggerHeight, (double)params.xOffset, (double)params.yOffset);
}
else
{
@@ -266,6 +274,26 @@ GCodeResult GCodes::GetSetWorkplaceCoordinates(GCodeBuffer& gb, const StringRef&
return GCodeResult::badOrMissingParameter;
}
+// Save any modified workplace coordinate offsets to file returning true if successful. Used by M500.
+bool GCodes::WriteWorkplaceCoordinates(FileStore *f) const
+{
+ for (size_t cs = 0; cs < NumCoordinateSystems; ++cs)
+ {
+ String<ScratchStringLength> scratchString;
+ scratchString.printf("G10 L2 P%u", cs + 1);
+ for (size_t axis = 0; axis < numVisibleAxes; ++axis)
+ {
+ scratchString.catf(" %c%.2f", axisLetters[axis], (double)workplaceCoordinates[cs][axis]);
+ }
+ scratchString.cat('\n');
+ if (!f->Write(scratchString.c_str()))
+ {
+ return false;
+ }
+ }
+ return true;
+}
+
#endif
// Define the probing grid, called when we see an M557 command
@@ -549,7 +577,7 @@ GCodeResult GCodes::SetOrReportZProbe(GCodeBuffer& gb, const StringRef &reply)
if (gb.Seen('A'))
{
- params.maxTaps = gb.GetUIValue();
+ params.maxTaps = min<uint32_t>(gb.GetUIValue(), ZProbe::MaxTapsLimit);
seen = true;
}
@@ -695,7 +723,6 @@ GCodeResult GCodes::DoDriveMapping(GCodeBuffer& gb, const StringRef& reply)
uint32_t drivers[MaxDriversPerAxis];
gb.GetUnsignedArray(drivers, numValues, false);
- // Check all the driver numbers are in range
AxisDriversConfig config;
config.numDrivers = numValues;
for (size_t i = 0; i < numValues; ++i)
@@ -718,8 +745,8 @@ GCodeResult GCodes::DoDriveMapping(GCodeBuffer& gb, const StringRef& reply)
currentUserPosition[drive] = 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
+ reprap.GetMove().SetNewPosition(moveBuffer.coords, true); // tell the Move system where the new axis is
}
- reprap.GetMove().SetNewPosition(moveBuffer.coords, true); // tell the Move system where any new axes are
platform.SetAxisDriversConfig(drive, config);
if (numTotalAxes + numExtruders > MaxTotalDrivers)
{
@@ -746,10 +773,10 @@ GCodeResult GCodes::DoDriveMapping(GCodeBuffer& gb, const StringRef& reply)
if (gb.Seen('P'))
{
seen = true;
- const int nva = gb.GetIValue();
- if (nva >= (int)MinAxes && (unsigned int)nva <= numTotalAxes)
+ const unsigned int nva = gb.GetUIValue();
+ if (nva >= MinAxes && nva <= numTotalAxes)
{
- numVisibleAxes = (size_t)nva;
+ numVisibleAxes = nva;
}
else
{
diff --git a/src/Movement/Kinematics/LinearDeltaKinematics.cpp b/src/Movement/Kinematics/LinearDeltaKinematics.cpp
index 47e5b887..896dfd4c 100644
--- a/src/Movement/Kinematics/LinearDeltaKinematics.cpp
+++ b/src/Movement/Kinematics/LinearDeltaKinematics.cpp
@@ -275,8 +275,14 @@ bool LinearDeltaKinematics::DoAutoCalibration(size_t numFactors, const RandomPro
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) =
+ const floatc_t d =
ComputeDerivative(adjustedJ, probeMotorPositions(i, DELTA_A_AXIS), probeMotorPositions(i, DELTA_B_AXIS), probeMotorPositions(i, DELTA_C_AXIS));
+ if (isnan(d)) // a couple of users have reported getting Nans in the derivative, probably due to points being unreachable
+ {
+ reply.printf("Auto calibration failed because probe point P%u was unreachable using the current delta parameters. Try a smaller probing radius.", i);
+ return true;
+ }
+ derivativeMatrix(i, j) = d;
}
}
diff --git a/src/Movement/Kinematics/ScaraKinematics.cpp b/src/Movement/Kinematics/ScaraKinematics.cpp
index ac0bff98..4ec47dc1 100644
--- a/src/Movement/Kinematics/ScaraKinematics.cpp
+++ b/src/Movement/Kinematics/ScaraKinematics.cpp
@@ -326,10 +326,10 @@ AxesBitmap ScaraKinematics::AxesAssumedHomed(AxesBitmap g92Axes) const
// Return the set of axes that must be homed prior to regular movement of the specified axes
AxesBitmap ScaraKinematics::MustBeHomedAxes(AxesBitmap axesMoving, bool disallowMovesBeforeHoming) const
{
- constexpr AxesBitmap xyzAxes = MakeBitmap<AxesBitmap>(X_AXIS) | MakeBitmap<AxesBitmap>(Y_AXIS) | MakeBitmap<AxesBitmap>(Z_AXIS);
- if ((axesMoving & xyzAxes) != 0)
+ constexpr AxesBitmap xyAxes = MakeBitmap<AxesBitmap>(X_AXIS) | MakeBitmap<AxesBitmap>(Y_AXIS);
+ if ((axesMoving & xyAxes) != 0)
{
- axesMoving |= xyzAxes;
+ axesMoving |= xyAxes;
}
return axesMoving;
}
diff --git a/src/RADDS/Pins_RADDS.h b/src/RADDS/Pins_RADDS.h
index 44f63244..df03c790 100644
--- a/src/RADDS/Pins_RADDS.h
+++ b/src/RADDS/Pins_RADDS.h
@@ -29,7 +29,7 @@ const size_t NumFirmwareUpdateModules = 1;
// The physical capabilities of the machine
// The number of drives in the machine, including X, Y, and Z plus extruder drives
-const size_t NumDirectDrivers = 9;
+constexpr size_t NumDirectDrivers = 9;
constexpr size_t MaxTotalDrivers = NumDirectDrivers;
// The number of heaters in the machine
@@ -56,10 +56,10 @@ constexpr Pin UsbVBusPin = NoPin; // Pin used to monitor VBUS on USB port. N
// The numbers of entries in each array must correspond with the values of DRIVES, AXES, or HEATERS. Set values to NoPin to flag unavailability.
// DRIVES
// X Y Z E1 E2 E3 E4 E5 E6
-const Pin ENABLE_PINS[NumDirectDrivers] = { 26, 22, 15, 62, 65, 49, 37, 31, 68 };
+constexpr Pin ENABLE_PINS[NumDirectDrivers] = { 26, 22, 15, 62, 65, 49, 37, 31, 68 };
// A15 A12 A09 A02 B19 C12 C03 D06 B16
-const Pin STEP_PINS[NumDirectDrivers] = { 24, 17, 2, 61, 64, 51, 35, 29, 67 };
-const Pin DIRECTION_PINS[NumDirectDrivers] = { 23, 16, 3, 60, 63, 53, 33, 27, 66 };
+constexpr Pin STEP_PINS[NumDirectDrivers] = { 24, 17, 2, 61, 64, 51, 35, 29, 67 };
+constexpr Pin DIRECTION_PINS[NumDirectDrivers] = { 23, 16, 3, 60, 63, 53, 33, 27, 66 };
// Endstops
// E Stops not currently used
@@ -74,51 +74,51 @@ const Pin DIRECTION_PINS[NumDirectDrivers] = { 23, 16, 3, 60, 63, 53, 33, 27, 6
//
// This leaves 34, 36, and 38 as spare pins (X, Y, Z max)
-const Pin END_STOP_PINS[NumEndstops] = { 28, 30, 32, 39 };
+constexpr Pin END_STOP_PINS[NumEndstops] = { 28, 30, 32, 39 };
// HEATERS - The bed is assumed to be the at index 0
// Analogue pin numbers
-const Pin TEMP_SENSE_PINS[NumThermistorInputs] = { 4, 0, 1, 2 };
+constexpr Pin TEMP_SENSE_PINS[NumThermistorInputs] = { 4, 0, 1, 2 };
// Heater outputs
// Bed PMW: D7 has hardware PWM so bed has PWM
// h0, h1 PMW: D13 & D12 are on TIOB0 & B8 which are both TC B channels, so they get PWM
// h2 bang-bang: D11 is on TIOA8 which is a TC A channel shared with h1, it gets bang-bang control
-const Pin HEAT_ON_PINS[NumHeaters] = { 7, 13, 12, 11 }; // bed, h0, h1, h2
+constexpr Pin HEAT_ON_PINS[NumHeaters] = { 7, 13, 12, 11 }; // bed, h0, h1, h2
// Default thermistor betas
-const float BED_R25 = 10000.0;
-const float BED_BETA = 4066.0;
-const float BED_SHC = 0.0;
-const float EXT_R25 = 100000.0;
-const float EXT_BETA = 4066.0;
-const float EXT_SHC = 0.0;
+constexpr float BED_R25 = 10000.0;
+constexpr float BED_BETA = 4066.0;
+constexpr float BED_SHC = 0.0;
+constexpr float EXT_R25 = 100000.0;
+constexpr float EXT_BETA = 4066.0;
+constexpr float EXT_SHC = 0.0;
// Thermistor series resistor value in Ohms
-const float THERMISTOR_SERIES_RS = 4700.0;
+constexpr float THERMISTOR_SERIES_RS = 4700.0;
-const size_t MaxSpiTempSensors = 2;
+constexpr size_t MaxSpiTempSensors = 2;
// Digital pins the 31855s have their select lines tied to
-const Pin SpiTempSensorCsPins[MaxSpiTempSensors] = { 38, 36 };
+constexpr Pin SpiTempSensorCsPins[MaxSpiTempSensors] = { 38, 36 };
// Digital pin number that controls the ATX power on/off
-const Pin ATX_POWER_PIN = 40;
+constexpr Pin ATX_POWER_PIN = 40;
// Z Probe pin
// Must be an ADC capable pin. Can be any of the ARM's A/D capable pins even a non-Arduino pin.
-const Pin Z_PROBE_PIN = A5; // RADDS "ADC" pin
+constexpr Pin Z_PROBE_PIN = A5; // RADDS "ADC" pin
// Digital pin number to turn the IR LED on (high) or off (low)
// D34 -- unused X-max on RADDS
-const Pin Z_PROBE_MOD_PIN = 34;
-const Pin DiagPin = NoPin;
+constexpr Pin Z_PROBE_MOD_PIN = 34;
+constexpr Pin DiagPin = NoPin;
// Use a PWM capable pin
-const size_t NUM_FANS = 2;
-const Pin COOLING_FAN_PINS[NUM_FANS] = { 9, 8 }; // Fan 0, Fan 1
+constexpr size_t NUM_FANS = 2;
+constexpr Pin COOLING_FAN_PINS[NUM_FANS] = { 9, 8 }; // Fan 0, Fan 1
// Firmware will attach a FALLING interrupt to this pin
// see FanInterrupt() in Platform.cpp
@@ -128,10 +128,10 @@ constexpr size_t NumTachos = 1;
constexpr Pin TachoPins[NumTachos] = { 25 };
// SD cards
-const size_t NumSdCards = 2;
-const Pin SdCardDetectPins[NumSdCards] = { 14, 14 };
-const Pin SdWriteProtectPins[NumSdCards] = { NoPin, NoPin };
-const Pin SdSpiCSPins[2] = { 87, 77 };
+constexpr size_t NumSdCards = 2;
+constexpr Pin SdCardDetectPins[NumSdCards] = { 14, 14 };
+constexpr Pin SdWriteProtectPins[NumSdCards] = { NoPin, NoPin };
+constexpr Pin SdSpiCSPins[2] = { 87, 77 };
// Definition of which pins we allow to be controlled using M42
// Spare pins on the Arduino Due are
@@ -152,18 +152,18 @@ const Pin SdSpiCSPins[2] = { 87, 77 };
// 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[] =
{
5, 6, 58, 59,
70, 71, 72, 73
};
// 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/Version.h b/src/Version.h
index 06498a06..e22999ec 100644
--- a/src/Version.h
+++ b/src/Version.h
@@ -22,7 +22,7 @@
#endif
#ifndef DATE
-# define DATE "2018-11-26b3"
+# define DATE "2018-11-28b1"
#endif
#define AUTHORS "reprappro, dc42, chrishamm, t3p3, dnewman, printm3d"