Version 1.17 dev 4
Support concurrenrt execution of commands form different channels M143 now supports individual temperature limits per heater Fixed issue with dely of up to 2 seconds when switching Duet WiFi heater channel 3 to servo mode When enable polarity is set using the M569 R parameter, disable the corresponding drive Add exdperimental S99 option on G1 command to log probe changes (Duet WiFi only)
This commit is contained in:
parent
57d257447d
commit
88e3092b78
25 changed files with 1791 additions and 1399 deletions
|
@ -5,7 +5,7 @@
|
|||
<provider copy-of="extension" id="org.eclipse.cdt.ui.UserLanguageSettingsProvider"/>
|
||||
<provider-reference id="org.eclipse.cdt.core.ReferencedProjectsLanguageSettingsProvider" ref="shared-provider"/>
|
||||
<provider-reference id="org.eclipse.cdt.managedbuilder.core.MBSLanguageSettingsProvider" ref="shared-provider"/>
|
||||
<provider class="org.eclipse.cdt.internal.build.crossgcc.CrossGCCBuiltinSpecsDetector" console="false" env-hash="337623625225680352" id="org.eclipse.cdt.build.crossgcc.CrossGCCBuiltinSpecsDetector" keep-relative-paths="false" name="CDT Cross GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD "${INPUTS}"" prefer-non-shared="true">
|
||||
<provider class="org.eclipse.cdt.internal.build.crossgcc.CrossGCCBuiltinSpecsDetector" console="false" env-hash="-303428918971435778" id="org.eclipse.cdt.build.crossgcc.CrossGCCBuiltinSpecsDetector" keep-relative-paths="false" name="CDT Cross GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD "${INPUTS}"" prefer-non-shared="true">
|
||||
<language-scope id="org.eclipse.cdt.core.gcc"/>
|
||||
<language-scope id="org.eclipse.cdt.core.g++"/>
|
||||
</provider>
|
||||
|
@ -16,7 +16,7 @@
|
|||
<provider copy-of="extension" id="org.eclipse.cdt.ui.UserLanguageSettingsProvider"/>
|
||||
<provider-reference id="org.eclipse.cdt.core.ReferencedProjectsLanguageSettingsProvider" ref="shared-provider"/>
|
||||
<provider-reference id="org.eclipse.cdt.managedbuilder.core.MBSLanguageSettingsProvider" ref="shared-provider"/>
|
||||
<provider class="org.eclipse.cdt.internal.build.crossgcc.CrossGCCBuiltinSpecsDetector" console="false" env-hash="337623625225680352" id="org.eclipse.cdt.build.crossgcc.CrossGCCBuiltinSpecsDetector" keep-relative-paths="false" name="CDT Cross GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD "${INPUTS}"" prefer-non-shared="true">
|
||||
<provider class="org.eclipse.cdt.internal.build.crossgcc.CrossGCCBuiltinSpecsDetector" console="false" env-hash="-303428918971435778" id="org.eclipse.cdt.build.crossgcc.CrossGCCBuiltinSpecsDetector" keep-relative-paths="false" name="CDT Cross GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD "${INPUTS}"" prefer-non-shared="true">
|
||||
<language-scope id="org.eclipse.cdt.core.gcc"/>
|
||||
<language-scope id="org.eclipse.cdt.core.g++"/>
|
||||
</provider>
|
||||
|
@ -27,7 +27,7 @@
|
|||
<provider copy-of="extension" id="org.eclipse.cdt.ui.UserLanguageSettingsProvider"/>
|
||||
<provider-reference id="org.eclipse.cdt.core.ReferencedProjectsLanguageSettingsProvider" ref="shared-provider"/>
|
||||
<provider-reference id="org.eclipse.cdt.managedbuilder.core.MBSLanguageSettingsProvider" ref="shared-provider"/>
|
||||
<provider class="org.eclipse.cdt.internal.build.crossgcc.CrossGCCBuiltinSpecsDetector" console="false" env-hash="337623625225680352" id="org.eclipse.cdt.build.crossgcc.CrossGCCBuiltinSpecsDetector" keep-relative-paths="false" name="CDT Cross GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD "${INPUTS}"" prefer-non-shared="true">
|
||||
<provider class="org.eclipse.cdt.internal.build.crossgcc.CrossGCCBuiltinSpecsDetector" console="false" env-hash="-303428918971435778" id="org.eclipse.cdt.build.crossgcc.CrossGCCBuiltinSpecsDetector" keep-relative-paths="false" name="CDT Cross GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD "${INPUTS}"" prefer-non-shared="true">
|
||||
<language-scope id="org.eclipse.cdt.core.gcc"/>
|
||||
<language-scope id="org.eclipse.cdt.core.g++"/>
|
||||
</provider>
|
||||
|
|
|
@ -23,14 +23,16 @@ Licence: GPL
|
|||
#ifndef CONFIGURATION_H
|
||||
#define CONFIGURATION_H
|
||||
|
||||
#include <cstddef> // for size_t
|
||||
|
||||
// Firmware name is now defined in the Pins file
|
||||
|
||||
#ifndef VERSION
|
||||
# define VERSION "1.17dev1"
|
||||
# define VERSION "1.17dev4"
|
||||
#endif
|
||||
|
||||
#ifndef DATE
|
||||
# define DATE "2016-11-12"
|
||||
# define DATE "2016-11-17"
|
||||
#endif
|
||||
|
||||
#define AUTHORS "reprappro, dc42, zpl, t3p3, dnewman"
|
||||
|
@ -82,7 +84,8 @@ const float HOT_ENOUGH_TO_RETRACT = 90.0; // Celsius
|
|||
|
||||
const uint8_t MAX_BAD_TEMPERATURE_COUNT = 4; // Number of bad temperature samples permitted before a heater fault is reported
|
||||
const float BAD_LOW_TEMPERATURE = -10.0; // Celsius
|
||||
const float DEFAULT_TEMPERATURE_LIMIT = 262.0; // Celsius
|
||||
const float DefaultExtruderTemperatureLimit = 262.0; // Celsius
|
||||
const float DefaultBedTemperatureLimit = 125.0; // Celsius
|
||||
const float HOT_END_FAN_TEMPERATURE = 45.0; // Temperature at which a thermostatic hot end fan comes on
|
||||
const float BAD_ERROR_TEMPERATURE = 2000.0; // Must exceed any reasonable 5temperature limit including DEFAULT_TEMPERATURE_LIMIT
|
||||
|
||||
|
@ -179,6 +182,8 @@ const unsigned int MaxTriggers = 10; // Must be <= 32 because we store a bitm
|
|||
const float NOZZLE_DIAMETER = 0.5; // Millimetres
|
||||
const float FILAMENT_WIDTH = 1.75; // Millimetres
|
||||
|
||||
const unsigned int MaxStackDepth = 5; // Maximum depth of stack
|
||||
|
||||
// Webserver stuff
|
||||
|
||||
#define DEFAULT_PASSWORD "reprap" // Default machine password
|
||||
|
|
|
@ -71,7 +71,9 @@ const float EXT_BETA = 4388.0;
|
|||
const float EXT_SHC = 0.0;
|
||||
|
||||
// Thermistor series resistor value in Ohms
|
||||
const float THERMISTOR_SERIES_RS = 4700.0;
|
||||
// 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;
|
||||
|
||||
// Number of SPI temperature sensors to support
|
||||
|
||||
|
|
|
@ -70,7 +70,7 @@ namespace DuetExpansion
|
|||
pinMode(DueX_INT, INPUT_PULLUP);
|
||||
pinMode(DueX_SG, INPUT_PULLUP);
|
||||
|
||||
expander.pinModeMultiple(AllFanBits, OUTPUT_PWM); // Initialise the PWM pins
|
||||
expander.pinModeMultiple(AllFanBits, OUTPUT_PWM_LOW); // Initialise the PWM pins
|
||||
const uint16_t stopBits = (boardType == ExpansionBoardType::DueX5) ? AllStopBitsX5 : AllStopBitsX2; // I am assuming that the X0 has 2 endstop inputs
|
||||
expander.pinModeMultiple(stopBits | AllGpioBits, INPUT); // Initialise the endstop inputs and GPIO pins (no pullups because 5V-tolerant)
|
||||
|
||||
|
@ -118,7 +118,8 @@ namespace DuetExpansion
|
|||
case OUTPUT_HIGH:
|
||||
mode = OUTPUT_HIGH_OPEN_DRAIN;
|
||||
break;
|
||||
case OUTPUT_PWM:
|
||||
case OUTPUT_PWM_LOW:
|
||||
case OUTPUT_PWM_HIGH:
|
||||
mode = OUTPUT_PWM_OPEN_DRAIN;
|
||||
break;
|
||||
case INPUT_PULLUP:
|
||||
|
|
|
@ -146,7 +146,8 @@ void SX1509::pinModeMultiple(uint16_t pins, PinMode inOut)
|
|||
clearBitsInWord(REG_DIR_B, pins);
|
||||
break;
|
||||
|
||||
case OUTPUT_PWM:
|
||||
case OUTPUT_PWM_LOW:
|
||||
case OUTPUT_PWM_HIGH:
|
||||
ledDriverInitMultiple(pins, false, false);
|
||||
break;
|
||||
|
||||
|
|
|
@ -713,7 +713,7 @@ void WifiFirmwareUploader::Spin()
|
|||
// Try to upload the given file at the given address
|
||||
void WifiFirmwareUploader::SendUpdateFile(const char *file, const char *dir, uint32_t address)
|
||||
{
|
||||
Platform *platform = reprap.GetPlatform();
|
||||
Platform * const platform = reprap.GetPlatform();
|
||||
uploadFile = platform->GetFileStore(dir, file, false);
|
||||
if (uploadFile == nullptr)
|
||||
{
|
||||
|
|
|
@ -9,10 +9,10 @@
|
|||
|
||||
#include "RepRapFirmware.h"
|
||||
|
||||
// This class stores a single G Code and provides functions to allow it to be parsed
|
||||
|
||||
GCodeBuffer::GCodeBuffer(Platform* p, const char* id, MessageType mt)
|
||||
: platform(p), identity(id), checksumRequired(false), writingFileDirectory(nullptr), toolNumberAdjust(0), responseMessageType(mt)
|
||||
// Create a default GCodeBuffer
|
||||
GCodeBuffer::GCodeBuffer(const char* id, MessageType mt)
|
||||
: machineState(new GCodeMachineState()), identity(id), checksumRequired(false), writingFileDirectory(nullptr),
|
||||
toolNumberAdjust(0), responseMessageType(mt)
|
||||
{
|
||||
Init();
|
||||
}
|
||||
|
@ -22,23 +22,23 @@ void GCodeBuffer::Init()
|
|||
gcodePointer = 0;
|
||||
readPointer = -1;
|
||||
inComment = false;
|
||||
state = GCodeState::idle;
|
||||
bufferState = GCodeBufferState::idle;
|
||||
}
|
||||
|
||||
void GCodeBuffer::Diagnostics(MessageType mtype)
|
||||
{
|
||||
switch (state)
|
||||
switch (bufferState)
|
||||
{
|
||||
case GCodeState::idle:
|
||||
platform->MessageF(mtype, "%s is idle\n", identity);
|
||||
case GCodeBufferState::idle:
|
||||
reprap.GetPlatform()->MessageF(mtype, "%s is idle\n", identity);
|
||||
break;
|
||||
|
||||
case GCodeState::ready:
|
||||
platform->MessageF(mtype, "%s is ready with \"%s\"\n", identity, Buffer());
|
||||
case GCodeBufferState::ready:
|
||||
reprap.GetPlatform()->MessageF(mtype, "%s is ready with \"%s\"\n", identity, Buffer());
|
||||
break;
|
||||
|
||||
case GCodeState::executing:
|
||||
platform->MessageF(mtype, "%s is doing \"%s\"\n", identity, Buffer());
|
||||
case GCodeBufferState::executing:
|
||||
reprap.GetPlatform()->MessageF(mtype, "%s is doing \"%s\"\n", identity, Buffer());
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -72,7 +72,7 @@ bool GCodeBuffer::Put(char c)
|
|||
gcodeBuffer[gcodePointer] = 0;
|
||||
if (reprap.Debug(moduleGcodes) && gcodeBuffer[0] != 0 && !writingFileDirectory) // Don't bother with blank/comment lines
|
||||
{
|
||||
platform->MessageF(DEBUG_MESSAGE, "%s: %s\n", identity, gcodeBuffer);
|
||||
reprap.GetPlatform()->MessageF(DEBUG_MESSAGE, "%s: %s\n", identity, gcodeBuffer);
|
||||
}
|
||||
|
||||
// Deal with line numbers and checksums
|
||||
|
@ -116,7 +116,7 @@ bool GCodeBuffer::Put(char c)
|
|||
}
|
||||
gcodeBuffer[gp2] = 0;
|
||||
}
|
||||
else if (checksumRequired || IsEmpty())
|
||||
else if ((checksumRequired && machineState->previous == nullptr) || IsEmpty())
|
||||
{
|
||||
// Checksum not found or buffer empty - cannot do anything
|
||||
gcodeBuffer[0] = 0;
|
||||
|
@ -124,7 +124,7 @@ bool GCodeBuffer::Put(char c)
|
|||
return false;
|
||||
}
|
||||
Init();
|
||||
state = GCodeState::ready;
|
||||
bufferState = GCodeBufferState::ready;
|
||||
return true;
|
||||
}
|
||||
else if (!inComment || writingFileDirectory)
|
||||
|
@ -132,7 +132,7 @@ bool GCodeBuffer::Put(char c)
|
|||
gcodeBuffer[gcodePointer++] = c;
|
||||
if (gcodePointer >= (int)GCODE_LENGTH)
|
||||
{
|
||||
platform->Message(GENERIC_MESSAGE, "Error: G-Code buffer length overflow.\n");
|
||||
reprap.GetPlatform()->Message(GENERIC_MESSAGE, "Error: G-Code buffer length overflow.\n");
|
||||
gcodePointer = 0;
|
||||
gcodeBuffer[0] = 0;
|
||||
}
|
||||
|
@ -174,7 +174,7 @@ bool GCodeBuffer::Seen(char c)
|
|||
readPointer = 0;
|
||||
for (;;)
|
||||
{
|
||||
char b = gcodeBuffer[readPointer];
|
||||
const char b = gcodeBuffer[readPointer];
|
||||
if (b == 0 || b == ';') break;
|
||||
if (b == c) return true;
|
||||
++readPointer;
|
||||
|
@ -188,7 +188,7 @@ float GCodeBuffer::GetFValue()
|
|||
{
|
||||
if (readPointer < 0)
|
||||
{
|
||||
platform->Message(GENERIC_MESSAGE, "Error: GCodes: Attempt to read a GCode float before a search.\n");
|
||||
reprap.GetPlatform()->Message(GENERIC_MESSAGE, "Error: GCodes: Attempt to read a GCode float before a search.\n");
|
||||
readPointer = -1;
|
||||
return 0.0;
|
||||
}
|
||||
|
@ -202,7 +202,7 @@ const void GCodeBuffer::GetFloatArray(float a[], size_t& returnedLength, bool do
|
|||
{
|
||||
if(readPointer < 0)
|
||||
{
|
||||
platform->Message(GENERIC_MESSAGE, "Error: GCodes: Attempt to read a GCode float array before a search.\n");
|
||||
reprap.GetPlatform()->Message(GENERIC_MESSAGE, "Error: GCodes: Attempt to read a GCode float array before a search.\n");
|
||||
readPointer = -1;
|
||||
returnedLength = 0;
|
||||
return;
|
||||
|
@ -214,7 +214,7 @@ const void GCodeBuffer::GetFloatArray(float a[], size_t& returnedLength, bool do
|
|||
{
|
||||
if (length >= returnedLength) // array limit has been set in here
|
||||
{
|
||||
platform->MessageF(GENERIC_MESSAGE, "Error: GCodes: Attempt to read a GCode float array that is too long: %s\n", gcodeBuffer);
|
||||
reprap.GetPlatform()->MessageF(GENERIC_MESSAGE, "Error: GCodes: Attempt to read a GCode float array that is too long: %s\n", gcodeBuffer);
|
||||
readPointer = -1;
|
||||
returnedLength = 0;
|
||||
return;
|
||||
|
@ -253,7 +253,7 @@ const void GCodeBuffer::GetLongArray(long l[], size_t& returnedLength)
|
|||
{
|
||||
if (readPointer < 0)
|
||||
{
|
||||
platform->Message(GENERIC_MESSAGE, "Error: GCodes: Attempt to read a GCode long array before a search.\n");
|
||||
reprap.GetPlatform()->Message(GENERIC_MESSAGE, "Error: GCodes: Attempt to read a GCode long array before a search.\n");
|
||||
readPointer = -1;
|
||||
return;
|
||||
}
|
||||
|
@ -264,7 +264,7 @@ const void GCodeBuffer::GetLongArray(long l[], size_t& returnedLength)
|
|||
{
|
||||
if (length >= returnedLength) // Array limit has been set in here
|
||||
{
|
||||
platform->MessageF(GENERIC_MESSAGE, "Error: GCodes: Attempt to read a GCode long array that is too long: %s\n", gcodeBuffer);
|
||||
reprap.GetPlatform()->MessageF(GENERIC_MESSAGE, "Error: GCodes: Attempt to read a GCode long array that is too long: %s\n", gcodeBuffer);
|
||||
readPointer = -1;
|
||||
returnedLength = 0;
|
||||
return;
|
||||
|
@ -290,11 +290,11 @@ const char* GCodeBuffer::GetString()
|
|||
{
|
||||
if (readPointer < 0)
|
||||
{
|
||||
platform->Message(GENERIC_MESSAGE, "Error: GCodes: Attempt to read a GCode string before a search.\n");
|
||||
reprap.GetPlatform()->Message(GENERIC_MESSAGE, "Error: GCodes: Attempt to read a GCode string before a search.\n");
|
||||
readPointer = -1;
|
||||
return "";
|
||||
}
|
||||
const char* result = &gcodeBuffer[readPointer + 1];
|
||||
const char* const result = &gcodeBuffer[readPointer + 1];
|
||||
readPointer = -1;
|
||||
return result;
|
||||
}
|
||||
|
@ -324,12 +324,12 @@ const char* GCodeBuffer::GetUnprecedentedString(bool optional)
|
|||
readPointer = -1;
|
||||
if (!optional)
|
||||
{
|
||||
platform->Message(GENERIC_MESSAGE, "Error: GCodes: String expected but not seen.\n");
|
||||
reprap.GetPlatform()->Message(GENERIC_MESSAGE, "Error: GCodes: String expected but not seen.\n");
|
||||
}
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
const char* result = &gcodeBuffer[readPointer + 1];
|
||||
const char* const result = &gcodeBuffer[readPointer + 1];
|
||||
readPointer = -1;
|
||||
return result;
|
||||
}
|
||||
|
@ -339,11 +339,11 @@ int32_t GCodeBuffer::GetIValue()
|
|||
{
|
||||
if (readPointer < 0)
|
||||
{
|
||||
platform->Message(GENERIC_MESSAGE, "Error: GCodes: Attempt to read a GCode int before a search.\n");
|
||||
reprap.GetPlatform()->Message(GENERIC_MESSAGE, "Error: GCodes: Attempt to read a GCode int before a search.\n");
|
||||
readPointer = -1;
|
||||
return 0;
|
||||
}
|
||||
int32_t result = strtol(&gcodeBuffer[readPointer + 1], 0, 0);
|
||||
const int32_t result = strtol(&gcodeBuffer[readPointer + 1], 0, 0);
|
||||
readPointer = -1;
|
||||
return result;
|
||||
}
|
||||
|
@ -368,27 +368,60 @@ void GCodeBuffer::TryGetIValue(char c, int32_t& val, bool& seen)
|
|||
}
|
||||
}
|
||||
|
||||
// Return true if this buffer contains a poll request or empty request that can be executed while macros etc. from another source are being completed
|
||||
bool GCodeBuffer::IsPollRequest()
|
||||
// Get the original machine state before we pushed anything
|
||||
GCodeMachineState& GCodeBuffer::OriginalMachineState() const
|
||||
{
|
||||
if (state == GCodeState::ready)
|
||||
{ if (IsEmpty())
|
||||
{
|
||||
return true;
|
||||
}
|
||||
if (Seen('M'))
|
||||
{
|
||||
return IsPollCode(GetIValue());
|
||||
}
|
||||
GCodeMachineState *ms = machineState;
|
||||
while (ms->previous != nullptr)
|
||||
{
|
||||
ms = ms->previous;
|
||||
}
|
||||
return false;
|
||||
return *ms;
|
||||
}
|
||||
|
||||
// Return true if the specified M code can be executed concurrently with other requests.
|
||||
// These should be codes that do not modify the state (we make an exception for M111) and are always executed in a single call to function HandleMCode.
|
||||
/*static*/ bool GCodeBuffer::IsPollCode(int code)
|
||||
// Push state returning true if successful (i.e. stack not overflowed)
|
||||
bool GCodeBuffer::PushState()
|
||||
{
|
||||
return code == 27 || code == 105 || code == 111 || code == 114 || code == 119 || code == 122 || code == 408 || code == 573;
|
||||
// Check the current stack depth
|
||||
unsigned int depth = 0;
|
||||
for (const GCodeMachineState *m1 = machineState; m1 != nullptr; m1 = m1->previous)
|
||||
{
|
||||
++depth;
|
||||
}
|
||||
if (depth >= MaxStackDepth + 1) // the +1 is to allow for the initial state record
|
||||
{
|
||||
return false;
|
||||
}
|
||||
|
||||
GCodeMachineState * const ms = GCodeMachineState::Allocate();
|
||||
ms->previous = machineState;
|
||||
ms->feedrate = machineState->feedrate;
|
||||
ms->drivesRelative = machineState->drivesRelative;
|
||||
ms->axesRelative = machineState->axesRelative;
|
||||
ms->doingFileMacro = machineState->doingFileMacro;
|
||||
ms->lockedResources = machineState->lockedResources;
|
||||
machineState = ms;
|
||||
return true;
|
||||
}
|
||||
|
||||
// Pop state returning true if successful (i.e. no stack underrun)
|
||||
bool GCodeBuffer::PopState()
|
||||
{
|
||||
GCodeMachineState * const ms = machineState;
|
||||
if (ms->previous == nullptr)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
|
||||
machineState = ms->previous;
|
||||
GCodeMachineState::Release(ms);
|
||||
return true;
|
||||
}
|
||||
|
||||
// Return true if this source is executing a file macro
|
||||
bool GCodeBuffer::IsDoingFileMacro() const
|
||||
{
|
||||
return machineState->doingFileMacro;
|
||||
}
|
||||
|
||||
// End
|
||||
|
|
|
@ -8,61 +8,67 @@
|
|||
#ifndef GCODEBUFFER_H_
|
||||
#define GCODEBUFFER_H_
|
||||
|
||||
// Small class to hold an individual GCode and provide functions to allow it to be parsed
|
||||
#include "GCodeMachineState.h"
|
||||
|
||||
// Class to hold an individual GCode and provide functions to allow it to be parsed
|
||||
class GCodeBuffer
|
||||
{
|
||||
public:
|
||||
GCodeBuffer(Platform* p, const char* id, MessageType mt);
|
||||
void Init(); // Set it up
|
||||
public:
|
||||
GCodeBuffer(const char* id, MessageType mt);
|
||||
void Init(); // Set it up
|
||||
void Diagnostics(MessageType mtype); // Write some debug info
|
||||
bool Put(char c); // Add a character to the end
|
||||
bool Put(const char *str, size_t len); // Add an entire string
|
||||
bool IsEmpty() const; // Does this buffer contain any code?
|
||||
bool Seen(char c); // Is a character present?
|
||||
float GetFValue(); // Get a float after a key letter
|
||||
int32_t GetIValue(); // Get an integer after a key letter
|
||||
void TryGetFValue(char c, float& val, bool& seen);
|
||||
void TryGetIValue(char c, int32_t& val, bool& seen);
|
||||
const char* GetUnprecedentedString(bool optional = false); // Get a string with no preceding key letter
|
||||
const char* GetString(); // Get a string after a key letter
|
||||
const void GetFloatArray(float a[], size_t& length, bool doPad); // Get a :-separated list of floats after a key letter
|
||||
const void GetLongArray(long l[], size_t& length); // Get a :-separated list of longs after a key letter
|
||||
const char* Buffer() const;
|
||||
bool IsIdle() const;
|
||||
bool IsReady() const; // Return true if a gcode is ready but hasn't been started yet
|
||||
bool IsExecuting() const; // Return true if a gcode has been started and is not paused
|
||||
void SetFinished(bool f); // Set the G Code executed (or not)
|
||||
const char* WritingFileDirectory() const; // If we are writing the G Code to a file, where that file is
|
||||
void SetWritingFileDirectory(const char* wfd); // Set the directory for the file to write the GCode in
|
||||
int GetToolNumberAdjust() const { return toolNumberAdjust; }
|
||||
void SetToolNumberAdjust(int arg) { toolNumberAdjust = arg; }
|
||||
void SetCommsProperties(uint32_t arg) { checksumRequired = (arg & 1); }
|
||||
bool StartingNewCode() const { return gcodePointer == 0; }
|
||||
bool IsPollRequest();
|
||||
MessageType GetResponseMessageType() const { return responseMessageType; }
|
||||
bool Put(char c); // Add a character to the end
|
||||
bool Put(const char *str, size_t len); // Add an entire string
|
||||
bool IsEmpty() const; // Does this buffer contain any code?
|
||||
bool Seen(char c); // Is a character present?
|
||||
float GetFValue(); // Get a float after a key letter
|
||||
int32_t GetIValue(); // Get an integer after a key letter
|
||||
void TryGetFValue(char c, float& val, bool& seen);
|
||||
void TryGetIValue(char c, int32_t& val, bool& seen);
|
||||
const char* GetUnprecedentedString(bool optional = false); // Get a string with no preceding key letter
|
||||
const char* GetString(); // Get a string after a key letter
|
||||
const void GetFloatArray(float a[], size_t& length, bool doPad); // Get a :-separated list of floats after a key letter
|
||||
const void GetLongArray(long l[], size_t& length); // Get a :-separated list of longs after a key letter
|
||||
const char* Buffer() const;
|
||||
bool IsIdle() const;
|
||||
bool IsReady() const; // Return true if a gcode is ready but hasn't been started yet
|
||||
bool IsExecuting() const; // Return true if a gcode has been started and is not paused
|
||||
void SetFinished(bool f); // Set the G Code executed (or not)
|
||||
const char* WritingFileDirectory() const; // If we are writing the G Code to a file, where that file is
|
||||
void SetWritingFileDirectory(const char* wfd); // Set the directory for the file to write the GCode in
|
||||
int GetToolNumberAdjust() const { return toolNumberAdjust; }
|
||||
void SetToolNumberAdjust(int arg) { toolNumberAdjust = arg; }
|
||||
void SetCommsProperties(uint32_t arg) { checksumRequired = (arg & 1); }
|
||||
bool StartingNewCode() const { return gcodePointer == 0; }
|
||||
MessageType GetResponseMessageType() const { return responseMessageType; }
|
||||
GCodeMachineState& MachineState() const { return *machineState; }
|
||||
GCodeMachineState& OriginalMachineState() const;
|
||||
bool PushState(); // Push state returning true if successful (i.e. stack not overflowed)
|
||||
bool PopState(); // Pop state returning true if successful (i.e. no stack underrun)
|
||||
bool IsDoingFileMacro() const; // Return true if this source is executing a file macro
|
||||
|
||||
static bool IsPollCode(int code);
|
||||
private:
|
||||
|
||||
private:
|
||||
|
||||
enum class GCodeState
|
||||
enum class GCodeBufferState
|
||||
{
|
||||
idle, // we don't have a complete gcode ready
|
||||
idle, // we don't have a complete gcode ready
|
||||
ready, // we have a complete gcode but haven't started executing it
|
||||
executing // we have a complete gcode and have started executing it
|
||||
};
|
||||
int CheckSum() const; // Compute the checksum (if any) at the end of the G Code
|
||||
Platform* platform; // Pointer to the RepRap's controlling class
|
||||
char gcodeBuffer[GCODE_LENGTH]; // The G Code
|
||||
const char* identity; // Where we are from (web, file, serial line etc)
|
||||
int gcodePointer; // Index in the buffer
|
||||
int readPointer; // Where in the buffer to read next
|
||||
bool inComment; // Are we after a ';' character?
|
||||
bool checksumRequired; // True if we only accept commands with a valid checksum
|
||||
GCodeState state; // Idle, executing or paused
|
||||
const char* writingFileDirectory; // If the G Code is going into a file, where that is
|
||||
int toolNumberAdjust; // The adjustment to tool numbers in commands we receive
|
||||
const MessageType responseMessageType; // The message type we use for responses to commands coming from this channel
|
||||
|
||||
int CheckSum() const; // Compute the checksum (if any) at the end of the G Code
|
||||
|
||||
GCodeMachineState *machineState; // Machine state for this gcode source
|
||||
char gcodeBuffer[GCODE_LENGTH]; // The G Code
|
||||
const char* identity; // Where we are from (web, file, serial line etc)
|
||||
int gcodePointer; // Index in the buffer
|
||||
int readPointer; // Where in the buffer to read next
|
||||
bool inComment; // Are we after a ';' character?
|
||||
bool checksumRequired; // True if we only accept commands with a valid checksum
|
||||
GCodeBufferState bufferState; // Idle, executing or paused
|
||||
const char* writingFileDirectory; // If the G Code is going into a file, where that is
|
||||
int toolNumberAdjust; // The adjustment to tool numbers in commands we receive
|
||||
const MessageType responseMessageType; // The message type we use for responses to commands coming from this channel
|
||||
};
|
||||
|
||||
inline const char* GCodeBuffer::Buffer() const
|
||||
|
@ -72,22 +78,22 @@ inline const char* GCodeBuffer::Buffer() const
|
|||
|
||||
inline bool GCodeBuffer::IsIdle() const
|
||||
{
|
||||
return state == GCodeState::idle;
|
||||
return bufferState == GCodeBufferState::idle;
|
||||
}
|
||||
|
||||
inline bool GCodeBuffer::IsReady() const
|
||||
{
|
||||
return state == GCodeState::ready;
|
||||
return bufferState == GCodeBufferState::ready;
|
||||
}
|
||||
|
||||
inline bool GCodeBuffer::IsExecuting() const
|
||||
{
|
||||
return state == GCodeState::executing;
|
||||
return bufferState == GCodeBufferState::executing;
|
||||
}
|
||||
|
||||
inline void GCodeBuffer::SetFinished(bool f)
|
||||
{
|
||||
state = (f) ? GCodeState::idle : GCodeState::executing;
|
||||
bufferState = (f) ? GCodeBufferState::idle : GCodeBufferState::executing;
|
||||
}
|
||||
|
||||
inline const char* GCodeBuffer::WritingFileDirectory() const
|
||||
|
|
55
src/GCodes/GCodeMachineState.cpp
Normal file
55
src/GCodes/GCodeMachineState.cpp
Normal file
|
@ -0,0 +1,55 @@
|
|||
/*
|
||||
* GCodeMachineState.cpp
|
||||
*
|
||||
* Created on: 15 Nov 2016
|
||||
* Author: David
|
||||
*/
|
||||
|
||||
#include "GCodeMachineState.h"
|
||||
|
||||
GCodeMachineState *GCodeMachineState::freeList = nullptr;
|
||||
unsigned int GCodeMachineState::numAllocated = 0;
|
||||
|
||||
// Create a default initialised GCodeMachineState
|
||||
GCodeMachineState::GCodeMachineState()
|
||||
: previous(nullptr), feedrate(DEFAULT_FEEDRATE), fileState(), lockedResources(0), state(GCodeState::normal),
|
||||
drivesRelative(false), axesRelative(false), doingFileMacro(false)
|
||||
{
|
||||
}
|
||||
|
||||
// Allocate a new GCodeMachineState
|
||||
/*static*/ GCodeMachineState *GCodeMachineState::Allocate()
|
||||
{
|
||||
GCodeMachineState *ms = freeList;
|
||||
if (ms != nullptr)
|
||||
{
|
||||
freeList = ms->previous;
|
||||
ms->lockedResources = 0;
|
||||
ms->state = GCodeState::normal;
|
||||
}
|
||||
else
|
||||
{
|
||||
ms = new GCodeMachineState();
|
||||
++numAllocated;
|
||||
}
|
||||
return ms;
|
||||
}
|
||||
|
||||
/*static*/ void GCodeMachineState::Release(GCodeMachineState *ms)
|
||||
{
|
||||
ms->fileState.Close();
|
||||
ms->previous = freeList;
|
||||
freeList = ms;
|
||||
}
|
||||
|
||||
/*static*/ unsigned int GCodeMachineState::GetNumInUse()
|
||||
{
|
||||
unsigned int inUse = numAllocated;
|
||||
for (GCodeMachineState *ms = freeList; ms != nullptr; ms = ms->previous)
|
||||
{
|
||||
--inUse;
|
||||
}
|
||||
return inUse;
|
||||
}
|
||||
|
||||
// End
|
65
src/GCodes/GCodeMachineState.h
Normal file
65
src/GCodes/GCodeMachineState.h
Normal file
|
@ -0,0 +1,65 @@
|
|||
/*
|
||||
* GCodeMachineState.h
|
||||
*
|
||||
* Created on: 15 Nov 2016
|
||||
* Author: David
|
||||
*/
|
||||
|
||||
#ifndef SRC_GCODES_GCODEMACHINESTATE_H_
|
||||
#define SRC_GCODES_GCODEMACHINESTATE_H_
|
||||
|
||||
#include <cstdint>
|
||||
#include "Configuration.h"
|
||||
#include "Storage/FileData.h"
|
||||
|
||||
// Enumeration to list all the possible states that the Gcode processing machine may be in
|
||||
enum class GCodeState : uint8_t
|
||||
{
|
||||
normal, // not doing anything and ready to process a new GCode
|
||||
waitingForMoveToComplete, // doing a homing move, so we must wait for it to finish before processing another GCode
|
||||
homing,
|
||||
setBed1,
|
||||
setBed2,
|
||||
setBed3,
|
||||
toolChange1,
|
||||
toolChange2,
|
||||
toolChange3,
|
||||
pausing1,
|
||||
pausing2,
|
||||
resuming1,
|
||||
resuming2,
|
||||
resuming3,
|
||||
flashing1,
|
||||
flashing2,
|
||||
stopping,
|
||||
sleeping
|
||||
};
|
||||
|
||||
// Class to hold the state of gcode execution for some input source
|
||||
class GCodeMachineState
|
||||
{
|
||||
public:
|
||||
GCodeMachineState();
|
||||
|
||||
GCodeMachineState *previous;
|
||||
float feedrate;
|
||||
FileData fileState;
|
||||
uint32_t lockedResources;
|
||||
GCodeState state;
|
||||
bool drivesRelative;
|
||||
bool axesRelative;
|
||||
bool doingFileMacro;
|
||||
|
||||
static GCodeMachineState *Allocate()
|
||||
post(!result.IsLive(); result.state == GCodeState::normal);
|
||||
|
||||
static void Release(GCodeMachineState *ms);
|
||||
static unsigned int GetNumAllocated() { return numAllocated; }
|
||||
static unsigned int GetNumInUse();
|
||||
|
||||
private:
|
||||
static GCodeMachineState *freeList;
|
||||
static unsigned int numAllocated;
|
||||
};
|
||||
|
||||
#endif /* SRC_GCODES_GCODEMACHINESTATE_H_ */
|
File diff suppressed because it is too large
Load diff
|
@ -25,54 +25,17 @@ Licence: GPL
|
|||
#include "GCodeBuffer.h"
|
||||
#include "Libraries/sha1/sha1.h"
|
||||
|
||||
const unsigned int StackSize = 5;
|
||||
|
||||
const char feedrateLetter = 'F'; // GCode feedrate
|
||||
const char extrudeLetter = 'E'; // GCode extrude
|
||||
|
||||
// Type for specifying which endstops we want to check
|
||||
typedef uint16_t EndstopChecks; // must be large enough to hold a bitmap of drive numbers or ZProbeActive
|
||||
const EndstopChecks ZProbeActive = 1 << 15; // must be distinct from 1 << (any drive number)
|
||||
const EndstopChecks LogProbeChanges = 1 << 14; // must be distinct from 1 << (any drive number)
|
||||
|
||||
const float minutesToSeconds = 60.0;
|
||||
const float secondsToMinutes = 1.0/minutesToSeconds;
|
||||
|
||||
// Enumeration to list all the possible states that the Gcode processing machine may be in
|
||||
enum class GCodeState
|
||||
{
|
||||
normal, // not doing anything and ready to process a new GCode
|
||||
waitingForMoveToComplete, // doing a homing move, so we must wait for it to finish before processing another GCode
|
||||
homing,
|
||||
setBed1,
|
||||
setBed2,
|
||||
setBed3,
|
||||
toolChange1,
|
||||
toolChange2,
|
||||
toolChange3,
|
||||
pausing1,
|
||||
pausing2,
|
||||
resuming1,
|
||||
resuming2,
|
||||
resuming3,
|
||||
flashing1,
|
||||
flashing2,
|
||||
stopping,
|
||||
sleeping
|
||||
};
|
||||
|
||||
// Small class to stack the state when we execute a macro file
|
||||
class GCodeMachineState
|
||||
{
|
||||
public:
|
||||
GCodeState state;
|
||||
GCodeBuffer *gb; // this may be null when executing config.g
|
||||
float feedrate;
|
||||
FileData fileState;
|
||||
bool drivesRelative;
|
||||
bool axesRelative;
|
||||
bool doingFileMacro;
|
||||
};
|
||||
|
||||
typedef uint16_t TriggerMask;
|
||||
|
||||
struct Trigger
|
||||
|
@ -125,8 +88,9 @@ public:
|
|||
bool DoingFileMacro() const; // Or still busy processing a macro file?
|
||||
float FractionOfFilePrinted() const; // Get fraction of file printed
|
||||
void Diagnostics(MessageType mtype); // Send helpful information out
|
||||
bool HaveIncomingData() const; // Is there something that we have to do?
|
||||
size_t GetStackPointer() const; // Returns the current stack pointer
|
||||
|
||||
bool RunConfigFile(const char* fileName); // Start running the config file
|
||||
bool IsRunningConfigFile() const; // Are we still running the config file?
|
||||
|
||||
bool GetAxisIsHomed(unsigned int axis) const // Has the axis been homed?
|
||||
{ return (axesHomed & (1 << axis)) != 0; }
|
||||
|
@ -149,7 +113,6 @@ public:
|
|||
bool IsRunning() const;
|
||||
|
||||
bool AllAxesAreHomed() const; // Return true if all axes are homed
|
||||
bool DoFileMacro(const char* fileName, bool reportMissing = true); // Run a GCode macro in a file, optionally report error if not found
|
||||
|
||||
void CancelPrint(); // Cancel the current print
|
||||
|
||||
|
@ -161,150 +124,166 @@ public:
|
|||
static const char axisLetters[MAX_AXES]; // 'X', 'Y', 'Z'
|
||||
|
||||
private:
|
||||
enum class CannedMoveType : uint8_t { none, relative, absolute };
|
||||
enum class CannedMoveType : uint8_t { none, relative, absolute };
|
||||
|
||||
struct RestorePoint
|
||||
{
|
||||
float moveCoords[DRIVES];
|
||||
float feedRate;
|
||||
RestorePoint() { Init(); }
|
||||
void Init();
|
||||
};
|
||||
struct RestorePoint
|
||||
{
|
||||
float moveCoords[DRIVES];
|
||||
float feedRate;
|
||||
RestorePoint() { Init(); }
|
||||
void Init();
|
||||
};
|
||||
|
||||
void FillGCodeBuffers(); // Get new data into the gcode buffers
|
||||
void StartNextGCode(StringRef& reply); // Fetch a new GCode and process it
|
||||
void DoFilePrint(GCodeBuffer* gb, StringRef& reply); // Get G Codes from a file and print them
|
||||
bool AllMovesAreFinishedAndMoveBufferIsLoaded(); // Wait for move queue to exhaust and the current position is loaded
|
||||
bool DoCannedCycleMove(EndstopChecks ce); // Do a move from an internally programmed canned cycle
|
||||
void FileMacroCyclesReturn(); // End a macro
|
||||
bool ActOnCode(GCodeBuffer* gb, StringRef& reply); // Do a G, M or T Code
|
||||
bool HandleGcode(GCodeBuffer* gb, StringRef& reply); // Do a G code
|
||||
bool HandleMcode(GCodeBuffer* gb, StringRef& reply); // Do an M code
|
||||
bool HandleTcode(GCodeBuffer* gb, StringRef& reply); // Do a T code
|
||||
int SetUpMove(GCodeBuffer* gb, StringRef& reply); // Pass a move on to the Move module
|
||||
bool DoDwell(GCodeBuffer *gb); // Wait for a bit
|
||||
bool DoDwellTime(float dwell); // Really wait for a bit
|
||||
bool DoHome(GCodeBuffer *gb, StringRef& reply, bool& error); // Home some axes
|
||||
bool DoSingleZProbeAtPoint(int probePointIndex, float heightAdjust); // Probe at a given point
|
||||
bool DoSingleZProbe(bool reportOnly, float heightAdjust); // Probe where we are
|
||||
int DoZProbe(float distance); // Do a Z probe cycle up to the maximum specified distance
|
||||
bool SetSingleZProbeAtAPosition(GCodeBuffer *gb, StringRef& reply); // Probes at a given position - see the comment at the head of the function itself
|
||||
void SetBedEquationWithProbe(int sParam, StringRef& reply); // Probes a series of points and sets the bed equation
|
||||
bool SetPrintZProbe(GCodeBuffer *gb, StringRef& reply); // Either return the probe value, or set its threshold
|
||||
void SetOrReportOffsets(StringRef& reply, GCodeBuffer *gb); // Deal with a G10
|
||||
bool SetPositions(GCodeBuffer *gb); // Deal with a G92
|
||||
bool LoadMoveBufferFromGCode(GCodeBuffer *gb, int moveType); // Set up a move for the Move class
|
||||
bool NoHome() const; // Are we homing and not finished?
|
||||
void Push(); // Push feedrate etc on the stack
|
||||
void Pop(); // Pop feedrate etc
|
||||
void DisableDrives(); // Turn the motors off
|
||||
void SetEthernetAddress(GCodeBuffer *gb, int mCode); // Does what it says
|
||||
void SetMACAddress(GCodeBuffer *gb); // Deals with an M540
|
||||
void HandleReply(GCodeBuffer *gb, bool error, const char *reply); // Handle G-Code replies
|
||||
void HandleReply(GCodeBuffer *gb, bool error, OutputBuffer *reply);
|
||||
bool OpenFileToWrite(const char* directory, // Start saving GCodes in a file
|
||||
const char* fileName, GCodeBuffer *gb);
|
||||
void WriteGCodeToFile(GCodeBuffer *gb); // Write this GCode into a file
|
||||
bool SendConfigToLine(); // Deal with M503
|
||||
void WriteHTMLToFile(char b, GCodeBuffer *gb); // Save an HTML file (usually to upload a new web interface)
|
||||
bool OffsetAxes(GCodeBuffer *gb); // Set offsets - deprecated, use G10
|
||||
void SetPidParameters(GCodeBuffer *gb, int heater, StringRef& reply); // Set the P/I/D parameters for a heater
|
||||
void SetHeaterParameters(GCodeBuffer *gb, StringRef& reply); // Set the thermistor and ADC parameters for a heater
|
||||
void ManageTool(GCodeBuffer *gb, StringRef& reply); // Create a new tool definition
|
||||
void SetToolHeaters(Tool *tool, float temperature); // Set all a tool's heaters to the temperature. For M104...
|
||||
bool ToolHeatersAtSetTemperatures(const Tool *tool, bool waitWhenCooling) const; // Wait for the heaters associated with the specified tool to reach their set temperatures
|
||||
void SetAllAxesNotHomed(); // Flag all axes as not homed
|
||||
void SetPositions(float positionNow[DRIVES]); // Set the current position to be this
|
||||
const char *TranslateEndStopResult(EndStopHit es); // Translate end stop result to text
|
||||
bool RetractFilament(bool retract); // Retract or un-retract filaments
|
||||
bool ChangeMicrostepping(size_t drive, int microsteps, int mode) const; // Change microstepping on the specified drive
|
||||
void ListTriggers(StringRef reply, TriggerMask mask); // Append a list of trigger endstops to a message
|
||||
bool CheckTriggers(); // Check for and execute triggers
|
||||
void DoEmergencyStop(); // Execute an emergency stop
|
||||
void DoPause(bool externalToFile); // Pause the print
|
||||
void SetMappedFanSpeed(); // Set the speeds of fans mapped for the current tool
|
||||
// Resources that can be locked.
|
||||
// To avoid deadlock, if you need multiple resources then you must lock them in increasing numerical order.
|
||||
typedef unsigned int Resource;
|
||||
static const Resource MoveResource = 0; // Movement system, including canned cycle variables
|
||||
static const Resource FileSystemResource = 1; // Non-sharable parts of the file system
|
||||
static const Resource HeaterResourceBase = 2;
|
||||
static const Resource FanResourceBase = HeaterResourceBase + HEATERS;
|
||||
static const size_t NumResources = FanResourceBase + NUM_FANS;
|
||||
|
||||
Platform* platform; // The RepRap machine
|
||||
Webserver* webserver; // The webserver class
|
||||
static_assert(NumResources <= 32, "Too many resources to keep a bitmap of them in class GCodeMachineState");
|
||||
|
||||
GCodeBuffer* httpGCode; // The sources...
|
||||
GCodeBuffer* telnetGCode; // ...
|
||||
GCodeBuffer* fileGCode; // ...
|
||||
GCodeBuffer* serialGCode; // ...
|
||||
GCodeBuffer* auxGCode; // this one is for the LCD display on the async serial interface
|
||||
GCodeBuffer* fileMacroGCode; // ...
|
||||
GCodeBuffer *gbCurrent;
|
||||
bool LockResource(const GCodeBuffer& gb, Resource r); // Lock the resource, returning true if success
|
||||
bool LockHeater(const GCodeBuffer& gb, int heater);
|
||||
bool LockFan(const GCodeBuffer& gb, int fan);
|
||||
bool LockFileSystem(const GCodeBuffer& gb); // Lock the unshareable parts of the file system
|
||||
bool LockMovement(const GCodeBuffer& gb); // Lock movement
|
||||
bool LockMovementAndWaitForStandstill(const GCodeBuffer& gb); // Lock movement and wait for pending moves to finish
|
||||
void UnlockAll(const GCodeBuffer& gb); // Release all locks
|
||||
|
||||
bool active; // Live and running?
|
||||
bool isPaused; // true if the print has been paused
|
||||
bool dwellWaiting; // We are in a dwell
|
||||
bool moveAvailable; // Have we seen a move G Code and set it up?
|
||||
float dwellTime; // How long a pause for a dwell (seconds)?
|
||||
float feedRate; // The feed rate of the last G0/G1 command that had an F parameter
|
||||
RawMove moveBuffer; // Move details to pass to Move class
|
||||
RestorePoint simulationRestorePoint; // The position and feed rate when we started a simulation
|
||||
RestorePoint pauseRestorePoint; // The position and feed rate when we paused the print
|
||||
RestorePoint toolChangeRestorePoint; // The position and feed rate when we freed a tool
|
||||
GCodeState state; // The main state variable of the GCode state machine
|
||||
bool drivesRelative;
|
||||
bool axesRelative;
|
||||
GCodeMachineState stack[StackSize]; // State that we save when calling macro files
|
||||
unsigned int stackPointer; // Push and Pop stack pointer
|
||||
size_t numAxes; // How many axes we have
|
||||
size_t numExtruders; // How many extruders we have, or may have
|
||||
void StartNextGCode(GCodeBuffer& gb, StringRef& reply); // Fetch a new or old GCode and process it
|
||||
void DoFilePrint(GCodeBuffer& gb, StringRef& reply); // Get G Codes from a file and print them
|
||||
bool AllMovesAreFinishedAndMoveBufferIsLoaded(); // Wait for move queue to exhaust and the current position is loaded
|
||||
bool DoFileMacro(GCodeBuffer& gb, const char* fileName, bool reportMissing = true); // Run a GCode macro in a file, optionally report error if not found
|
||||
bool DoCannedCycleMove(GCodeBuffer& gb, EndstopChecks ce); // Do a move from an internally programmed canned cycle
|
||||
void FileMacroCyclesReturn(GCodeBuffer& gb); // End a macro
|
||||
bool ActOnCode(GCodeBuffer& gb, StringRef& reply); // Do a G, M or T Code
|
||||
bool HandleGcode(GCodeBuffer& gb, StringRef& reply); // Do a G code
|
||||
bool HandleMcode(GCodeBuffer& gb, StringRef& reply); // Do an M code
|
||||
bool HandleTcode(GCodeBuffer& gb, StringRef& reply); // Do a T code
|
||||
int SetUpMove(GCodeBuffer& gb, StringRef& reply); // Pass a move on to the Move module
|
||||
bool DoDwell(GCodeBuffer& gb); // Wait for a bit
|
||||
bool DoDwellTime(float dwell); // Really wait for a bit
|
||||
bool DoHome(GCodeBuffer& gb, StringRef& reply, bool& error); // Home some axes
|
||||
bool DoSingleZProbeAtPoint(GCodeBuffer& gb, int probePointIndex, float heightAdjust); // Probe at a given point
|
||||
bool DoSingleZProbe(GCodeBuffer& gb, bool reportOnly, float heightAdjust); // Probe where we are
|
||||
int DoZProbe(GCodeBuffer& gb, float distance); // Do a Z probe cycle up to the maximum specified distance
|
||||
bool SetSingleZProbeAtAPosition(GCodeBuffer& gb, StringRef& reply); // Probes at a given position - see the comment at the head of the function itself
|
||||
void SetBedEquationWithProbe(int sParam, StringRef& reply); // Probes a series of points and sets the bed equation
|
||||
bool SetPrintZProbe(GCodeBuffer& gb, StringRef& reply); // Either return the probe value, or set its threshold
|
||||
bool SetOrReportOffsets(GCodeBuffer& gb, StringRef& reply); // Deal with a G10
|
||||
bool SetPositions(GCodeBuffer& gb); // Deal with a G92
|
||||
bool LoadMoveBufferFromGCode(GCodeBuffer& gb, int moveType); // Set up a move for the Move class
|
||||
bool NoHome() const; // Are we homing and not finished?
|
||||
bool Push(GCodeBuffer& gb); // Push feedrate etc on the stack
|
||||
void Pop(GCodeBuffer& gb); // Pop feedrate etc
|
||||
void DisableDrives(); // Turn the motors off
|
||||
void SetEthernetAddress(GCodeBuffer& gb, int mCode); // Does what it says
|
||||
void SetMACAddress(GCodeBuffer& gb); // Deals with an M540
|
||||
void HandleReply(GCodeBuffer& gb, bool error, const char *reply); // Handle G-Code replies
|
||||
void HandleReply(GCodeBuffer& gb, bool error, OutputBuffer *reply);
|
||||
bool OpenFileToWrite(GCodeBuffer& gb, const char* directory, // Start saving GCodes in a file
|
||||
const char* fileName);
|
||||
void WriteGCodeToFile(GCodeBuffer& gb); // Write this GCode into a file
|
||||
bool SendConfigToLine(); // Deal with M503
|
||||
void WriteHTMLToFile(GCodeBuffer& gb, char b); // Save an HTML file (usually to upload a new web interface)
|
||||
bool OffsetAxes(GCodeBuffer& gb); // Set offsets - deprecated, use G10
|
||||
void SetPidParameters(GCodeBuffer& gb, int heater, StringRef& reply); // Set the P/I/D parameters for a heater
|
||||
void SetHeaterParameters(GCodeBuffer& gb, StringRef& reply); // Set the thermistor and ADC parameters for a heater
|
||||
void ManageTool(GCodeBuffer& gb, StringRef& reply); // Create a new tool definition
|
||||
void SetToolHeaters(Tool *tool, float temperature); // Set all a tool's heaters to the temperature. For M104...
|
||||
bool ToolHeatersAtSetTemperatures(const Tool *tool, bool waitWhenCooling) const; // Wait for the heaters associated with the specified tool to reach their set temperatures
|
||||
void SetAllAxesNotHomed(); // Flag all axes as not homed
|
||||
void SetPositions(float positionNow[DRIVES]); // Set the current position to be this
|
||||
const char *TranslateEndStopResult(EndStopHit es); // Translate end stop result to text
|
||||
bool RetractFilament(bool retract); // Retract or un-retract filaments
|
||||
bool ChangeMicrostepping(size_t drive, int microsteps, int mode) const; // Change microstepping on the specified drive
|
||||
void ListTriggers(StringRef reply, TriggerMask mask); // Append a list of trigger endstops to a message
|
||||
void CheckTriggers(); // Check for and execute triggers
|
||||
void DoEmergencyStop(); // Execute an emergency stop
|
||||
void DoPause(bool externalToFile); // Pause the print
|
||||
void SetMappedFanSpeed(); // Set the speeds of fans mapped for the current tool
|
||||
|
||||
Platform* platform; // The RepRap machine
|
||||
Webserver* webserver; // The webserver class
|
||||
|
||||
GCodeBuffer* gcodeSources[6]; // The various sources of gcodes
|
||||
|
||||
GCodeBuffer*& httpGCode = gcodeSources[0];
|
||||
GCodeBuffer*& telnetGCode = gcodeSources[1];
|
||||
GCodeBuffer*& fileGCode = gcodeSources[2];
|
||||
GCodeBuffer*& serialGCode = gcodeSources[3];
|
||||
GCodeBuffer*& auxGCode = gcodeSources[4]; // This one is for the LCD display on the async serial interface
|
||||
GCodeBuffer*& daemonGCode = gcodeSources[5]; // Used for executing config.g and trigger macro files
|
||||
size_t nextGcodeSource; // The one to check next
|
||||
|
||||
const GCodeBuffer* resourceOwners[NumResources]; // Which gcode buffer owns each resource
|
||||
|
||||
bool active; // Live and running?
|
||||
bool isPaused; // true if the print has been paused
|
||||
bool dwellWaiting; // We are in a dwell
|
||||
bool moveAvailable; // Have we seen a move G Code and set it up?
|
||||
float dwellTime; // How long a pause for a dwell (seconds)?
|
||||
float feedRate; // The feed rate of the last G0/G1 command that had an F parameter
|
||||
RawMove moveBuffer; // Move details to pass to Move class
|
||||
RestorePoint simulationRestorePoint; // The position and feed rate when we started a simulation
|
||||
RestorePoint pauseRestorePoint; // The position and feed rate when we paused the print
|
||||
RestorePoint toolChangeRestorePoint; // The position and feed rate when we freed a tool
|
||||
size_t numAxes; // How many axes we have
|
||||
size_t numExtruders; // How many extruders we have, or may have
|
||||
float axisScaleFactors[MAX_AXES]; // Scale XYZ coordinates by this factor (for Delta configurations)
|
||||
float lastRawExtruderPosition[MaxExtruders]; // Extruder position of the last move fed into the Move class
|
||||
float rawExtruderTotalByDrive[MaxExtruders]; // Total extrusion amount fed to Move class since starting print, before applying extrusion factor, per drive
|
||||
float rawExtruderTotal; // Total extrusion amount fed to Move class since starting print, before applying extrusion factor, summed over all drives
|
||||
float lastRawExtruderPosition[MaxExtruders]; // Extruder position of the last move fed into the Move class
|
||||
float rawExtruderTotalByDrive[MaxExtruders]; // Total extrusion amount fed to Move class since starting print, before applying extrusion factor, per drive
|
||||
float rawExtruderTotal; // Total extrusion amount fed to Move class since starting print, before applying extrusion factor, summed over all drives
|
||||
float record[DRIVES]; // Temporary store for move positions
|
||||
float cannedMoveCoords[DRIVES]; // Where to go or how much to move by in a canned cycle move, last is feed rate
|
||||
float cannedFeedRate; // How fast to do it
|
||||
CannedMoveType cannedMoveType[DRIVES]; // Is this drive involved in a canned cycle move?
|
||||
bool offSetSet; // Are any axis offsets non-zero?
|
||||
float distanceScale; // MM or inches
|
||||
FileData fileBeingPrinted;
|
||||
FileData fileToPrint;
|
||||
FileStore* fileBeingWritten; // A file to write G Codes (or sometimes HTML) to
|
||||
uint16_t toBeHomed; // Bitmap of axes still to be homed
|
||||
bool doingFileMacro; // Are we executing a macro file?
|
||||
int oldToolNumber, newToolNumber; // Tools being changed
|
||||
const char* eofString; // What's at the end of an HTML file?
|
||||
uint8_t eofStringCounter; // Check the...
|
||||
uint8_t eofStringLength; // ... EoF string as we read.
|
||||
int probeCount; // Counts multiple probe points
|
||||
int8_t cannedCycleMoveCount; // Counts through internal (i.e. not macro) canned cycle moves
|
||||
bool cannedCycleMoveQueued; // True if a canned cycle move has been set
|
||||
float longWait; // Timer for things that happen occasionally (seconds)
|
||||
bool limitAxes; // Don't think outside the box.
|
||||
uint32_t axesHomed; // Bitmap of which axes have been homed
|
||||
float pausedFanValues[NUM_FANS]; // Fan speeds when the print was paused
|
||||
float lastDefaultFanSpeed; // Last speed given in a M106 command with on fan number
|
||||
float speedFactor; // speed factor, including the conversion from mm/min to mm/sec, normally 1/60
|
||||
float extrusionFactors[MaxExtruders]; // extrusion factors (normally 1.0)
|
||||
float distanceScale; // MM or inches
|
||||
FileData fileToPrint;
|
||||
FileStore* fileBeingWritten; // A file to write G Codes (or sometimes HTML) to
|
||||
uint16_t toBeHomed; // Bitmap of axes still to be homed
|
||||
int oldToolNumber, newToolNumber; // Tools being changed
|
||||
const char* eofString; // What's at the end of an HTML file?
|
||||
uint8_t eofStringCounter; // Check the...
|
||||
uint8_t eofStringLength; // ... EoF string as we read.
|
||||
int probeCount; // Counts multiple probe points
|
||||
int8_t cannedCycleMoveCount; // Counts through internal (i.e. not macro) canned cycle moves
|
||||
bool cannedCycleMoveQueued; // True if a canned cycle move has been set
|
||||
float longWait; // Timer for things that happen occasionally (seconds)
|
||||
bool limitAxes; // Don't think outside the box.
|
||||
uint32_t axesHomed; // Bitmap of which axes have been homed
|
||||
float pausedFanValues[NUM_FANS]; // Fan speeds when the print was paused
|
||||
float lastDefaultFanSpeed; // Last speed given in a M106 command with on fan number
|
||||
float speedFactor; // speed factor, including the conversion from mm/min to mm/sec, normally 1/60
|
||||
float extrusionFactors[MaxExtruders]; // extrusion factors (normally 1.0)
|
||||
|
||||
// Z probe
|
||||
float lastProbedZ; // the last height at which the Z probe stopped
|
||||
bool zProbesSet; // True if all Z probing is done and we can set the bed equation
|
||||
volatile bool zProbeTriggered; // Set by the step ISR when a move is aborted because the Z probe is triggered
|
||||
// Z probe
|
||||
float lastProbedZ; // the last height at which the Z probe stopped
|
||||
bool zProbesSet; // True if all Z probing is done and we can set the bed equation
|
||||
volatile bool zProbeTriggered; // Set by the step ISR when a move is aborted because the Z probe is triggered
|
||||
|
||||
float simulationTime; // Accumulated simulation time
|
||||
uint8_t simulationMode; // 0 = not simulating, 1 = simulating, >1 are simulation modes for debugging
|
||||
FilePosition filePos; // The position we got up to in the file being printed
|
||||
float simulationTime; // Accumulated simulation time
|
||||
uint8_t simulationMode; // 0 = not simulating, 1 = simulating, >1 are simulation modes for debugging
|
||||
FilePosition filePos; // The position we got up to in the file being printed
|
||||
|
||||
// Firmware retraction settings
|
||||
float retractLength, retractExtra; // retraction length and extra length to un-retract
|
||||
float retractSpeed; // retract speed in mm/min
|
||||
float unRetractSpeed; // un=retract speed in mm/min
|
||||
float retractHop; // Z hop when retracting
|
||||
// Firmware retraction settings
|
||||
float retractLength, retractExtra; // retraction length and extra length to un-retract
|
||||
float retractSpeed; // retract speed in mm/min
|
||||
float unRetractSpeed; // un=retract speed in mm/min
|
||||
float retractHop; // Z hop when retracting
|
||||
|
||||
// Triggers
|
||||
Trigger triggers[MaxTriggers]; // Trigger conditions
|
||||
TriggerMask lastEndstopStates; // States of the endstop inputs last time we looked
|
||||
static_assert(MaxTriggers <= 32, "Too many triggers");
|
||||
uint32_t triggersPending; // Bitmap of triggers pending but not yet executed
|
||||
// Triggers
|
||||
Trigger triggers[MaxTriggers]; // Trigger conditions
|
||||
TriggerMask lastEndstopStates; // States of the endstop inputs last time we looked
|
||||
static_assert(MaxTriggers <= 32, "Too many triggers");
|
||||
uint32_t triggersPending; // Bitmap of triggers pending but not yet executed
|
||||
|
||||
// Firmware update
|
||||
uint8_t firmwareUpdateModuleMap; // Bitmap of firmware modules to be updated
|
||||
// Firmware update
|
||||
uint8_t firmwareUpdateModuleMap; // Bitmap of firmware modules to be updated
|
||||
bool isFlashing; // Is a new firmware binary going to be flashed?
|
||||
|
||||
// SHA1 hashing
|
||||
|
@ -312,27 +291,17 @@ private:
|
|||
SHA1Context hash;
|
||||
bool StartHash(const char* filename);
|
||||
bool AdvanceHash(StringRef &reply);
|
||||
|
||||
// Misc
|
||||
bool isWaiting; // True if waiting to reach temperature
|
||||
bool cancelWait; // Set true to cancel waiting
|
||||
};
|
||||
|
||||
//*****************************************************************************************************
|
||||
|
||||
inline bool GCodes::DoingFileMacro() const
|
||||
{
|
||||
return doingFileMacro;
|
||||
}
|
||||
|
||||
inline bool GCodes::HaveIncomingData() const
|
||||
{
|
||||
return fileBeingPrinted.IsLive() ||
|
||||
webserver->GCodeAvailable(WebSource::HTTP) ||
|
||||
webserver->GCodeAvailable(WebSource::Telnet) ||
|
||||
platform->GCodeAvailable(SerialSource::USB) ||
|
||||
platform->GCodeAvailable(SerialSource::AUX);
|
||||
}
|
||||
|
||||
inline size_t GCodes::GetStackPointer() const
|
||||
{
|
||||
return stackPointer;
|
||||
return fileGCode->IsDoingFileMacro();
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -36,18 +36,18 @@ void Heat::Init()
|
|||
{
|
||||
if (heater == bedHeater || heater == chamberHeater)
|
||||
{
|
||||
pids[heater]->Init(DefaultBedHeaterGain, DefaultBedHeaterTimeConstant, DefaultBedHeaterDeadTime, false);
|
||||
pids[heater]->Init(DefaultBedHeaterGain, DefaultBedHeaterTimeConstant, DefaultBedHeaterDeadTime, DefaultBedTemperatureLimit, false);
|
||||
}
|
||||
#ifndef DUET_NG
|
||||
else if (heater == HEATERS - 1)
|
||||
{
|
||||
// Heater 6 pin is shared with fan 1. By default we support fan 1, so disable heater 6.
|
||||
pids[heater]->Init(-1.0, -1.0, -1.0, true);
|
||||
pids[heater]->Init(-1.0, -1.0, -1.0, DefaultExtruderTemperatureLimit, true);
|
||||
}
|
||||
#endif
|
||||
else
|
||||
{
|
||||
pids[heater]->Init(DefaultHotEndHeaterGain, DefaultHotEndHeaterTimeConstant, DefaultHotEndHeaterDeadTime, true);
|
||||
pids[heater]->Init(DefaultHotEndHeaterGain, DefaultHotEndHeaterTimeConstant, DefaultHotEndHeaterDeadTime, DefaultExtruderTemperatureLimit, true);
|
||||
}
|
||||
}
|
||||
lastTime = millis() - platform->HeatSampleInterval(); // flag the PIDS as due for spinning
|
||||
|
@ -171,6 +171,19 @@ float Heat::GetStandbyTemperature(int8_t heater) const
|
|||
return (heater >= 0 && heater < HEATERS) ? pids[heater]->GetStandbyTemperature() : ABS_ZERO;
|
||||
}
|
||||
|
||||
void Heat::SetTemperatureLimit(int8_t heater, float t)
|
||||
{
|
||||
if (heater >= 0 && heater < HEATERS)
|
||||
{
|
||||
pids[heater]->SetTemperatureLimit(t);
|
||||
}
|
||||
}
|
||||
|
||||
float Heat::GetTemperatureLimit(int8_t heater) const
|
||||
{
|
||||
return (heater >= 0 && heater < HEATERS) ? pids[heater]->GetTemperatureLimit() : ABS_ZERO;
|
||||
}
|
||||
|
||||
float Heat::GetTemperature(int8_t heater) const
|
||||
{
|
||||
return (heater >= 0 && heater < HEATERS) ? pids[heater]->GetTemperature() : ABS_ZERO;
|
||||
|
@ -264,4 +277,22 @@ void Heat::GetAutoTuneStatus(StringRef& reply) const
|
|||
}
|
||||
}
|
||||
|
||||
// Get the highest temperature limit of any heater
|
||||
float Heat::GetHighestTemperatureLimit() const
|
||||
{
|
||||
float limit = ABS_ZERO;
|
||||
for (size_t h = 0; h < HEATERS; ++h)
|
||||
{
|
||||
if (h < reprap.GetToolHeatersInUse() || (int)h == bedHeater || (int)h == chamberHeater)
|
||||
{
|
||||
const float t = pids[h]->GetTemperatureLimit();
|
||||
if (t > limit)
|
||||
{
|
||||
limit = t;
|
||||
}
|
||||
}
|
||||
}
|
||||
return limit;
|
||||
}
|
||||
|
||||
// End
|
||||
|
|
|
@ -58,6 +58,8 @@ public:
|
|||
float GetActiveTemperature(int8_t heater) const;
|
||||
void SetStandbyTemperature(int8_t heater, float t);
|
||||
float GetStandbyTemperature(int8_t heater) const;
|
||||
void SetTemperatureLimit(int8_t heater, float t);
|
||||
float GetTemperatureLimit(int8_t heater) const;
|
||||
void Activate(int8_t heater); // Turn on a heater
|
||||
void Standby(int8_t heater); // Set a heater idle
|
||||
float GetTemperature(int8_t heater) const; // Get the temperature of a heater
|
||||
|
@ -106,6 +108,8 @@ public:
|
|||
bool IsHeaterEnabled(size_t heater) const // Is this heater enabled?
|
||||
pre(heater < HEATERS);
|
||||
|
||||
float GetHighestTemperatureLimit() const; // Get the highest temperature limit of any heater
|
||||
|
||||
private:
|
||||
Platform* platform; // The instance of the RepRap hardware class
|
||||
PID* pids[HEATERS]; // A PID controller for each heater
|
||||
|
|
|
@ -31,8 +31,9 @@ PID::PID(Platform* p, int8_t h) : platform(p), heater(h), mode(HeaterMode::off)
|
|||
{
|
||||
}
|
||||
|
||||
void PID::Init(float pGain, float pTc, float pTd, bool usePid)
|
||||
void PID::Init(float pGain, float pTc, float pTd, float tempLimit, bool usePid)
|
||||
{
|
||||
temperatureLimit = tempLimit;
|
||||
maxTempExcursion = DefaultMaxTempExcursion;
|
||||
maxHeatingFaultTime = DefaultMaxHeatingFaultTime;
|
||||
model.SetParameters(pGain, pTc, pTd, 1.0, usePid);
|
||||
|
@ -108,7 +109,7 @@ TemperatureError PID::ReadTemperature()
|
|||
{
|
||||
err = TemperatureError::openCircuit;
|
||||
}
|
||||
else if (temperature > platform->GetTemperatureLimit())
|
||||
else if (temperature > temperatureLimit)
|
||||
{
|
||||
err = TemperatureError::tooHigh;
|
||||
}
|
||||
|
@ -397,7 +398,7 @@ void PID::Spin()
|
|||
|
||||
void PID::SetActiveTemperature(float t)
|
||||
{
|
||||
if (t > platform->GetTemperatureLimit())
|
||||
if (t > temperatureLimit)
|
||||
{
|
||||
platform->MessageF(GENERIC_MESSAGE, "Error: Temperature %.1f too high for heater %d!\n", t, heater);
|
||||
}
|
||||
|
@ -413,7 +414,7 @@ void PID::SetActiveTemperature(float t)
|
|||
|
||||
void PID::SetStandbyTemperature(float t)
|
||||
{
|
||||
if (t > platform->GetTemperatureLimit())
|
||||
if (t > temperatureLimit)
|
||||
{
|
||||
platform->MessageF(GENERIC_MESSAGE, "Error: Temperature %.1f too high for heater %d!\n", t, heater);
|
||||
}
|
||||
|
|
|
@ -36,13 +36,15 @@ class PID
|
|||
public:
|
||||
|
||||
PID(Platform* p, int8_t h);
|
||||
void Init(float pGain, float pTc, float pTd, bool usePid); // (Re)Set everything to start
|
||||
void Init(float pGain, float pTc, float pTd, float tempLimit, bool usePid); // (Re)Set everything to start
|
||||
void Reset();
|
||||
void Spin(); // Called in a tight loop to keep things running
|
||||
void SetActiveTemperature(float t);
|
||||
float GetActiveTemperature() const;
|
||||
void SetStandbyTemperature(float t);
|
||||
float GetStandbyTemperature() const;
|
||||
void SetTemperatureLimit(float t);
|
||||
float GetTemperatureLimit() const;
|
||||
void Activate(); // Switch from idle to active
|
||||
void Standby(); // Switch from active to idle
|
||||
bool Active() const; // Are we active?
|
||||
|
@ -60,6 +62,7 @@ public:
|
|||
|
||||
const FopDt& GetModel() const // Get the process model
|
||||
{ return model; }
|
||||
|
||||
bool SetModel(float gain, float tc, float td, float maxPwm, bool usePid); // Set the process model
|
||||
|
||||
bool IsModelUsed() const // Is the model being used to determine the PID parameters?
|
||||
|
@ -93,6 +96,7 @@ private:
|
|||
Platform* platform; // The instance of the class that is the RepRap hardware
|
||||
float activeTemperature; // The required active temperature
|
||||
float standbyTemperature; // The required standby temperature
|
||||
float temperatureLimit; // The maximum allowed temperature for this heater
|
||||
float maxTempExcursion; // The maximum temperature excursion permitted while maintaining the setpoint
|
||||
float maxHeatingFaultTime; // How long a heater fault is permitted to persist before a heater fault is raised
|
||||
float temperature; // The current temperature
|
||||
|
@ -147,6 +151,16 @@ inline float PID::GetStandbyTemperature() const
|
|||
return standbyTemperature;
|
||||
}
|
||||
|
||||
inline void PID::SetTemperatureLimit(float t)
|
||||
{
|
||||
temperatureLimit = t;
|
||||
}
|
||||
|
||||
inline float PID::GetTemperatureLimit() const
|
||||
{
|
||||
return temperatureLimit;
|
||||
}
|
||||
|
||||
inline float PID::GetTemperature() const
|
||||
{
|
||||
return temperature;
|
||||
|
|
|
@ -55,6 +55,35 @@ static size_t savedMovePointer = 0;
|
|||
|
||||
#endif
|
||||
|
||||
#if DDA_LOG_PROBE_CHANGES
|
||||
|
||||
size_t DDA::numLoggedProbePositions = 0;
|
||||
int32_t DDA::loggedProbePositions[MIN_AXES * MaxLoggedProbePositions];
|
||||
bool DDA::probeTriggered = false;
|
||||
|
||||
void DDA::LogProbePosition()
|
||||
{
|
||||
if (numLoggedProbePositions < MaxLoggedProbePositions)
|
||||
{
|
||||
int32_t *p = loggedProbePositions + (numLoggedProbePositions * MIN_AXES);
|
||||
for (size_t drive = 0; drive < MIN_AXES; ++drive)
|
||||
{
|
||||
DriveMovement& dm = ddm[drive];
|
||||
if (dm.state == DMState::moving)
|
||||
{
|
||||
p[drive] = endPoint[drive] - dm.GetNetStepsLeft();
|
||||
}
|
||||
else
|
||||
{
|
||||
p[drive] = endPoint[drive];
|
||||
}
|
||||
}
|
||||
++numLoggedProbePositions;
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
DDA::DDA(DDA* n) : next(n), prev(nullptr), state(empty)
|
||||
{
|
||||
memset(ddm, 0, sizeof(ddm)); //DEBUG to clear stepError field
|
||||
|
@ -149,7 +178,7 @@ bool DDA::Init(const GCodes::RawMove &nextMove, bool doMotorMapping)
|
|||
bool realMove = false, xyMoving = false;
|
||||
const bool isSpecialDeltaMove = (move->IsDeltaMode() && !doMotorMapping);
|
||||
float accelerations[DRIVES];
|
||||
const float *normalAccelerations = reprap.GetPlatform()->Accelerations();
|
||||
const float * const normalAccelerations = reprap.GetPlatform()->Accelerations();
|
||||
const size_t numAxes = reprap.GetGCodes()->GetNumAxes();
|
||||
for (size_t drive = 0; drive < DRIVES; drive++)
|
||||
{
|
||||
|
@ -262,7 +291,7 @@ bool DDA::Init(const GCodes::RawMove &nextMove, bool doMotorMapping)
|
|||
{
|
||||
// Pure Z movement. We can't use the main calculation because it divides by a2plusb2.
|
||||
dm.direction = (directionVector[Z_AXIS] >= 0.0);
|
||||
dm.mp.delta.reverseStartStep = dm.totalSteps + 1;
|
||||
dm.reverseStartStep = dm.totalSteps + 1;
|
||||
}
|
||||
else
|
||||
{
|
||||
|
@ -279,11 +308,11 @@ bool DDA::Init(const GCodes::RawMove &nextMove, bool doMotorMapping)
|
|||
// We may be almost at the peak height already, in which case we don't really have a reversal.
|
||||
if (numStepsUp < 1 || (dm.direction && (uint32_t)numStepsUp <= dm.totalSteps))
|
||||
{
|
||||
dm.mp.delta.reverseStartStep = dm.totalSteps + 1;
|
||||
dm.reverseStartStep = dm.totalSteps + 1;
|
||||
}
|
||||
else
|
||||
{
|
||||
dm.mp.delta.reverseStartStep = (uint32_t)numStepsUp + 1;
|
||||
dm.reverseStartStep = (uint32_t)numStepsUp + 1;
|
||||
|
||||
// Correct the initial direction and the total number of steps
|
||||
if (dm.direction)
|
||||
|
@ -301,7 +330,7 @@ bool DDA::Init(const GCodes::RawMove &nextMove, bool doMotorMapping)
|
|||
}
|
||||
else
|
||||
{
|
||||
dm.mp.delta.reverseStartStep = dm.totalSteps + 1;
|
||||
dm.reverseStartStep = dm.totalSteps + 1;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -538,7 +567,7 @@ void DDA::RecalculateMove()
|
|||
canPause = (endStopsToCheck == 0);
|
||||
if (canPause && endSpeed != 0.0)
|
||||
{
|
||||
const Platform *p = reprap.GetPlatform();
|
||||
const Platform * const p = reprap.GetPlatform();
|
||||
for (size_t drive = 0; drive < DRIVES; ++drive)
|
||||
{
|
||||
if (ddm[drive].state == DMState::moving && endSpeed * fabsf(directionVector[drive]) > p->ActualInstantDv(drive))
|
||||
|
@ -760,10 +789,10 @@ void DDA::Prepare()
|
|||
// Check for sensible values, print them if they look dubious
|
||||
if (reprap.Debug(moduleDda)
|
||||
&& ( dm.totalSteps > 1000000
|
||||
|| dm.mp.cart.reverseStartStep < dm.mp.cart.decelStartStep
|
||||
|| (dm.mp.cart.reverseStartStep <= dm.totalSteps
|
||||
&& dm.mp.cart.fourMaxStepDistanceMinusTwoDistanceToStopTimesCsquaredDivA > (int64_t)(dm.mp.cart.twoCsquaredTimesMmPerStepDivA * dm.mp.cart.reverseStartStep))
|
||||
)
|
||||
|| dm.reverseStartStep < dm.mp.cart.decelStartStep
|
||||
|| (dm.reverseStartStep <= dm.totalSteps
|
||||
&& dm.mp.cart.fourMaxStepDistanceMinusTwoDistanceToStopTimesCsquaredDivA > (int64_t)(dm.mp.cart.twoCsquaredTimesMmPerStepDivA * dm.reverseStartStep))
|
||||
)
|
||||
)
|
||||
{
|
||||
DebugPrint();
|
||||
|
@ -828,6 +857,69 @@ void DDA::Prepare()
|
|||
state = frozen; // must do this last so that the ISR doesn't start executing it before we have finished setting it up
|
||||
}
|
||||
|
||||
// Take a unit positive-hyperquadrant vector, and return the factor needed to obtain
|
||||
// length of the vector as projected to touch box[].
|
||||
float DDA::VectorBoxIntersection(const float v[], const float box[], size_t dimensions)
|
||||
{
|
||||
// Generate a vector length that is guaranteed to exceed the size of the box
|
||||
float biggerThanBoxDiagonal = 2.0*Magnitude(box, dimensions);
|
||||
float magnitude = biggerThanBoxDiagonal;
|
||||
for (size_t d = 0; d < dimensions; d++)
|
||||
{
|
||||
if (biggerThanBoxDiagonal*v[d] > box[d])
|
||||
{
|
||||
float a = box[d]/v[d];
|
||||
if (a < magnitude)
|
||||
{
|
||||
magnitude = a;
|
||||
}
|
||||
}
|
||||
}
|
||||
return magnitude;
|
||||
}
|
||||
|
||||
// Normalise a vector with dim1 dimensions so that it is unit in the first dim2 dimensions, and also return its previous magnitude in dim2 dimensions
|
||||
float DDA::Normalise(float v[], size_t dim1, size_t dim2)
|
||||
{
|
||||
float magnitude = Magnitude(v, dim2);
|
||||
if (magnitude <= 0.0)
|
||||
{
|
||||
return 0.0;
|
||||
}
|
||||
Scale(v, 1.0/magnitude, dim1);
|
||||
return magnitude;
|
||||
}
|
||||
|
||||
// Return the magnitude of a vector
|
||||
float DDA::Magnitude(const float v[], size_t dimensions)
|
||||
{
|
||||
float magnitude = 0.0;
|
||||
for (size_t d = 0; d < dimensions; d++)
|
||||
{
|
||||
magnitude += v[d]*v[d];
|
||||
}
|
||||
magnitude = sqrtf(magnitude);
|
||||
return magnitude;
|
||||
}
|
||||
|
||||
// Multiply a vector by a scalar
|
||||
void DDA::Scale(float v[], float scale, size_t dimensions)
|
||||
{
|
||||
for(size_t d = 0; d < dimensions; d++)
|
||||
{
|
||||
v[d] = scale*v[d];
|
||||
}
|
||||
}
|
||||
|
||||
// Move a vector into the positive hyperquadrant
|
||||
void DDA::Absolute(float v[], size_t dimensions)
|
||||
{
|
||||
for(size_t d = 0; d < dimensions; d++)
|
||||
{
|
||||
v[d] = fabsf(v[d]);
|
||||
}
|
||||
}
|
||||
|
||||
// The remaining functions are speed-critical, so use full optimisation
|
||||
#pragma GCC optimize ("O3")
|
||||
|
||||
|
@ -839,12 +931,15 @@ pre(state == frozen)
|
|||
moveStartTime = tim;
|
||||
state = executing;
|
||||
|
||||
if (firstDM == nullptr)
|
||||
#if DDA_LOG_PROBE_CHANGES
|
||||
if ((endStopsToCheck & LogProbeChanges) != 0)
|
||||
{
|
||||
// No steps are pending. This should not happen!
|
||||
return true; // schedule another interrupt immediately
|
||||
numLoggedProbePositions = 0;
|
||||
probeTriggered = false;
|
||||
}
|
||||
else
|
||||
#endif
|
||||
|
||||
if (firstDM != nullptr)
|
||||
{
|
||||
unsigned int extrusions = 0, retractions = 0; // bitmaps of extruding and retracting drives
|
||||
const size_t numAxes = reprap.GetGCodes()->GetNumAxes();
|
||||
|
@ -887,7 +982,7 @@ pre(state == frozen)
|
|||
}
|
||||
}
|
||||
|
||||
Platform *platform = reprap.GetPlatform();
|
||||
Platform * const platform = reprap.GetPlatform();
|
||||
if (extruding)
|
||||
{
|
||||
platform->ExtrudeOn();
|
||||
|
@ -901,11 +996,10 @@ pre(state == frozen)
|
|||
{
|
||||
return platform->ScheduleInterrupt(firstDM->nextStepTime + moveStartTime);
|
||||
}
|
||||
else
|
||||
{
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
// No steps are pending. This should not happen, except perhaps for an extrude-only move when extrusion is prohibited
|
||||
return true; // schedule another interrupt immediately
|
||||
}
|
||||
|
||||
extern uint32_t maxReps;
|
||||
|
@ -915,7 +1009,7 @@ extern uint32_t maxReps;
|
|||
// This must be as fast as possible, because it determines the maximum movement speed.
|
||||
bool DDA::Step()
|
||||
{
|
||||
Platform *platform = reprap.GetPlatform();
|
||||
Platform * const platform = reprap.GetPlatform();
|
||||
uint32_t lastStepPulseTime = platform->GetInterruptClocks();
|
||||
bool repeat;
|
||||
uint32_t numReps = 0;
|
||||
|
@ -946,6 +1040,33 @@ bool DDA::Step()
|
|||
}
|
||||
}
|
||||
|
||||
#if DDA_LOG_PROBE_CHANGES
|
||||
else if ((endStopsToCheck & LogProbeChanges) != 0)
|
||||
{
|
||||
switch (platform->GetZProbeResult())
|
||||
{
|
||||
case EndStopHit::lowHit:
|
||||
if (!probeTriggered)
|
||||
{
|
||||
probeTriggered = true;
|
||||
LogProbePosition();
|
||||
}
|
||||
break;
|
||||
|
||||
case EndStopHit::lowNear:
|
||||
case EndStopHit::noStop:
|
||||
if (probeTriggered)
|
||||
{
|
||||
probeTriggered = false;
|
||||
LogProbePosition();
|
||||
}
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
const size_t numAxes = reprap.GetGCodes()->GetNumAxes();
|
||||
for (size_t drive = 0; drive < numAxes; ++drive)
|
||||
{
|
||||
|
@ -1089,15 +1210,7 @@ void DDA::StopDrive(size_t drive)
|
|||
DriveMovement& dm = ddm[drive];
|
||||
if (dm.state == DMState::moving)
|
||||
{
|
||||
int32_t stepsLeft = dm.totalSteps - dm.nextStep + 1;
|
||||
if (dm.direction)
|
||||
{
|
||||
endPoint[drive] -= stepsLeft; // we were going forwards
|
||||
}
|
||||
else
|
||||
{
|
||||
endPoint[drive] += stepsLeft; // we were going backwards
|
||||
}
|
||||
endPoint[drive] -= dm.GetNetStepsLeft();
|
||||
dm.state = DMState::idle;
|
||||
if (drive < reprap.GetGCodes()->GetNumAxes())
|
||||
{
|
||||
|
@ -1184,67 +1297,4 @@ DriveMovement *DDA::RemoveDM(size_t drive)
|
|||
return nullptr;
|
||||
}
|
||||
|
||||
// Take a unit positive-hyperquadrant vector, and return the factor needed to obtain
|
||||
// length of the vector as projected to touch box[].
|
||||
float DDA::VectorBoxIntersection(const float v[], const float box[], size_t dimensions)
|
||||
{
|
||||
// Generate a vector length that is guaranteed to exceed the size of the box
|
||||
float biggerThanBoxDiagonal = 2.0*Magnitude(box, dimensions);
|
||||
float magnitude = biggerThanBoxDiagonal;
|
||||
for (size_t d = 0; d < dimensions; d++)
|
||||
{
|
||||
if (biggerThanBoxDiagonal*v[d] > box[d])
|
||||
{
|
||||
float a = box[d]/v[d];
|
||||
if (a < magnitude)
|
||||
{
|
||||
magnitude = a;
|
||||
}
|
||||
}
|
||||
}
|
||||
return magnitude;
|
||||
}
|
||||
|
||||
// Normalise a vector with dim1 dimensions so that it is unit in the first dim2 dimensions, and also return its previous magnitude in dim2 dimensions
|
||||
float DDA::Normalise(float v[], size_t dim1, size_t dim2)
|
||||
{
|
||||
float magnitude = Magnitude(v, dim2);
|
||||
if (magnitude <= 0.0)
|
||||
{
|
||||
return 0.0;
|
||||
}
|
||||
Scale(v, 1.0/magnitude, dim1);
|
||||
return magnitude;
|
||||
}
|
||||
|
||||
// Return the magnitude of a vector
|
||||
float DDA::Magnitude(const float v[], size_t dimensions)
|
||||
{
|
||||
float magnitude = 0.0;
|
||||
for (size_t d = 0; d < dimensions; d++)
|
||||
{
|
||||
magnitude += v[d]*v[d];
|
||||
}
|
||||
magnitude = sqrtf(magnitude);
|
||||
return magnitude;
|
||||
}
|
||||
|
||||
// Multiply a vector by a scalar
|
||||
void DDA::Scale(float v[], float scale, size_t dimensions)
|
||||
{
|
||||
for(size_t d = 0; d < dimensions; d++)
|
||||
{
|
||||
v[d] = scale*v[d];
|
||||
}
|
||||
}
|
||||
|
||||
// Move a vector into the positive hyperquadrant
|
||||
void DDA::Absolute(float v[], size_t dimensions)
|
||||
{
|
||||
for(size_t d = 0; d < dimensions; d++)
|
||||
{
|
||||
v[d] = fabsf(v[d]);
|
||||
}
|
||||
}
|
||||
|
||||
// End
|
||||
|
|
|
@ -10,6 +10,12 @@
|
|||
|
||||
#include "DriveMovement.h"
|
||||
|
||||
#ifdef DUET_NG
|
||||
#define DDA_LOG_PROBE_CHANGES 1
|
||||
#else
|
||||
#define DDA_LOG_PROBE_CHANGES 0 // save memory on the wired Duet
|
||||
#endif
|
||||
|
||||
/**
|
||||
* This defines a single linear movement of the print head
|
||||
*/
|
||||
|
@ -80,6 +86,12 @@ public:
|
|||
|
||||
static void PrintMoves(); // print saved moves for debugging
|
||||
|
||||
#if DDA_LOG_PROBE_CHANGES
|
||||
static const size_t MaxLoggedProbePositions = 40;
|
||||
static size_t numLoggedProbePositions;
|
||||
static int32_t loggedProbePositions[MIN_AXES * MaxLoggedProbePositions];
|
||||
#endif
|
||||
|
||||
private:
|
||||
void RecalculateMove();
|
||||
void CalcNewSpeeds();
|
||||
|
@ -140,6 +152,12 @@ private:
|
|||
uint32_t clocksNeeded; // in clocks
|
||||
uint32_t moveStartTime; // clock count at which the move was started
|
||||
|
||||
#if DDA_LOG_PROBE_CHANGES
|
||||
static bool probeTriggered;
|
||||
|
||||
void LogProbePosition();
|
||||
#endif
|
||||
|
||||
DriveMovement* firstDM; // the contained DM that needs the first step
|
||||
|
||||
DriveMovement ddm[DRIVES]; // These describe the state of each drive movement
|
||||
|
|
|
@ -39,7 +39,7 @@ void DriveMovement::PrepareCartesianAxis(const DDA& dda, const PrepParams& param
|
|||
}
|
||||
|
||||
// No reverse phase
|
||||
mp.cart.reverseStartStep = totalSteps + 1;
|
||||
reverseStartStep = totalSteps + 1;
|
||||
mp.cart.fourMaxStepDistanceMinusTwoDistanceToStopTimesCsquaredDivA = 0;
|
||||
}
|
||||
|
||||
|
@ -106,7 +106,7 @@ void DriveMovement::PrepareExtruder(const DDA& dda, const PrepParams& params, bo
|
|||
if (dda.decelDistance * stepsPerMm < 0.5) // if less than 1 deceleration step
|
||||
{
|
||||
totalSteps = (uint)max<int32_t>(netSteps, 0);
|
||||
mp.cart.decelStartStep = mp.cart.reverseStartStep = netSteps + 1;
|
||||
mp.cart.decelStartStep = reverseStartStep = netSteps + 1;
|
||||
topSpeedTimesCdivAPlusDecelStartClocks = 0;
|
||||
mp.cart.fourMaxStepDistanceMinusTwoDistanceToStopTimesCsquaredDivA = 0;
|
||||
twoDistanceToStopTimesCsquaredDivA = 0;
|
||||
|
@ -130,27 +130,27 @@ void DriveMovement::PrepareExtruder(const DDA& dda, const PrepParams& params, bo
|
|||
{
|
||||
// No reverse phase
|
||||
totalSteps = (uint)max<int32_t>(netSteps, 0);
|
||||
mp.cart.reverseStartStep = netSteps + 1;
|
||||
reverseStartStep = netSteps + 1;
|
||||
mp.cart.fourMaxStepDistanceMinusTwoDistanceToStopTimesCsquaredDivA = 0;
|
||||
}
|
||||
else
|
||||
{
|
||||
mp.cart.reverseStartStep = (initialDecelSpeed < 0.0)
|
||||
? mp.cart.decelStartStep
|
||||
: (twoDistanceToStopTimesCsquaredDivA/mp.cart.twoCsquaredTimesMmPerStepDivA) + 1;
|
||||
reverseStartStep = (initialDecelSpeed < 0.0)
|
||||
? mp.cart.decelStartStep
|
||||
: (twoDistanceToStopTimesCsquaredDivA/mp.cart.twoCsquaredTimesMmPerStepDivA) + 1;
|
||||
// Because the step numbers are rounded down, we may sometimes get a situation in which netSteps = 1 and reverseStartStep = 1.
|
||||
// This would lead to totalSteps = -1, which must be avoided.
|
||||
const int32_t overallSteps = (int32_t)(2 * (mp.cart.reverseStartStep - 1)) - netSteps;
|
||||
const int32_t overallSteps = (int32_t)(2 * (reverseStartStep - 1)) - netSteps;
|
||||
if (overallSteps > 0)
|
||||
{
|
||||
totalSteps = overallSteps;
|
||||
mp.cart.fourMaxStepDistanceMinusTwoDistanceToStopTimesCsquaredDivA =
|
||||
(int64_t)((2 * (mp.cart.reverseStartStep - 1)) * mp.cart.twoCsquaredTimesMmPerStepDivA) - (int64_t)twoDistanceToStopTimesCsquaredDivA;
|
||||
(int64_t)((2 * (reverseStartStep - 1)) * mp.cart.twoCsquaredTimesMmPerStepDivA) - (int64_t)twoDistanceToStopTimesCsquaredDivA;
|
||||
}
|
||||
else
|
||||
{
|
||||
totalSteps = (uint)max<int32_t>(netSteps, 0);
|
||||
mp.cart.reverseStartStep = totalSteps + 1;
|
||||
reverseStartStep = totalSteps + 1;
|
||||
mp.cart.fourMaxStepDistanceMinusTwoDistanceToStopTimesCsquaredDivA = 0;
|
||||
}
|
||||
}
|
||||
|
@ -161,25 +161,24 @@ void DriveMovement::DebugPrint(char c, bool isDeltaMovement) const
|
|||
{
|
||||
if (state != DMState::idle)
|
||||
{
|
||||
debugPrintf("DM%c%s dir=%c steps=%u next=%u interval=%u sstcda=%u "
|
||||
debugPrintf("DM%c%s dir=%c steps=%u next=%u rev=%u interval=%u sstcda=%u "
|
||||
"acmadtcdts=%d tstcdapdsc=%u 2dtstc2diva=%" PRIu64 "\n",
|
||||
c, (state == DMState::stepError) ? " ERR:" : ":", (direction) ? 'F' : 'B', totalSteps, nextStep, stepInterval, startSpeedTimesCdivA,
|
||||
c, (state == DMState::stepError) ? " ERR:" : ":", (direction) ? 'F' : 'B', totalSteps, nextStep, reverseStartStep, stepInterval, startSpeedTimesCdivA,
|
||||
accelClocksMinusAccelDistanceTimesCdivTopSpeed, topSpeedTimesCdivAPlusDecelStartClocks, twoDistanceToStopTimesCsquaredDivA);
|
||||
|
||||
if (isDeltaMovement)
|
||||
{
|
||||
debugPrintf("revss=%d hmz0sK=%d minusAaPlusBbTimesKs=%d dSquaredMinusAsquaredMinusBsquared=%" PRId64 "\n"
|
||||
debugPrintf("hmz0sK=%d minusAaPlusBbTimesKs=%d dSquaredMinusAsquaredMinusBsquared=%" PRId64 "\n"
|
||||
"2c2mmsdak=%u asdsk=%u dsdsk=%u mmstcdts=%u\n",
|
||||
mp.delta.reverseStartStep, mp.delta.hmz0sK, mp.delta.minusAaPlusBbTimesKs, mp.delta.dSquaredMinusAsquaredMinusBsquaredTimesKsquaredSsquared,
|
||||
mp.delta.hmz0sK, mp.delta.minusAaPlusBbTimesKs, mp.delta.dSquaredMinusAsquaredMinusBsquaredTimesKsquaredSsquared,
|
||||
mp.delta.twoCsquaredTimesMmPerStepDivAK, mp.delta.accelStopDsK, mp.delta.decelStartDsK, mp.delta.mmPerStepTimesCdivtopSpeedK
|
||||
);
|
||||
}
|
||||
else
|
||||
{
|
||||
debugPrintf("accelStopStep=%u decelStartStep=%u revStartStep=%u nextStep=%u nextStepTime=%u 2CsqtMmPerStepDivA=%" PRIu64 "\n",
|
||||
mp.cart.accelStopStep, mp.cart.decelStartStep, mp.cart.reverseStartStep, nextStep, nextStepTime, mp.cart.twoCsquaredTimesMmPerStepDivA
|
||||
);
|
||||
debugPrintf(" mmPerStepTimesCdivtopSpeed=%u fmsdmtstdca2=%" PRId64 "\n",
|
||||
debugPrintf("accelStopStep=%u decelStartStep=%u 2CsqtMmPerStepDivA=%" PRIu64 "\n"
|
||||
"mmPerStepTimesCdivtopSpeed=%u fmsdmtstdca2=%" PRId64 "\n",
|
||||
mp.cart.accelStopStep, mp.cart.decelStartStep, mp.cart.twoCsquaredTimesMmPerStepDivA,
|
||||
mp.cart.mmPerStepTimesCdivtopSpeed, mp.cart.fourMaxStepDistanceMinusTwoDistanceToStopTimesCsquaredDivA
|
||||
);
|
||||
}
|
||||
|
@ -203,8 +202,8 @@ pre(nextStep < totalSteps; stepsTillRecalc == 0)
|
|||
uint32_t shiftFactor;
|
||||
if (stepInterval < DDA::MinCalcIntervalCartesian)
|
||||
{
|
||||
uint32_t stepsToLimit = ((nextStep <= mp.cart.reverseStartStep && mp.cart.reverseStartStep <= totalSteps)
|
||||
? mp.cart.reverseStartStep
|
||||
uint32_t stepsToLimit = ((nextStep <= reverseStartStep && reverseStartStep <= totalSteps)
|
||||
? reverseStartStep
|
||||
: totalSteps
|
||||
) - nextStep;
|
||||
if (stepInterval < DDA::MinCalcIntervalCartesian/4 && stepsToLimit > 8)
|
||||
|
@ -242,7 +241,7 @@ pre(nextStep < totalSteps; stepsTillRecalc == 0)
|
|||
// steady speed phase
|
||||
nextStepTime = (uint32_t)((int32_t)(((uint64_t)mp.cart.mmPerStepTimesCdivtopSpeed * nextCalcStep)/K1) + accelClocksMinusAccelDistanceTimesCdivTopSpeed);
|
||||
}
|
||||
else if (nextCalcStep < mp.cart.reverseStartStep)
|
||||
else if (nextCalcStep < reverseStartStep)
|
||||
{
|
||||
// deceleration phase, not reversed yet
|
||||
uint64_t temp = mp.cart.twoCsquaredTimesMmPerStepDivA * nextCalcStep;
|
||||
|
@ -254,7 +253,7 @@ pre(nextStep < totalSteps; stepsTillRecalc == 0)
|
|||
else
|
||||
{
|
||||
// deceleration phase, reversing or already reversed
|
||||
if (nextCalcStep == mp.cart.reverseStartStep)
|
||||
if (nextCalcStep == reverseStartStep)
|
||||
{
|
||||
direction = !direction;
|
||||
if (live)
|
||||
|
@ -299,8 +298,8 @@ pre(nextStep < totalSteps; stepsTillRecalc == 0)
|
|||
uint32_t shiftFactor;
|
||||
if (stepInterval < DDA::MinCalcIntervalDelta)
|
||||
{
|
||||
const uint32_t stepsToLimit = ((nextStep < mp.delta.reverseStartStep && mp.delta.reverseStartStep <= totalSteps)
|
||||
? mp.delta.reverseStartStep
|
||||
const uint32_t stepsToLimit = ((nextStep < reverseStartStep && reverseStartStep <= totalSteps)
|
||||
? reverseStartStep
|
||||
: totalSteps
|
||||
) - nextStep;
|
||||
if (stepInterval < DDA::MinCalcIntervalDelta/8 && stepsToLimit > 16)
|
||||
|
@ -330,7 +329,7 @@ pre(nextStep < totalSteps; stepsTillRecalc == 0)
|
|||
}
|
||||
stepsTillRecalc = (1u << shiftFactor) - 1; // store number of additional steps to generate
|
||||
|
||||
if (nextStep == mp.delta.reverseStartStep)
|
||||
if (nextStep == reverseStartStep)
|
||||
{
|
||||
direction = false;
|
||||
if (live)
|
||||
|
|
|
@ -40,6 +40,7 @@ public:
|
|||
void PrepareExtruder(const DDA& dda, const PrepParams& params, bool doCompensation);
|
||||
void ReduceSpeed(const DDA& dda, float inverseSpeedFactor);
|
||||
void DebugPrint(char c, bool withDelta) const;
|
||||
int32_t GetNetStepsLeft() const;
|
||||
|
||||
private:
|
||||
bool CalcNextStepTimeCartesianFull(const DDA &dda, bool live);
|
||||
|
@ -63,6 +64,7 @@ public:
|
|||
|
||||
// These values change as the step is executed
|
||||
uint32_t nextStep; // number of steps already done
|
||||
uint32_t reverseStartStep; // the step number for which we need to reverse direction due to pressure advance or delta movement
|
||||
uint32_t nextStepTime; // how many clocks after the start of this move the next step is due
|
||||
uint32_t stepInterval; // how many clocks between steps
|
||||
DriveMovement *nextDM; // link to next DM that needs a step
|
||||
|
@ -78,7 +80,6 @@ public:
|
|||
// The following depend on how the move is executed, so they must be set up in Prepare()
|
||||
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 reverseStartStep; // the first step number for which we need to reverse direction due to pressure advance
|
||||
uint32_t mmPerStepTimesCdivtopSpeed; // mmPerStepInHyperCuboidSpace * clock / topSpeed
|
||||
|
||||
// The following only need to be stored per-drive if we are supporting pressure advance
|
||||
|
@ -89,7 +90,6 @@ public:
|
|||
{
|
||||
// The following don't depend on how the move is executed, so they can be set up in Init
|
||||
int64_t dSquaredMinusAsquaredMinusBsquaredTimesKsquaredSsquared;
|
||||
uint32_t reverseStartStep;
|
||||
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;
|
||||
uint32_t twoCsquaredTimesMmPerStepDivAK; // this could be stored in the DDA if all towers use the same steps/mm
|
||||
|
@ -150,4 +150,16 @@ inline bool DriveMovement::CalcNextStepTimeDelta(const DDA &dda, bool live)
|
|||
return false;
|
||||
}
|
||||
|
||||
// Return the number of net steps left for the move in the forwards direction.
|
||||
inline int32_t DriveMovement::GetNetStepsLeft() const
|
||||
{
|
||||
const int32_t netStepsLeft =
|
||||
( (nextStep >= reverseStartStep || reverseStartStep >= totalSteps)
|
||||
? totalSteps // no reverse due, or we have already reversed
|
||||
: 2 * reverseStartStep - totalSteps // we have yet to reverse
|
||||
)
|
||||
- nextStep + 1;
|
||||
return (direction) ? netStepsLeft : -netStepsLeft;
|
||||
}
|
||||
|
||||
#endif /* DRIVEMOVEMENT_H_ */
|
||||
|
|
|
@ -423,13 +423,28 @@ extern uint64_t lastNum;
|
|||
|
||||
void Move::Diagnostics(MessageType mtype)
|
||||
{
|
||||
reprap.GetPlatform()->Message(mtype, "=== Move ===\n");
|
||||
reprap.GetPlatform()->MessageF(mtype, "MaxReps: %u, StepErrors: %u, MaxWait: %ums, Underruns: %u, %u\n",
|
||||
Platform * const p = reprap.GetPlatform();
|
||||
p->Message(mtype, "=== Move ===\n");
|
||||
p->MessageF(mtype, "MaxReps: %u, StepErrors: %u, MaxWait: %ums, Underruns: %u, %u\n",
|
||||
maxReps, stepErrors, longestGcodeWaitInterval, numLookaheadUnderruns, numPrepareUnderruns);
|
||||
maxReps = 0;
|
||||
numLookaheadUnderruns = numPrepareUnderruns = 0;
|
||||
longestGcodeWaitInterval = 0;
|
||||
|
||||
#if DDA_LOG_PROBE_CHANGES
|
||||
// Temporary code to print Z probe trigger positions
|
||||
p->Message(mtype, "Probe change coordinates:");
|
||||
char ch = ' ';
|
||||
for (size_t i = 0; i < DDA::numLoggedProbePositions; ++i)
|
||||
{
|
||||
float xyzPos[MIN_AXES];
|
||||
MachineToEndPoint(DDA::loggedProbePositions + (MIN_AXES * i), xyzPos, MIN_AXES);
|
||||
p->MessageF(mtype, "%c%.2f,%.2f", ch, xyzPos[X_AXIS], xyzPos[Y_AXIS]);
|
||||
ch = ',';
|
||||
}
|
||||
p->Message(mtype, "\n");
|
||||
#endif
|
||||
|
||||
#if 0
|
||||
// For debugging
|
||||
if (sqCount != 0)
|
||||
|
@ -1170,7 +1185,7 @@ void Move::DeltaProbeInterrupt()
|
|||
}
|
||||
|
||||
bool dir = deltaProbe.GetDirection();
|
||||
Platform *platform = reprap.GetPlatform();
|
||||
Platform * const platform = reprap.GetPlatform();
|
||||
platform->SetDirection(X_AXIS, dir);
|
||||
platform->SetDirection(Y_AXIS, dir);
|
||||
platform->SetDirection(Z_AXIS, dir);
|
||||
|
@ -1535,7 +1550,7 @@ int Move::DoDeltaProbe(float frequency, float amplitude, float rate, float dista
|
|||
const uint32_t firstInterruptTime = deltaProbe.Start();
|
||||
if (firstInterruptTime != 0xFFFFFFFF)
|
||||
{
|
||||
Platform *platform = reprap.GetPlatform();
|
||||
Platform * const platform = reprap.GetPlatform();
|
||||
platform->EnableDrive(X_AXIS);
|
||||
platform->EnableDrive(Y_AXIS);
|
||||
platform->EnableDrive(Z_AXIS);
|
||||
|
|
|
@ -369,7 +369,6 @@ void Platform::Init()
|
|||
THERMISTOR_SERIES_RS); // initialise the thermistor parameters
|
||||
thermistorFilters[heater].Init(0);
|
||||
}
|
||||
SetTemperatureLimit(DEFAULT_TEMPERATURE_LIMIT);
|
||||
|
||||
// Fans
|
||||
InitFans();
|
||||
|
@ -450,14 +449,8 @@ bool Platform::AnyFileOpen(const FATFS *fs) const
|
|||
return false;
|
||||
}
|
||||
|
||||
void Platform::SetTemperatureLimit(float t)
|
||||
{
|
||||
temperatureLimit = t;
|
||||
}
|
||||
|
||||
// Specify which thermistor channel a particular heater uses
|
||||
void Platform::SetThermistorNumber(size_t heater, size_t thermistor)
|
||||
pre(heater < HEATERS && thermistor < HEATERS)
|
||||
{
|
||||
heaterTempChannels[heater] = thermistor;
|
||||
|
||||
|
@ -1635,7 +1628,6 @@ void Platform::SetPidParameters(size_t heater, const PidParameters& params)
|
|||
{
|
||||
WriteNvData();
|
||||
}
|
||||
SetTemperatureLimit(temperatureLimit); // recalculate the thermistor resistance at max allowed temperature for the tick ISR
|
||||
}
|
||||
}
|
||||
const PidParameters& Platform::GetPidParameters(size_t heater) const
|
||||
|
@ -2221,11 +2213,24 @@ void Platform::AppendAuxReply(const char *msg)
|
|||
// Discard this response if either no aux device is attached or if the response is empty
|
||||
if (msg[0] != 0 && HaveAux())
|
||||
{
|
||||
// Regular text-based responses for AUX are currently stored and processed by M105/M408
|
||||
if (auxGCodeReply != nullptr || OutputBuffer::Allocate(auxGCodeReply))
|
||||
if (msg[0] == '{')
|
||||
{
|
||||
auxSeq++;
|
||||
auxGCodeReply->cat(msg);
|
||||
// JSON responses are always sent directly to the AUX device
|
||||
OutputBuffer *buf;
|
||||
if (OutputBuffer::Allocate(buf))
|
||||
{
|
||||
buf->copy(msg);
|
||||
auxOutput->Push(buf);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
// Regular text-based responses for AUX are currently stored and processed by M105/M408
|
||||
if (auxGCodeReply != nullptr || OutputBuffer::Allocate(auxGCodeReply))
|
||||
{
|
||||
auxSeq++;
|
||||
auxGCodeReply->cat(msg);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -2304,22 +2309,6 @@ void Platform::Message(MessageType type, const char *message)
|
|||
usbOutput->Push(usbOutputBuffer);
|
||||
}
|
||||
|
||||
// Check if we need to write the indentation chars first
|
||||
const size_t stackPointer = reprap.GetGCodes()->GetStackPointer();
|
||||
if (stackPointer > 0)
|
||||
{
|
||||
// First, make sure we get the indentation right
|
||||
char indentation[StackSize * 2 + 1];
|
||||
for(size_t i = 0; i < stackPointer * 2; i++)
|
||||
{
|
||||
indentation[i] = ' ';
|
||||
}
|
||||
indentation[stackPointer * 2] = 0;
|
||||
|
||||
// Append the indentation string
|
||||
usbOutputBuffer->cat(indentation);
|
||||
}
|
||||
|
||||
// Append the message string
|
||||
usbOutputBuffer->cat(message);
|
||||
}
|
||||
|
@ -2667,7 +2656,7 @@ bool Platform::GetFirmwarePin(int logicalPin, PinAccess access, Pin& firmwarePin
|
|||
}
|
||||
else if (access == PinAccess::pwm || access == PinAccess::servo)
|
||||
{
|
||||
desiredMode = OUTPUT_PWM;
|
||||
desiredMode = (invert) ? OUTPUT_PWM_HIGH : OUTPUT_PWM_LOW;
|
||||
}
|
||||
else
|
||||
{
|
||||
|
|
|
@ -481,10 +481,10 @@ public:
|
|||
void SetPhysicalDrives(size_t drive, uint32_t physicalDrives);
|
||||
uint32_t GetPhysicalDrives(size_t drive) const;
|
||||
void SetDirection(size_t drive, bool direction);
|
||||
void SetDirectionValue(size_t drive, bool dVal);
|
||||
bool GetDirectionValue(size_t drive) const;
|
||||
void SetEnableValue(size_t drive, bool eVal);
|
||||
bool GetEnableValue(size_t drive) const;
|
||||
void SetDirectionValue(size_t driver, bool dVal);
|
||||
bool GetDirectionValue(size_t driver) const;
|
||||
void SetEnableValue(size_t driver, bool eVal);
|
||||
bool GetEnableValue(size_t driver) const;
|
||||
void EnableDriver(size_t driver);
|
||||
void DisableDriver(size_t driver);
|
||||
void EnableDrive(size_t drive);
|
||||
|
@ -565,26 +565,43 @@ public:
|
|||
|
||||
// Heat and temperature
|
||||
|
||||
float GetTemperature(size_t heater, TemperatureError& err); // Result is in degrees Celsius
|
||||
float GetTemperature(size_t heater, TemperatureError& err) // Result is in degrees Celsius
|
||||
pre (heater < HEATERS);
|
||||
|
||||
float GetZProbeTemperature(); // Get our best estimate of the Z probe temperature
|
||||
void SetHeater(size_t heater, float power); // power is a fraction in [0,1]
|
||||
|
||||
void SetHeater(size_t heater, float power) // power is a fraction in [0,1]
|
||||
pre (heater < HEATERS);
|
||||
|
||||
uint32_t HeatSampleInterval() const;
|
||||
void SetHeatSampleTime(float st);
|
||||
float GetHeatSampleTime() const;
|
||||
void SetPidParameters(size_t heater, const PidParameters& params);
|
||||
const PidParameters& GetPidParameters(size_t heater) const;
|
||||
|
||||
const PidParameters& GetPidParameters(size_t heater) const
|
||||
pre (heater < HEATERS);
|
||||
|
||||
Thermistor& GetThermistor(size_t heater)
|
||||
pre (heater < HEATERS)
|
||||
{
|
||||
return thermistors[heater];
|
||||
}
|
||||
void SetThermistorNumber(size_t heater, size_t thermistor);
|
||||
int GetThermistorNumber(size_t heater) const;
|
||||
bool IsThermistorChannel(uint8_t heater) const;
|
||||
bool IsThermocoupleChannel(uint8_t heater) const;
|
||||
bool IsRtdChannel(uint8_t heater) const;
|
||||
void SetTemperatureLimit(float t);
|
||||
float GetTemperatureLimit() const { return temperatureLimit; }
|
||||
|
||||
void SetThermistorNumber(size_t heater, size_t thermistor)
|
||||
pre(heater < HEATERS; thermistor < HEATERS);
|
||||
|
||||
int GetThermistorNumber(size_t heater) const
|
||||
pre (heater < HEATERS);
|
||||
|
||||
bool IsThermistorChannel(uint8_t heater) const
|
||||
pre(heater < HEATERS);
|
||||
|
||||
bool IsThermocoupleChannel(uint8_t heater) const
|
||||
pre(heater < HEATERS);
|
||||
|
||||
bool IsRtdChannel(uint8_t heater) const
|
||||
pre(heater < HEATERS);
|
||||
|
||||
void UpdateConfiguredHeaters();
|
||||
bool AnyHeaterHot(uint16_t heaters, float t); // called to see if we need to turn on the hot end fan
|
||||
|
||||
|
@ -722,7 +739,9 @@ private:
|
|||
|
||||
void SetDriverCurrent(size_t driver, float current, bool isPercent);
|
||||
void UpdateMotorCurrent(size_t driver);
|
||||
void SetDriverDirection(uint8_t driver, bool direction);
|
||||
void SetDriverDirection(uint8_t driver, bool direction)
|
||||
pre(driver < DRIVES);
|
||||
|
||||
static uint32_t CalcDriverBitmap(size_t driver); // calculate the step bit for this driver
|
||||
|
||||
volatile DriverStatus driverState[DRIVES];
|
||||
|
@ -786,7 +805,6 @@ private:
|
|||
Pin spiTempSenseCsPins[MaxSpiTempSensors];
|
||||
uint32_t configuredHeaters; // bitmask of all heaters in use
|
||||
uint32_t heatSampleTicks;
|
||||
float temperatureLimit;
|
||||
|
||||
// Fans
|
||||
|
||||
|
@ -1048,21 +1066,19 @@ inline bool Platform::GetDirectionValue(size_t drive) const
|
|||
|
||||
inline void Platform::SetDriverDirection(uint8_t driver, bool direction)
|
||||
{
|
||||
if (driver < DRIVES)
|
||||
{
|
||||
bool d = (direction == FORWARDS) ? directions[driver] : !directions[driver];
|
||||
digitalWrite(DIRECTION_PINS[driver], d);
|
||||
}
|
||||
bool d = (direction == FORWARDS) ? directions[driver] : !directions[driver];
|
||||
digitalWrite(DIRECTION_PINS[driver], d);
|
||||
}
|
||||
|
||||
inline void Platform::SetEnableValue(size_t drive, bool eVal)
|
||||
inline void Platform::SetEnableValue(size_t driver, bool eVal)
|
||||
{
|
||||
enableValues[drive] = eVal;
|
||||
enableValues[driver] = eVal;
|
||||
DisableDriver(driver); // disable the drive, because the enable polarity may have been wrong before
|
||||
}
|
||||
|
||||
inline bool Platform::GetEnableValue(size_t drive) const
|
||||
inline bool Platform::GetEnableValue(size_t driver) const
|
||||
{
|
||||
return enableValues[drive];
|
||||
return enableValues[driver];
|
||||
}
|
||||
|
||||
inline float Platform::AxisMaximum(size_t axis) const
|
||||
|
|
|
@ -59,9 +59,9 @@ void RepRap::Init()
|
|||
configFile = platform->GetDefaultFile();
|
||||
}
|
||||
|
||||
if (gCodes->DoFileMacro(configFile, false))
|
||||
if (gCodes->RunConfigFile(configFile))
|
||||
{
|
||||
while (gCodes->DoingFileMacro())
|
||||
while (gCodes->IsRunningConfigFile())
|
||||
{
|
||||
// GCodes::Spin will read the macro and ensure DoingFileMacro returns false when it's done
|
||||
Spin();
|
||||
|
@ -730,8 +730,8 @@ OutputBuffer *RepRap::GetStatusResponse(uint8_t type, ResponseSource source)
|
|||
response->catf(",\"coldExtrudeTemp\":%1.f", heat->ColdExtrude() ? 0 : HOT_ENOUGH_TO_EXTRUDE);
|
||||
response->catf(",\"coldRetractTemp\":%1.f", heat->ColdExtrude() ? 0 : HOT_ENOUGH_TO_RETRACT);
|
||||
|
||||
// Maximum hotend temperature
|
||||
response->catf(",\"tempLimit\":%1.f", platform->GetTemperatureLimit());
|
||||
// Maximum hotend temperature - DWC just wants the highest one
|
||||
response->catf(",\"tempLimit\":%1.f", heat->GetHighestTemperatureLimit());
|
||||
|
||||
// Endstops
|
||||
uint16_t endstops = 0;
|
||||
|
@ -755,7 +755,7 @@ OutputBuffer *RepRap::GetStatusResponse(uint8_t type, ResponseSource source)
|
|||
size_t mountedCards = 0;
|
||||
for(size_t i = 0; i < NumSdCards; i++)
|
||||
{
|
||||
if (reprap.GetPlatform()->GetMassStorage()->IsDriveMounted(i))
|
||||
if (platform->GetMassStorage()->IsDriveMounted(i))
|
||||
{
|
||||
mountedCards |= (1 << i);
|
||||
}
|
||||
|
@ -1329,14 +1329,14 @@ OutputBuffer *RepRap::GetFilelistResponse(const char *dir)
|
|||
}
|
||||
|
||||
// If the requested volume is not mounted, report an error
|
||||
if (!reprap.GetPlatform()->GetMassStorage()->CheckDriveMounted(dir))
|
||||
if (!platform->GetMassStorage()->CheckDriveMounted(dir))
|
||||
{
|
||||
response->copy("{\"err\":1}");
|
||||
return response;
|
||||
}
|
||||
|
||||
// Check if the directory exists
|
||||
if (!reprap.GetPlatform()->GetMassStorage()->DirectoryExists(dir))
|
||||
if (!platform->GetMassStorage()->DirectoryExists(dir))
|
||||
{
|
||||
response->copy("{\"err\":2}");
|
||||
return response;
|
||||
|
|
|
@ -173,7 +173,7 @@ float Tool::MaxFeedrate() const
|
|||
const size_t numAxes = reprap.GetGCodes()->GetNumAxes();
|
||||
for (size_t d = 0; d < driveCount; d++)
|
||||
{
|
||||
float mf = reprap.GetPlatform()->MaxFeedrate(drives[d] + numAxes);
|
||||
const float mf = reprap.GetPlatform()->MaxFeedrate(drives[d] + numAxes);
|
||||
if (mf > result)
|
||||
{
|
||||
result = mf;
|
||||
|
@ -193,7 +193,7 @@ float Tool::InstantDv() const
|
|||
const size_t numAxes = reprap.GetGCodes()->GetNumAxes();
|
||||
for (size_t d = 0; d < driveCount; d++)
|
||||
{
|
||||
float idv = reprap.GetPlatform()->ActualInstantDv(drives[d] + numAxes);
|
||||
const float idv = reprap.GetPlatform()->ActualInstantDv(drives[d] + numAxes);
|
||||
if (idv < result)
|
||||
{
|
||||
result = idv;
|
||||
|
@ -306,7 +306,7 @@ void Tool::SetVariables(const float* standby, const float* active)
|
|||
}
|
||||
else
|
||||
{
|
||||
const float temperatureLimit = reprap.GetPlatform()->GetTemperatureLimit();
|
||||
const float temperatureLimit = reprap.GetHeat()->GetTemperatureLimit(heaters[heater]);
|
||||
if (active[heater] < temperatureLimit)
|
||||
{
|
||||
activeTemperatures[heater] = active[heater];
|
||||
|
|
Reference in a new issue