diff options
author | David Crocker <dcrocker@eschertech.com> | 2017-06-11 00:19:50 +0300 |
---|---|---|
committer | David Crocker <dcrocker@eschertech.com> | 2017-06-11 00:23:47 +0300 |
commit | 310b7c0e1ae92d65421276c3779efeddfb6977ff (patch) | |
tree | 56afba8162017646c4f1a47b8da0512482c7f336 /src | |
parent | d026b0e4d2a7d5fda771e843cfca12e0370440d7 (diff) |
Version 1.19beta6
Refactored temperatyure sensor code
Refactored fan control code
Support invisible axes (M584 P parameter)
Supprt user-defined virtual heaters
Support heater names
Support proportional thermostatic fan control
Fix G10 retraction command
Removed delta probe code
Diffstat (limited to 'src')
65 files changed, 2259 insertions, 1935 deletions
diff --git a/src/Configuration.h b/src/Configuration.h index abde541c..9e9e192a 100644 --- a/src/Configuration.h +++ b/src/Configuration.h @@ -87,6 +87,11 @@ const int8_t DefaultBedHeater = 0; const int8_t DefaultChamberHeater = -1; const int8_t DefaultE0Heater = 1; // Index of the default first extruder heater +const unsigned int FirstVirtualHeater = 100; // the heater number at which virtual heaters start +const unsigned int MaxVirtualHeaters = 10; // the number of virtual heaters supported + +const size_t MaxHeaterNameLength = 20; // Maximum number of characters in a heater name + // These parameters are about right for a typical PCB bed heater that maxes out at 110C const float DefaultBedHeaterGain = 90.0; const float DefaultBedHeaterTimeConstant = 700.0; @@ -103,9 +108,13 @@ const float MinimumConnectedTemperature = -5.0; // Temperatures below this we t static_assert(DefaultMaxTempExcursion > TEMPERATURE_CLOSE_ENOUGH, "DefaultMaxTempExcursion is too low"); // Temperature sense channels +const unsigned int FirstThermistorChannel = 0; // Temperature sensor channels 0... are thermistors const unsigned int FirstThermocoupleChannel = 100; // Temperature sensor channels 100... are thermocouples const unsigned int FirstRtdChannel = 200; // Temperature sensor channels 200... are RTDs const unsigned int FirstLinearAdcChannel = 300; // Temperature sensor channels 300... use an ADC that provides a linear output over a temperature range +const unsigned int CpuTemperatureSenseChannel = 1000; // Sensor 1000 is the MCJU's own temperature sensor +const unsigned int FirstTmcDriversSenseChannel = 1001; // Sensors 1001..1002 are the TMC2660 driver temperature sense +const unsigned int NumTmcDriversSenseChannels = 2; // Sensors 1001..1002 are the TMC2660 driver temperature sense // PWM frequencies const unsigned int SlowHeaterPwmFreq = 10; // slow PWM frequency for bed and chamber heaters, compatible with DC/AC SSRs diff --git a/src/Duet/Pins_Duet.h b/src/Duet/Pins_Duet.h index 1ca958b0..aff131bd 100644 --- a/src/Duet/Pins_Duet.h +++ b/src/Duet/Pins_Duet.h @@ -19,17 +19,15 @@ const size_t NumFirmwareUpdateModules = 1; const size_t DRIVES = 9; // The number of drives in the machine, including X, Y, and Z plus extruder drives #define DRIVES_(a,b,c,d,e,f,g,h,i,j) { a,b,c,d,e,f,g,h,i } -const int8_t HEATERS = 7; // The number of heaters in the machine; 0 is the heated bed even if there isn't one +const size_t Heaters = 7; // The number of heaters in the machine; 0 is the heated bed even if there isn't one #define HEATERS_(a,b,c,d,e,f,g,h) { a,b,c,d,e,f,g } -const unsigned int FirstVirtualHeater = 100; -const unsigned int NumVirtualHeaters = 1; // CPU temperature only -const size_t MAX_AXES = 6; // The maximum number of movement axes in the machine, usually just X, Y and Z, <= DRIVES +const size_t MinAxes = 3; // The minimum and default number of axes +const size_t MaxAxes = 6; // The maximum number of movement axes in the machine, usually just X, Y and Z, <= DRIVES // Initialization macro used in statements needing to initialize values in arrays of size MAX_AXES #define AXES_(a,b,c,d,e,f) { a,b,c,d,e,f } -const size_t MIN_AXES = 3; // The minimum and default number of axes -const size_t MaxExtruders = DRIVES - MIN_AXES; // The maximum number of extruders +const size_t MaxExtruders = DRIVES - MinAxes; // The maximum number of extruders const size_t MaxDriversPerAxis = 4; // The maximum number of stepper drivers assigned to one axis const size_t NUM_SERIAL_CHANNELS = 3; // The number of serial IO channels (USB and two auxiliary UARTs) @@ -61,8 +59,8 @@ const float STEPPER_DAC_VOLTAGE_OFFSET = -0.025; // Stepper motor current o const bool HEAT_ON = false; // false for inverted heater (e.g. Duet v0.6), true for not (e.g. Duet v0.4) -const Pin TEMP_SENSE_PINS[HEATERS] = { 5, 4, 0, 7, 8, 9, 11 }; // Analogue pin numbers -const Pin HEAT_ON_PINS[HEATERS] = { 6, X5, X7, 7, 8, 9, X17 }; // Heater Channel 7 (pin X17) is shared with Fan1 +const Pin TEMP_SENSE_PINS[Heaters] = { 5, 4, 0, 7, 8, 9, 11 }; // Analogue pin numbers +const Pin HEAT_ON_PINS[Heaters] = { 6, X5, X7, 7, 8, 9, X17 }; // Heater Channel 7 (pin X17) is shared with Fan1 // Default thermistor parameters // Bed thermistor: http://uk.farnell.com/epcos/b57863s103f040/sensor-miniature-ntc-10k/dp/1299930?Ntt=129-9930 diff --git a/src/DuetNG/Pins_DuetNG.h b/src/DuetNG/Pins_DuetNG.h index c0e4d483..2003b078 100644 --- a/src/DuetNG/Pins_DuetNG.h +++ b/src/DuetNG/Pins_DuetNG.h @@ -32,17 +32,15 @@ const size_t NumFirmwareUpdateModules = 1; // 1 module const size_t DRIVES = 10; // The number of drives in the machine, including X, Y and Z plus extruder drives #define DRIVES_(a,b,c,d,e,f,g,h,i,j) { a,b,c,d,e,f,g,h,i,j } -const int8_t HEATERS = 8; // The number of heaters in the machine; 0 is the heated bed even if there isn't one +const size_t Heaters = 8; // The number of heaters in the machine; 0 is the heated bed even if there isn't one #define HEATERS_(a,b,c,d,e,f,g,h) { a,b,c,d,e,f,g,h } -const unsigned int FirstVirtualHeater = 100; -const unsigned int NumVirtualHeaters = 3; // CPU temperature, on-board driver temperatures, DueX driver temperatures -const size_t MAX_AXES = 6; // The maximum number of movement axes in the machine, usually just X, Y and Z, <= DRIVES +const size_t MinAxes = 3; // The minimum and default number of axes +const size_t MaxAxes = 6; // The maximum number of movement axes in the machine, usually just X, Y and Z, <= DRIVES // Initialization macro used in statements needing to initialize values in arrays of size MAX_AXES #define AXES_(a,b,c,d,e,f) { a,b,c,d,e,f } -const size_t MIN_AXES = 3; // The minimum and default number of axes -const size_t MaxExtruders = DRIVES - MIN_AXES; // The maximum number of extruders +const size_t MaxExtruders = DRIVES - MinAxes; // The maximum number of extruders const size_t MaxDriversPerAxis = 4; // The maximum number of stepper drivers assigned to one axis const size_t NUM_SERIAL_CHANNELS = 2; // The number of serial IO channels (USB and one auxiliary UART) @@ -71,8 +69,8 @@ const Pin END_STOP_PINS[DRIVES] = { 46, 02, 93, 74, 48, 200, 203, 202, 201, 213 // HEATERS const bool HEAT_ON = false; // false for inverted heater (e.g. Duet v0.6), true for not (e.g. Duet v0.4) -const Pin TEMP_SENSE_PINS[HEATERS] = { 45, 47, 44, 61, 62, 63, 59, 18 }; // Thermistor pin numbers -const Pin HEAT_ON_PINS[HEATERS] = { 19, 20, 16, 35, 37, 40, 43, 15 }; // Heater pin numbers (heater 7 pin TBC) +const Pin TEMP_SENSE_PINS[Heaters] = { 45, 47, 44, 61, 62, 63, 59, 18 }; // Thermistor pin numbers +const Pin HEAT_ON_PINS[Heaters] = { 19, 20, 16, 35, 37, 40, 43, 15 }; // Heater pin numbers (heater 7 pin TBC) // Default thermistor parameters const float BED_R25 = 100000.0; diff --git a/src/Fan.cpp b/src/Fan.cpp index efdcb737..46cb3b9b 100644 --- a/src/Fan.cpp +++ b/src/Fan.cpp @@ -8,10 +8,12 @@ #include "Fan.h" #include "Platform.h" #include "RepRap.h" +#include "GCodes/GCodeBuffer.h" +#include "Heating/Heat.h" void Fan::Init(Pin p_pin, bool hwInverted) { - val = 0.0; + val = lastVal = 0.0; minVal = 0.1; // 10% minimum fan speed blipTime = 100; // 100ms fan blip freq = DefaultFanPwmFreq; @@ -19,47 +21,150 @@ void Fan::Init(Pin p_pin, bool hwInverted) hardwareInverted = hwInverted; inverted = blipping = false; heatersMonitored = 0; - triggerTemperature = HOT_END_FAN_TEMPERATURE; - thermostatIsOn = false; + triggerTemperatures[0] = triggerTemperatures[1] = HOT_END_FAN_TEMPERATURE; lastPwm = -1.0; // force a refresh Refresh(); } -void Fan::SetValue(float speed) +// Set or report the parameters for this fan +// If 'mcode' is an M-code used to set parameters for the current kinematics (which should only ever be 106) +// then search for parameters used to configure the fan. If any are found, perform appropriate actions and return true. +// If errors were discovered while processing parameters, put an appropriate error message in 'reply' and set 'error' to true. +// If no relevant parameters are found, print the existing ones to 'reply' and return false. +// Exceptions: +// 1. Only process the S parameter unless other values were processed. +// 2. Don't process the R parameter, but if it is present don't print the existing configuration. +bool Fan::Configure(unsigned int mcode, int fanNum, GCodeBuffer& gb, StringRef& reply, bool& error) { - if (speed > 1.0) + if (!IsEnabled()) { - speed /= 255.0; + reply.printf("Fan %d is disabled", fanNum); + error = true; + return true; // say we have processed it } - const float newVal = constrain<float>(speed, 0.0, 1.0); - if (val == 0.0 && newVal > 0.0 && newVal < 1.0 && blipTime != 0) + + bool seen = false; + if (mcode == 106) { - // Starting the fan from standstill, so blip the fan - blipping = true; - blipStartTime = millis(); + if (gb.Seen('I')) // Invert cooling + { + seen = true; + const int invert = gb.GetIValue(); + if (invert < 0) + { + Disable(); + } + else + { + inverted = (invert > 0); + } + } + + if (gb.Seen('F')) // Set PWM frequency + { + seen = true; + freq = (uint16_t)constrain<int>(gb.GetIValue(), 1, 65535); + lastPwm = -1.0; // force the PWM to be updated + Refresh(); + } + + if (gb.Seen('T')) + { + seen = true; + size_t numTemps = 2; + gb.GetFloatArray(triggerTemperatures, numTemps, true); + } + + if (gb.Seen('B')) // Set blip time + { + seen = true; + blipTime = (uint32_t)(max<float>(gb.GetFValue(), 0.0) * SecondsToMillis); + } + + if (gb.Seen('L')) // Set minimum speed + { + seen = true; + float speed = gb.GetFValue(); + if (speed > 1.0) + { + speed /= 255.0; + } + minVal = constrain<float>(speed, 0.0, 1.0); + } + + if (gb.Seen('H')) // Set thermostatically-controlled heaters + { + seen = true; + long heaters[Heaters + MaxVirtualHeaters]; + size_t numH = ARRAY_SIZE(heaters); + gb.GetLongArray(heaters, numH); + + // Note that M106 H-1 disables thermostatic mode. The following code implements that automatically. + heatersMonitored = 0; + for (size_t h = 0; h < numH; ++h) + { + const int hnum = heaters[h]; + if (hnum >= 0 && hnum < (int)Heaters) + { + heatersMonitored |= (1u << (unsigned int)hnum); + } + else if (hnum >= (int)FirstVirtualHeater && hnum < (int)(FirstVirtualHeater + MaxVirtualHeaters)) + { + // Heaters 100, 101... are virtual heaters i.e. CPU and driver temperatures + heatersMonitored |= (1u << (Heaters + (unsigned int)hnum - FirstVirtualHeater)); + } + } + if (heatersMonitored != 0) + { + SetValue(1.0); // default the fan speed to full for safety + } + } + + // We only act on the 'S' parameter here if we have processed other parameters + if (seen && gb.Seen('S')) // Set new fan value - process this after processing 'H' or it may not be acted on + { + const float f = constrain<float>(gb.GetFValue(), 0.0, 255.0); + SetValue(f); + } + + if (seen) + { + Refresh(); + } + else if (!gb.Seen('R') && !gb.Seen('S')) + { + // Report the configuration of the specified fan + reply.printf("Fan%i frequency: %uHz, speed: %d%%, min: %d%%, blip: %.2f, inverted: %s", + fanNum, + (unsigned int)freq, + (int)(val * 100.0), + (int)(minVal * 100.0), + (float)blipTime * MillisToSeconds, + (inverted) ? "yes" : "no"); + if (heatersMonitored != 0) + { + reply.catf(", temperature: %.1f:%.1fC, heaters:", triggerTemperatures[0], triggerTemperatures[1]); + for (unsigned int i = 0; i < Heaters + MaxVirtualHeaters; ++i) + { + if ((heatersMonitored & (1u << i)) != 0) + { + reply.catf(" %u", (i < Heaters) ? i : FirstVirtualHeater + i - Heaters); + } + } + } + } } - val = newVal; - Refresh(); + + return seen; } -void Fan::SetMinValue(float speed) +void Fan::SetValue(float speed) { if (speed > 1.0) { speed /= 255.0; } - minVal = constrain<float>(speed, 0.0, 1.0); - Refresh(); -} - -void Fan::SetBlipTime(float t) -{ - blipTime = (uint32_t)(max<float>(t, 0.0) * SecondsToMillis); -} - -void Fan::SetInverted(bool inv) -{ - inverted = inv; + val = constrain<float>(speed, 0.0, 1.0); Refresh(); } @@ -88,17 +193,9 @@ void Fan::SetHardwarePwm(float pwmVal) } } -void Fan::SetPwmFrequency(float p_freq) -{ - freq = (uint16_t)constrain<float>(p_freq, 1.0, 65535.0); - lastPwm = -1.0; // force the PWM to be updated - Refresh(); -} - void Fan::SetHeatersMonitored(uint16_t h) { heatersMonitored = h; - thermostatIsOn = false; Refresh(); } @@ -107,19 +204,59 @@ void Fan::SetHeatersMonitored(uint16_t h) void Fan::Refresh() { float reqVal; +#ifdef DUET_NG + uint32_t driverChannelsMonitored = 0; +#endif + if (heatersMonitored == 0) { reqVal = val; } - else if (reprap.GetPlatform().AnyHeaterHot(heatersMonitored, (thermostatIsOn) ? triggerTemperature - ThermostatHysteresis : triggerTemperature)) - { - thermostatIsOn = true; - reqVal = max<float>(0.5, val); // make sure that thermostatic fans always run at 50% speed or more - } else { - thermostatIsOn = false; reqVal = 0.0; + const bool bangBangMode = (triggerTemperatures[1] <= triggerTemperatures[0]); + for (size_t h = 0; h < Heaters + MaxVirtualHeaters; ++h) + { + // Check if this heater is both monitored by this fan and in use + if ( ((1 << h) & heatersMonitored) != 0 + && (h < reprap.GetToolHeatersInUse() || h >= Heaters || (int)h == reprap.GetHeat().GetBedHeater() || (int)h == reprap.GetHeat().GetChamberHeater()) + ) + { + // This heater is both monitored and potentially active + if (h < Heaters && reprap.GetHeat().IsTuning(h)) + { + reqVal = 1.0; // when turning the PID for a monitored heater, turn the fan on + } + else + { + const size_t heaterHumber = (h >= Heaters) ? (h - Heaters) + FirstVirtualHeater : h; + TemperatureError err; + const float ht = reprap.GetHeat().GetTemperature(heaterHumber, err); + if (err != TemperatureError::success || ht < BAD_LOW_TEMPERATURE || ht >= triggerTemperatures[1]) + { + reqVal = max<float>(reqVal, (bangBangMode) ? max<float>(0.5, val) : 1.0); + } + else if (!bangBangMode && ht > triggerTemperatures[0]) + { + // We already know that ht < triggerTemperatures[1], therefore unless we have NaNs it is safe to divide by (triggerTemperatures[1] - triggerTemperatures[0]) + reqVal = max<float>(reqVal, (ht - triggerTemperatures[0])/(triggerTemperatures[1] - triggerTemperatures[0])); + } + else if (lastVal != 0.0 && ht + ThermostatHysteresis > triggerTemperatures[0]) + { + // If the fan is on, add a hysteresis before turning it off + reqVal = max<float>(reqVal, (bangBangMode) ? max<float>(0.5, val) : minVal); + } +#ifdef DUET_NG + const unsigned int channel = reprap.GetHeat().GetHeaterChannel(heaterHumber); + if (channel >= FirstTmcDriversSenseChannel && channel < FirstTmcDriversSenseChannel + NumTmcDriversSenseChannels) + { + driverChannelsMonitored |= 1 << (channel - FirstTmcDriversSenseChannel); + } +#endif + } + } + } } if (reqVal > 0.0) @@ -129,6 +266,23 @@ void Fan::Refresh() reqVal = minVal; } + if (lastVal == 0.0) + { + // We are turning this fan on +#ifdef DUET_NG + if (driverChannelsMonitored != 0) + { + reprap.GetPlatform().DriverCoolingFansOn(driverChannelsMonitored); // tell Platform that we have started a fan that cools drivers + } +#endif + if (reqVal < 1.0 && blipTime != 0) + { + // Starting the fan from standstill, so blip the fan + blipping = true; + blipStartTime = millis(); + } + } + if (blipping) { if (millis() - blipStartTime < blipTime) @@ -141,7 +295,9 @@ void Fan::Refresh() } } } + SetHardwarePwm(reqVal); + lastVal = reqVal; } void Fan::Check() @@ -10,12 +10,32 @@ #include "RepRapFirmware.h" +class GCodeBuffer; + class Fan { +public: + // Set or report the parameters for this fan + // If 'mCode' is an M-code used to set parameters for the current kinematics (which should only ever be 106 or 107) + // then search for parameters used to configure the fan. If any are found, perform appropriate actions and return true. + // If errors were discovered while processing parameters, put an appropriate error message in 'reply' and set 'error' to true. + // If no relevant parameters are found, print the existing ones to 'reply' and return false. + bool Configure(unsigned int mcode, int fanNum, GCodeBuffer& gb, StringRef& reply, bool& error); + + bool IsEnabled() const { return pin != NoPin; } + float GetValue() const { return val; } + + void Init(Pin p_pin, bool hwInverted); + void SetValue(float speed); + void SetHeatersMonitored(uint16_t h); + void Check(); + void Disable(); + private: float val; + float lastVal; float minVal; - float triggerTemperature; + float triggerTemperatures[2]; float lastPwm; uint32_t blipTime; // in milliseconds uint32_t blipStartTime; @@ -25,31 +45,9 @@ private: bool inverted; bool hardwareInverted; bool blipping; - bool thermostatIsOn; // if it is a thermostatic fan, true if it is turned on void Refresh(); void SetHardwarePwm(float pwmVal); - -public: - bool IsEnabled() const { return pin != NoPin; } - float GetValue() const { return val; } - float GetMinValue() const { return minVal; } - float GetBlipTime() const { return (float)blipTime * MillisToSeconds; } - float GetPwmFrequency() const { return freq; } - bool GetInverted() const { return inverted; } - uint16_t GetHeatersMonitored() const { return heatersMonitored; } - float GetTriggerTemperature() const { return triggerTemperature; } - - void Init(Pin p_pin, bool hwInverted); - void SetValue(float speed); - void SetMinValue(float speed); - void SetBlipTime(float t); - void SetInverted(bool inv); - void SetPwmFrequency(float p_freq); - void SetTriggerTemperature(float t) { triggerTemperature = t; } - void SetHeatersMonitored(uint16_t h); - void Check(); - void Disable(); }; #endif /* SRC_FAN_H_ */ diff --git a/src/GCodes/GCodeBuffer.cpp b/src/GCodes/GCodeBuffer.cpp index 48917e20..1910259c 100644 --- a/src/GCodes/GCodeBuffer.cpp +++ b/src/GCodes/GCodeBuffer.cpp @@ -29,7 +29,7 @@ void GCodeBuffer::Init() { gcodePointer = 0; readPointer = -1; - inComment = timerRunning = false; + inQuotes = inComment = timerRunning = false; bufferState = GCodeBufferState::idle; } @@ -75,7 +75,7 @@ int GCodeBuffer::CheckSum() const // not yet complete. If true, it is complete and ready to be acted upon. bool GCodeBuffer::Put(char c) { - if (c == ';') + if (!inQuotes && c == ';') { inComment = true; } @@ -141,12 +141,18 @@ bool GCodeBuffer::Put(char c) } else if (!inComment || writingFileDirectory) { - gcodeBuffer[gcodePointer++] = c; if (gcodePointer >= (int)GCODE_LENGTH) { reprap.GetPlatform().MessageF(GENERIC_MESSAGE, "Error: G-Code buffer '$s' length overflow\n", identity); - gcodePointer = 0; - gcodeBuffer[0] = 0; + Init(); + } + else + { + gcodeBuffer[gcodePointer++] = c; + if (c == '"' && !inComment) + { + inQuotes = !inQuotes; + } } } @@ -366,7 +372,7 @@ const void GCodeBuffer::GetLongArray(long l[], size_t& returnedLength) // Get a string after a G Code letter found by a call to Seen(). // It will be the whole of the rest of the GCode string, so strings should always be the last parameter. -// Use the other overload of GetString to get strings that may not be the last parameter. +// Use the other overload of GetString to get strings that may not be the last parameter, or may be quoted. const char* GCodeBuffer::GetString() { if (readPointer < 0) @@ -379,8 +385,8 @@ const char* GCodeBuffer::GetString() return result; } -// Get and copy a possibly quoted string -bool GCodeBuffer::GetString(char *buf, size_t buflen) +// Get and copy a quoted string +bool GCodeBuffer::GetQuotedString(char *buf, size_t buflen) { if (readPointer < 0) { @@ -407,8 +413,9 @@ bool GCodeBuffer::GetString(char *buf, size_t buflen) if (i < buflen) { buf[i] = 0; + return true; } - return i <= buflen; + return false; } } if (i < buflen) @@ -418,28 +425,7 @@ bool GCodeBuffer::GetString(char *buf, size_t buflen) ++i; } } - else - { - // Non-quoted string, terminate it on space or semicolon or control character - for (;;) - { - if (c <= ' ' || c == ';') - { - if (i < buflen) - { - buf[i] = 0; - } - return i != 0 && i <= buflen; // no string found - } - if (i < buflen) - { - buf[i] = c; - } - ++i; - c = gcodeBuffer[readPointer++]; - } - } - return false; // to keep Eclipse happy + return false; } // This returns a pointer to the end of the buffer where a @@ -511,7 +497,7 @@ void GCodeBuffer::TryGetIValue(char c, int32_t& val, bool& seen) } } -// Try to get a flow array exactly 'numVals' long after parameter letter 'c'. +// Try to get a float array exactly 'numVals' long after parameter letter 'c'. // If the wrong number of value is provided, generate an error message and return true. // Else set 'seen' if we saw the letter and value, and return false. bool GCodeBuffer::TryGetFloatArray(char c, size_t numVals, float vals[], StringRef& reply, bool& seen) @@ -533,6 +519,16 @@ bool GCodeBuffer::TryGetFloatArray(char c, size_t numVals, float vals[], StringR return false; } +// Try to get a quoted string after parameter letter. +// If we found it then set 'seen' true, else leave 'seen' alone +void GCodeBuffer::TryGetQuotedString(char c, char *buf, size_t buflen, bool& seen) +{ + if (Seen(c) && GetQuotedString(buf, buflen)) + { + seen = true; + } +} + // Get an IP address quad after a key letter bool GCodeBuffer::GetIPAddress(uint8_t ip[4]) { diff --git a/src/GCodes/GCodeBuffer.h b/src/GCodes/GCodeBuffer.h index 4e424281..b1716d8f 100644 --- a/src/GCodes/GCodeBuffer.h +++ b/src/GCodes/GCodeBuffer.h @@ -25,19 +25,23 @@ public: bool IsEmpty() const; // Does this buffer contain any code? bool Seen(char c); // Is a character present? bool SeenAfterSpace(char c); // Is a character present? + char GetCommandLetter(); // Find the first G, M or T command float GetFValue(); // Get a float after a key letter int32_t GetIValue(); // Get an integer after a key letter bool GetIPAddress(uint8_t ip[4]); // Get an IP address quad after a key letter bool GetIPAddress(uint32_t& ip); // Get an IP address quad after a key letter - void TryGetFValue(char c, float& val, bool& seen); - void TryGetIValue(char c, int32_t& val, bool& seen); - bool TryGetFloatArray(char c, size_t numVals, float vals[], StringRef& reply, 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 - bool GetString(char *buf, size_t buflen); // Get and copy a possibly quoted string + bool GetQuotedString(char *buf, size_t buflen); // Get and copy a quoted string 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 + + void TryGetFValue(char c, float& val, bool& seen); + void TryGetIValue(char c, int32_t& val, bool& seen); + bool TryGetFloatArray(char c, size_t numVals, float vals[], StringRef& reply, bool& seen); + void TryGetQuotedString(char c, char *buf, size_t buflen, bool& seen); + const char* Buffer() const; bool IsIdle() const; bool IsReady() const; // Return true if a gcode is ready but hasn't been started yet @@ -80,6 +84,7 @@ private: 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 inQuotes; // Are we inside double quotation marks? 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 diff --git a/src/GCodes/GCodes.cpp b/src/GCodes/GCodes.cpp index f26160b4..1e5fb3bf 100644 --- a/src/GCodes/GCodes.cpp +++ b/src/GCodes/GCodes.cpp @@ -38,10 +38,10 @@ #include "FirmwareUpdater.h" #endif -const char GCodes::axisLetters[MAX_AXES] = AXES_('X', 'Y', 'Z', 'U', 'V', 'W'); +const char GCodes::axisLetters[MaxAxes] = AXES_('X', 'Y', 'Z', 'U', 'V', 'W'); const char* const PAUSE_G = "pause.g"; -const char* const HomingFileNames[MAX_AXES] = AXES_("homex.g", "homey.g", "homez.g", "homeu.g", "homev.g", "homew.g"); +const char* const HomingFileNames[MaxAxes] = AXES_("homex.g", "homey.g", "homez.g", "homeu.g", "homev.g", "homew.g"); const char* const HOME_ALL_G = "homeall.g"; const char* const HOME_DELTA_G = "homedelta.g"; const char* const DefaultHeightMapFile = "heightmap.csv"; @@ -88,7 +88,7 @@ void GCodes::Exit() void GCodes::Init() { Reset(); - numAxes = MIN_AXES; + numVisibleAxes = numTotalAxes = XYZ_AXES; numExtruders = MaxExtruders; distanceScale = 1.0; arcSegmentLength = DefaultArcSegmentLength; @@ -108,7 +108,7 @@ void GCodes::Init() active = true; longWait = platform.Time(); limitAxes = true; - for(size_t axis = 0; axis < MAX_AXES; axis++) + for(size_t axis = 0; axis < MaxAxes; axis++) { axisScaleFactors[axis] = 1.0; } @@ -157,9 +157,9 @@ void GCodes::Reset() { extrusionFactors[i] = 1.0; } - reprap.GetMove().GetKinematics().GetAssumedInitialPosition(numAxes, moveBuffer.coords); + reprap.GetMove().GetKinematics().GetAssumedInitialPosition(numVisibleAxes, moveBuffer.coords); moveBuffer.xAxes = DefaultXAxisMapping; - for (size_t i = numAxes; i < DRIVES; ++i) + for (size_t i = numTotalAxes; i < DRIVES; ++i) { moveBuffer.coords[i] = 0.0; } @@ -274,7 +274,7 @@ void GCodes::Spin() } else { - for (size_t axis = 0; axis < numAxes; ++axis) + for (size_t axis = 0; axis < numTotalAxes; ++axis) { // Leave the Z axis until all other axes are done if ((toBeHomed & (1u << axis)) != 0 && (axis != Z_AXIS || toBeHomed == (1u << Z_AXIS))) @@ -377,11 +377,11 @@ void GCodes::Spin() if (LockMovementAndWaitForStandstill(gb)) { float currentZ = moveBuffer.coords[Z_AXIS]; - for (size_t drive = 0; drive < numAxes; ++drive) + for (size_t drive = 0; drive < numVisibleAxes; ++drive) { moveBuffer.coords[drive] = pauseRestorePoint.moveCoords[drive]; } - for (size_t drive = numAxes; drive < DRIVES; ++drive) + for (size_t drive = numTotalAxes; drive < DRIVES; ++drive) { moveBuffer.coords[drive] = 0.0; } @@ -412,9 +412,9 @@ void GCodes::Spin() { platform.SetFanValue(i, pausedFanSpeeds[i]); } - for (size_t drive = numAxes; drive < DRIVES; ++drive) + for (size_t drive = numTotalAxes; drive < DRIVES; ++drive) { - lastRawExtruderPosition[drive - numAxes] = pauseRestorePoint.moveCoords[drive]; // reset the extruder position in case we are receiving absolute extruder moves + lastRawExtruderPosition[drive - numTotalAxes] = pauseRestorePoint.moveCoords[drive]; // reset the extruder position in case we are receiving absolute extruder moves } fileGCode->MachineState().feedrate = pauseRestorePoint.feedRate; isPaused = false; @@ -638,7 +638,7 @@ void GCodes::Spin() { const uint32_t xAxes = reprap.GetCurrentXAxes(); reprap.GetMove().GetCurrentUserPosition(moveBuffer.coords, 0, xAxes); - for (size_t i = numAxes; i < DRIVES; ++i) + for (size_t i = numTotalAxes; i < DRIVES; ++i) { moveBuffer.coords[i] = 0.0; } @@ -664,13 +664,13 @@ void GCodes::Spin() { const uint32_t xAxes = reprap.GetCurrentXAxes(); reprap.GetMove().GetCurrentUserPosition(moveBuffer.coords, 0, xAxes); - for (size_t i = numAxes; i < DRIVES; ++i) + for (size_t i = numTotalAxes; i < DRIVES; ++i) { moveBuffer.coords[i] = 0.0; } for (size_t i = 0; i < tool->DriveCount(); ++i) { - moveBuffer.coords[numAxes + tool->Drive(i)] = retractLength + retractExtra; + moveBuffer.coords[numTotalAxes + tool->Drive(i)] = retractLength + retractExtra; } moveBuffer.feedRate = unRetractSpeed; moveBuffer.moveType = 0; @@ -917,13 +917,13 @@ void GCodes::DoPause(GCodeBuffer& gb) if (&gb == fileGCode) { // Pausing a file print because of a command in the file itself - for (size_t drive = 0; drive < numAxes; ++drive) + for (size_t drive = 0; drive < numVisibleAxes; ++drive) { pauseRestorePoint.moveCoords[drive] = moveBuffer.coords[drive]; } - for (size_t drive = numAxes; drive < DRIVES; ++drive) + for (size_t drive = numTotalAxes; drive < DRIVES; ++drive) { - pauseRestorePoint.moveCoords[drive] = lastRawExtruderPosition[drive - numAxes]; // get current extruder positions into pausedMoveBuffer + pauseRestorePoint.moveCoords[drive] = lastRawExtruderPosition[drive - numTotalAxes]; // get current extruder positions into pausedMoveBuffer } pauseRestorePoint.feedRate = gb.MachineState().feedrate; } @@ -943,16 +943,16 @@ void GCodes::DoPause(GCodeBuffer& gb) if (segmentsLeft != 0) { - for (size_t drive = numAxes; drive < DRIVES; ++drive) + for (size_t drive = numTotalAxes; drive < DRIVES; ++drive) { pauseRestorePoint.moveCoords[drive] += moveBuffer.coords[drive]; // add on the extrusion in the move not yet taken } ClearMove(); } - for (size_t drive = numAxes; drive < DRIVES; ++drive) + for (size_t drive = numTotalAxes; drive < DRIVES; ++drive) { - pauseRestorePoint.moveCoords[drive] = lastRawExtruderPosition[drive - numAxes] - pauseRestorePoint.moveCoords[drive]; + pauseRestorePoint.moveCoords[drive] = lastRawExtruderPosition[drive - numTotalAxes] - pauseRestorePoint.moveCoords[drive]; } //TODO record the virtual extruder positions of mixing tools too. But that's very hard to do unless we store it in the move. @@ -1008,7 +1008,7 @@ bool GCodes::LockMovementAndWaitForStandstill(const GCodeBuffer& gb) // Get the current positions. These may not be the same as the ones we remembered from last time if we just did a special move. reprap.GetMove().GetCurrentUserPosition(moveBuffer.coords, 0, reprap.GetCurrentXAxes()); - memcpy(moveBuffer.initialCoords, moveBuffer.coords, numAxes * sizeof(moveBuffer.initialCoords[0])); + memcpy(moveBuffer.initialCoords, moveBuffer.coords, numVisibleAxes * sizeof(moveBuffer.initialCoords[0])); return true; } @@ -1038,7 +1038,7 @@ void GCodes::Pop(GCodeBuffer& gb) bool GCodes::LoadExtrusionAndFeedrateFromGCode(GCodeBuffer& gb, int moveType) { // Zero every extruder drive as some drives may not be moved - for (size_t drive = numAxes; drive < DRIVES; drive++) + for (size_t drive = numTotalAxes; drive < DRIVES; drive++) { moveBuffer.coords[drive] = 0.0; } @@ -1098,7 +1098,7 @@ bool GCodes::LoadExtrusionAndFeedrateFromGCode(GCodeBuffer& gb, int moveType) lastRawExtruderPosition[drive] += extrusionAmount; rawExtruderTotalByDrive[drive] += extrusionAmount; rawExtruderTotal += extrusionAmount; - moveBuffer.coords[drive + numAxes] = extrusionAmount * extrusionFactors[drive]; + moveBuffer.coords[drive + numTotalAxes] = extrusionAmount * extrusionFactors[drive]; } } } @@ -1129,7 +1129,7 @@ bool GCodes::LoadExtrusionAndFeedrateFromGCode(GCodeBuffer& gb, int moveType) lastRawExtruderPosition[drive] += extrusionAmount; rawExtruderTotalByDrive[drive] += extrusionAmount; rawExtruderTotal += extrusionAmount; - moveBuffer.coords[drive + numAxes] = extrusionAmount * extrusionFactors[drive]; + moveBuffer.coords[drive + numTotalAxes] = extrusionAmount * extrusionFactors[drive]; } } } @@ -1147,7 +1147,7 @@ unsigned int GCodes::LoadMoveBufferFromGCode(GCodeBuffer& gb, int moveType) { const Tool * const currentTool = reprap.GetCurrentTool(); unsigned int numSegments = 1; - for (size_t axis = 0; axis < numAxes; axis++) + for (size_t axis = 0; axis < numVisibleAxes; axis++) { if (gb.Seen(axisLetters[axis])) { @@ -1161,7 +1161,7 @@ unsigned int GCodes::LoadMoveBufferFromGCode(GCodeBuffer& gb, int moveType) { // Perform X axis mapping const uint32_t xMap = currentTool->GetXAxisMap(); - for (size_t mappedAxis = 0; mappedAxis < numAxes; ++mappedAxis) + for (size_t mappedAxis = 0; mappedAxis < numVisibleAxes; ++mappedAxis) { if ((xMap & (1u << mappedAxis)) != 0) { @@ -1233,7 +1233,7 @@ unsigned int GCodes::LoadMoveBufferFromGCode(GCodeBuffer& gb, int moveType) #endif ) { - reprap.GetMove().GetKinematics().LimitPosition(moveBuffer.coords, numAxes, axesHomed); + reprap.GetMove().GetKinematics().LimitPosition(moveBuffer.coords, numVisibleAxes, axesHomed); } return numSegments; @@ -1267,7 +1267,7 @@ int GCodes::SetUpMove(GCodeBuffer& gb, StringRef& reply) if (ival == 1) { - for (size_t i = 0; i < numAxes; ++i) + for (size_t i = 0; i < numTotalAxes; ++i) { if (gb.Seen(axisLetters[i])) { @@ -1317,7 +1317,7 @@ int GCodes::SetUpMove(GCodeBuffer& gb, StringRef& reply) } // Load the move buffer with either the absolute movement required or the relative movement required - memcpy(moveBuffer.initialCoords, moveBuffer.coords, numAxes * sizeof(moveBuffer.initialCoords[0])); + memcpy(moveBuffer.initialCoords, moveBuffer.coords, numVisibleAxes * sizeof(moveBuffer.initialCoords[0])); if (LoadExtrusionAndFeedrateFromGCode(gb, moveBuffer.moveType)) { segmentsLeft = LoadMoveBufferFromGCode(gb, moveBuffer.moveType); @@ -1327,7 +1327,7 @@ int GCodes::SetUpMove(GCodeBuffer& gb, StringRef& reply) // We assume it is a normal printing move needing pressure advance if there is forward extrusion and XYU.. movement. // The movement code will only apply pressure advance if there is forward extrusion, so we only need to check for XYU.. movement here. moveBuffer.usePressureAdvance = false; - for (size_t axis = 0; axis < numAxes; ++axis) + for (size_t axis = 0; axis < numVisibleAxes; ++axis) { if (axis != Z_AXIS && moveBuffer.coords[axis] != moveBuffer.initialCoords[axis]) { @@ -1347,7 +1347,7 @@ int GCodes::SetUpMove(GCodeBuffer& gb, StringRef& reply) // Calculate the XY length of the move float sumOfSquares = 0.0; unsigned int numXaxes = 0; - for (size_t axis = 0; axis < numAxes; ++axis) + for (size_t axis = 0; axis < numVisibleAxes; ++axis) { if ((moveBuffer.xAxes & (1u << axis)) != 0) { @@ -1386,7 +1386,7 @@ bool GCodes::DoArcMove(GCodeBuffer& gb, bool clockwise) // Adjust them for relative/absolute coordinates, tool offset, and X axis mapping. Also get the optional Z parameter const Tool * const currentTool = reprap.GetCurrentTool(); const bool axesRelative = gb.MachineState().axesRelative; - memcpy(moveBuffer.initialCoords, moveBuffer.coords, numAxes * sizeof(moveBuffer.initialCoords[0])); + memcpy(moveBuffer.initialCoords, moveBuffer.coords, numVisibleAxes * sizeof(moveBuffer.initialCoords[0])); if (gb.Seen('Z')) { @@ -1424,7 +1424,7 @@ bool GCodes::DoArcMove(GCodeBuffer& gb, bool clockwise) } // Deal with the X axes - for (size_t axis = 0; axis < numAxes; ++axis) + for (size_t axis = 0; axis < numVisibleAxes; ++axis) { if (axis != Y_AXIS) { @@ -1514,7 +1514,7 @@ bool GCodes::ReadMove(RawMove& m) arcCurrentAngle += arcAngleIncrement; } - for (size_t drive = 0; drive < numAxes; ++drive) + for (size_t drive = 0; drive < numVisibleAxes; ++drive) { if (doingArcMove && drive != Z_AXIS) { @@ -1537,7 +1537,7 @@ bool GCodes::ReadMove(RawMove& m) } // Do the extruders - for (size_t drive = numAxes; drive < DRIVES; ++drive) + for (size_t drive = numTotalAxes; drive < DRIVES; ++drive) { const float extrusionToDo = moveBuffer.coords[drive]/segmentsLeft; m.coords[drive] = extrusionToDo; @@ -1553,7 +1553,7 @@ bool GCodes::ReadMove(RawMove& m) // Calculate the move length, to see how much new babystepping is appropriate for this move float xMoveLength = 0.0; const uint32_t xAxes = reprap.GetCurrentXAxes(); - for (size_t drive = 0; drive < numAxes; ++drive) + for (size_t drive = 0; drive < numVisibleAxes; ++drive) { if ((xAxes & (1 << drive)) != 0) { @@ -1686,7 +1686,7 @@ bool GCodes::SetPositions(GCodeBuffer& gb) // Don't pause the machine if only extruder drives are being reset (DC, 2015-09-06). // This avoids blobs and seams when the gcode uses absolute E coordinates and periodically includes G92 E0. bool includingAxes = false; - for (size_t drive = 0; drive < numAxes; ++drive) + for (size_t drive = 0; drive < numVisibleAxes; ++drive) { if (gb.Seen(axisLetters[drive])) { @@ -1746,7 +1746,7 @@ bool GCodes::OffsetAxes(GCodeBuffer& gb) for (size_t drive = 0; drive < DRIVES; drive++) { cannedMoveType[drive] = CannedMoveType::none; - if (drive < numAxes) + if (drive < numVisibleAxes) { record[drive] = moveBuffer.coords[drive]; if (gb.Seen(axisLetters[drive])) @@ -1827,7 +1827,7 @@ bool GCodes::DoHome(GCodeBuffer& gb, StringRef& reply, bool& error) else { toBeHomed = 0; - for (size_t axis = 0; axis < numAxes; ++axis) + for (size_t axis = 0; axis < numTotalAxes; ++axis) { if (gb.Seen(axisLetters[axis])) { @@ -1840,7 +1840,7 @@ bool GCodes::DoHome(GCodeBuffer& gb, StringRef& reply, bool& error) { ClearBabyStepping(); } - if (toBeHomed == 0 || toBeHomed == ((1u << numAxes) - 1)) + if (toBeHomed == 0 || toBeHomed == ((1u << numTotalAxes) - 1)) { // Homing everything SetAllAxesNotHomed(); @@ -1848,7 +1848,7 @@ bool GCodes::DoHome(GCodeBuffer& gb, StringRef& reply, bool& error) } else if ( platform.MustHomeXYBeforeZ() && ((toBeHomed & (1u << Z_AXIS)) != 0) - && ((toBeHomed | axesHomed | (1u << Z_AXIS)) != ((1u << numAxes) - 1)) + && ((toBeHomed | axesHomed | (1u << Z_AXIS)) != ((1u << numVisibleAxes) - 1)) ) { // We can only home Z if both X and Y have already been homed or are being homed @@ -2007,40 +2007,32 @@ bool GCodes::DoSingleZProbe(GCodeBuffer& gb, StringRef& reply, bool reportOnly, // Returns 2 if success, with the current position in moveBuffer int GCodes::DoZProbe(GCodeBuffer& gb, float distance) { - if (platform.GetZProbeType() == ZProbeTypeDelta) + // Check for probe already triggered at start + if (!cannedCycleMoveQueued) { - const ZProbeParameters& params = platform.GetCurrentZProbeParameters(); - return reprap.GetMove().DoDeltaProbe(params.extraParam, 1.0, params.probeSpeed, distance); //TODO second parameter - } - else - { - // Check for probe already triggered at start - if (!cannedCycleMoveQueued) + if (reprap.GetPlatform().GetZProbeResult() == EndStopHit::lowHit) { - if (reprap.GetPlatform().GetZProbeResult() == EndStopHit::lowHit) - { - return 0; - } - zProbeTriggered = false; + return 0; } + zProbeTriggered = false; + } - // Do a normal canned cycle Z movement with Z probe enabled - for (size_t drive = 0; drive < DRIVES; drive++) - { - cannedMoveType[drive] = CannedMoveType::none; - } + // Do a normal canned cycle Z movement with Z probe enabled + for (size_t drive = 0; drive < DRIVES; drive++) + { + cannedMoveType[drive] = CannedMoveType::none; + } - cannedMoveCoords[Z_AXIS] = -distance; - cannedMoveType[Z_AXIS] = CannedMoveType::relative; - cannedFeedRate = platform.GetCurrentZProbeParameters().probeSpeed; + cannedMoveCoords[Z_AXIS] = -distance; + cannedMoveType[Z_AXIS] = CannedMoveType::relative; + cannedFeedRate = platform.GetCurrentZProbeParameters().probeSpeed; - if (DoCannedCycleMove(gb, ZProbeActive)) - { - platform.SetProbing(false); - return (zProbeTriggered) ? 2 : 1; - } - return -1; + if (DoCannedCycleMove(gb, ZProbeActive)) + { + platform.SetProbing(false); + return (zProbeTriggered) ? 2 : 1; } + return -1; } // This is called to execute a G30. @@ -2375,26 +2367,26 @@ void GCodes::GetCurrentCoordinates(StringRef& s) const if (currentTool != nullptr) { const float * const offset = currentTool->GetOffset(); - for (size_t i = 0; i < numAxes; ++i) + for (size_t i = 0; i < numVisibleAxes; ++i) { liveCoordinates[i] += offset[i]; } } s.Clear(); - for (size_t axis = 0; axis < numAxes; ++axis) + for (size_t axis = 0; axis < numVisibleAxes; ++axis) { s.catf("%c: %.3f ", axisLetters[axis], liveCoordinates[axis]); } - for (size_t i = numAxes; i < DRIVES; i++) + for (size_t i = numTotalAxes; i < DRIVES; i++) { - s.catf("E%u: %.1f ", i - numAxes, liveCoordinates[i]); + s.catf("E%u: %.1f ", i - numTotalAxes, liveCoordinates[i]); } // Print the axis stepper motor positions as Marlin does, as an aid to debugging. // Don't bother with the extruder endpoints, they are zero after any non-extruding move. s.cat(" Count"); - for (size_t i = 0; i < numAxes; ++i) + for (size_t i = 0; i < numVisibleAxes; ++i) { s.catf(" %d", reprap.GetMove().GetEndPoint(i)); } @@ -2614,14 +2606,14 @@ bool GCodes::SetOrReportOffsets(GCodeBuffer &gb, StringRef& reply) } // Deal with setting offsets - float offset[MAX_AXES]; - for (size_t i = 0; i < MAX_AXES; ++i) + float offset[MaxAxes]; + for (size_t i = 0; i < MaxAxes; ++i) { offset[i] = tool->GetOffset()[i]; } bool settingOffset = false; - for (size_t axis = 0; axis < numAxes; ++axis) + for (size_t axis = 0; axis < numVisibleAxes; ++axis) { gb.TryGetFValue(axisLetters[axis], offset[axis], settingOffset); } @@ -2637,8 +2629,8 @@ bool GCodes::SetOrReportOffsets(GCodeBuffer &gb, StringRef& reply) // Deal with setting temperatures bool settingTemps = false; size_t hCount = tool->HeaterCount(); - float standby[HEATERS]; - float active[HEATERS]; + float standby[Heaters]; + float active[Heaters]; if (hCount > 0) { tool->GetVariables(standby, active); @@ -2663,7 +2655,7 @@ bool GCodes::SetOrReportOffsets(GCodeBuffer &gb, StringRef& reply) { // Print offsets and temperatures reply.printf("Tool %d offsets:", toolNumber); - for (size_t axis = 0; axis < numAxes; ++axis) + for (size_t axis = 0; axis < numVisibleAxes; ++axis) { reply.catf(" %c%.2f", axisLetters[axis], offset[axis]); } @@ -2716,8 +2708,8 @@ void GCodes::ManageTool(GCodeBuffer& gb, StringRef& reply) } // Check heaters - long heaters[HEATERS]; - size_t hCount = HEATERS; + long heaters[Heaters]; + size_t hCount = Heaters; if (gb.Seen('H')) { gb.GetLongArray(heaters, hCount); @@ -2732,10 +2724,10 @@ void GCodes::ManageTool(GCodeBuffer& gb, StringRef& reply) uint32_t xMap; if (gb.Seen('X')) { - long xMapping[MAX_AXES]; - size_t xCount = numAxes; + long xMapping[MaxAxes]; + size_t xCount = numVisibleAxes; gb.GetLongArray(xMapping, xCount); - xMap = LongArrayToBitMap(xMapping, xCount) & ((1u << numAxes) - 1); + xMap = LongArrayToBitMap(xMapping, xCount) & ((1u << numVisibleAxes) - 1); seen = true; } else @@ -3077,7 +3069,7 @@ void GCodes::SetPidParameters(GCodeBuffer& gb, int heater, StringRef& reply) heater = gb.GetIValue(); } - if (heater >= 0 && heater < HEATERS) + if (heater >= 0 && heater < (int)Heaters) { const FopDt& model = reprap.GetHeat().GetHeaterModel(heater); M301PidParameters pp = model.GetM301PidParameters(false); @@ -3105,72 +3097,53 @@ void GCodes::SetPidParameters(GCodeBuffer& gb, int heater, StringRef& reply) } } -void GCodes::SetHeaterParameters(GCodeBuffer& gb, StringRef& reply) +// Process M305, returning true if an error occurs +bool GCodes::SetHeaterParameters(GCodeBuffer& gb, StringRef& reply) { if (gb.Seen('P')) { int heater = gb.GetIValue(); - if (heater >= 0 && heater < HEATERS) + if ((heater >= 0 && heater < (int)Heaters) || (heater >= (int)FirstVirtualHeater && heater < (int)(FirstVirtualHeater + MaxVirtualHeaters))) { - Thermistor& th = platform.GetThermistor(heater); + Heat& heat = reprap.GetHeat(); + const int oldChannel = heat.GetHeaterChannel(heater); bool seen = false; - - // We must set the 25C resistance and beta together in order to calculate Rinf. Check for these first. - float r25 = th.GetR25(); - float beta = th.GetBeta(); - float shC = th.GetShc(); - float seriesR = th.GetSeriesR(); - - gb.TryGetFValue('T', r25, seen); - gb.TryGetFValue('B', beta, seen); - gb.TryGetFValue('C', shC, seen); - gb.TryGetFValue('R', seriesR, seen); - if (seen) - { - th.SetParameters(r25, beta, shC, seriesR); - } - - if (gb.Seen('L')) - { - th.SetLowOffset((int8_t)constrain<int>(gb.GetIValue(), -100, 100)); - seen = true; - } - if (gb.Seen('H')) - { - th.SetHighOffset((int8_t)constrain<int>(gb.GetIValue(), -100, 100)); - seen = true; - } - - if (gb.Seen('X')) + long channel = oldChannel; + gb.TryGetIValue('X', channel, seen); + if (!seen && oldChannel < 0) { - int thermistor = gb.GetIValue(); - if ( (0 <= thermistor && thermistor < HEATERS) - || ((int)FirstThermocoupleChannel <= thermistor && thermistor < (int)(FirstThermocoupleChannel + MaxSpiTempSensors)) - || ((int)FirstRtdChannel <= thermistor && thermistor < (int)(FirstRtdChannel + MaxSpiTempSensors)) - || ((int)FirstLinearAdcChannel <= thermistor && thermistor < (int)(FirstLinearAdcChannel + MaxSpiTempSensors)) - ) + // For backwards compatibility, if no sensor has been configured on this channel then assume the thermistor normally associated with the heater + if (heater < (int)Heaters) { - platform.SetThermistorNumber(heater, thermistor); + channel = heater; } else { - platform.MessageF(GENERIC_MESSAGE, "Thermistor number %d is out of range\n", thermistor); + reply.printf("Virtual heater %d is not configured", heater); + return false; } - seen = true; } - if (!seen) + if (channel != oldChannel) { - reply.printf("T:%.1f B:%.1f C:%.2e R:%.1f L:%d H:%d X:%d", - th.GetR25(), th.GetBeta(), th.GetShc(), th.GetSeriesR(), - th.GetLowOffset(), th.GetHighOffset(), platform.GetThermistorNumber(heater)); + if (heat.SetHeaterChannel(heater, channel)) + { + reply.printf("unable to use sensor channel %d on heater %d", channel, heater); + return true; + } } + + bool hadError = false; + heat.ConfigureHeaterSensor(305, (unsigned int)heater, gb, reply, hadError); + return hadError; } else { - platform.MessageF(GENERIC_MESSAGE, "Heater number %d is out of range\n", heater); + reply.printf("heater number %d is out of range", heater); + return true; } } + return false; } void GCodes::SetToolHeaters(Tool *tool, float temperature) @@ -3181,8 +3154,8 @@ void GCodes::SetToolHeaters(Tool *tool, float temperature) return; } - float standby[HEATERS]; - float active[HEATERS]; + float standby[Heaters]; + float active[Heaters]; tool->GetVariables(standby, active); for (size_t h = 0; h < tool->HeaterCount(); h++) { @@ -3206,7 +3179,7 @@ bool GCodes::RetractFilament(GCodeBuffer& gb, bool retract) // Get ready to generate a move const uint32_t xAxes = reprap.GetCurrentXAxes(); reprap.GetMove().GetCurrentUserPosition(moveBuffer.coords, 0, xAxes); - for (size_t i = numAxes; i < DRIVES; ++i) + for (size_t i = numTotalAxes; i < DRIVES; ++i) { moveBuffer.coords[i] = 0.0; } @@ -3224,7 +3197,7 @@ bool GCodes::RetractFilament(GCodeBuffer& gb, bool retract) { for (size_t i = 0; i < tool->DriveCount(); ++i) { - moveBuffer.coords[numAxes + tool->Drive(i)] = retractLength; + moveBuffer.coords[numTotalAxes + tool->Drive(i)] = -retractLength; } moveBuffer.feedRate = retractSpeed; moveBuffer.canPauseAfter = false; // don't pause after a retraction because that could cause too much retraction @@ -3252,7 +3225,7 @@ bool GCodes::RetractFilament(GCodeBuffer& gb, bool retract) { for (size_t i = 0; i < tool->DriveCount(); ++i) { - moveBuffer.coords[numAxes + tool->Drive(i)] = retractLength + retractExtra; + moveBuffer.coords[numTotalAxes + tool->Drive(i)] = retractLength + retractExtra; } moveBuffer.feedRate = unRetractSpeed; moveBuffer.canPauseAfter = true; @@ -3414,13 +3387,13 @@ void GCodes::ListTriggers(StringRef reply, TriggerMask mask) { reply.cat(' '); } - if (i < numAxes) + if (i < numVisibleAxes) { reply.cat(axisLetters[i]); } - else + else if (i >= numTotalAxes) { - reply.catf("E%d", i - numAxes); + reply.catf("E%d", i - numTotalAxes); } printed = true; } @@ -3479,7 +3452,7 @@ bool GCodes::AdvanceHash(StringRef &reply) bool GCodes::AllAxesAreHomed() const { - const uint32_t allAxes = (1u << numAxes) - 1; + const uint32_t allAxes = (1u << numTotalAxes) - 1; return (axesHomed & allAxes) == allAxes; } @@ -3530,7 +3503,7 @@ void GCodes::GenerateTemperatureReport(StringRef& reply) const const int8_t bedHeater = heat.GetBedHeater(); const int8_t chamberHeater = heat.GetChamberHeater(); reply.copy("T:"); - for (int8_t heater = 0; heater < HEATERS; heater++) + for (int heater = 0; heater < (int)Heaters; heater++) { if (heater != bedHeater && heater != chamberHeater) { @@ -3641,7 +3614,7 @@ bool GCodes::LockResource(const GCodeBuffer& gb, Resource r) bool GCodes::LockHeater(const GCodeBuffer& gb, int heater) { - if (heater >= 0 && heater < HEATERS) + if (heater >= 0 && heater < (int)Heaters) { return LockResource(gb, HeaterResourceBase + heater); } diff --git a/src/GCodes/GCodes.h b/src/GCodes/GCodes.h index b54a0430..d3453f20 100644 --- a/src/GCodes/GCodes.h +++ b/src/GCodes/GCodes.h @@ -75,7 +75,7 @@ public: struct RawMove { float coords[DRIVES]; // new positions for the axes, amount of movement for the extruders - float initialCoords[MAX_AXES]; // the initial positions of the axes + float initialCoords[MaxAxes]; // the initial positions of the axes float feedRate; // feed rate of this move FilePosition filePos; // offset in the file being printed at the end of reading this move uint32_t xAxes; // axes that X is mapped to @@ -139,10 +139,11 @@ public: void MoveStoppedByZProbe() { zProbeTriggered = true; } // Called from the step ISR when the Z probe is triggered, causing the move to be aborted - size_t GetNumAxes() const { return numAxes; } + size_t GetTotalAxes() const { return numTotalAxes; } + size_t GetVisibleAxes() const { return numVisibleAxes; } size_t GetNumExtruders() const { return numExtruders; } - static const char axisLetters[MAX_AXES]; // 'X', 'Y', 'Z' + static const char axisLetters[MaxAxes]; // 'X', 'Y', 'Z' private: GCodes(const GCodes&); // private copy constructor to prevent copying @@ -163,7 +164,7 @@ private: 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 Resource FanResourceBase = HeaterResourceBase + Heaters; static const size_t NumResources = FanResourceBase + NUM_FANS; static_assert(NumResources <= 32, "Too many resources to keep a bitmap of them in class GCodeMachineState"); @@ -214,7 +215,7 @@ private: bool SendConfigToLine(); // Deal with M503 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 + bool SetHeaterParameters(GCodeBuffer& gb, StringRef& reply); // Set the thermistor and ADC parameters for a heater, returning true if an error occurs 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 @@ -278,7 +279,7 @@ private: // The following contain the details of moves that the Move module fetches RawMove moveBuffer; // Move details to pass to Move class unsigned int segmentsLeft; // The number of segments left to do in the current move, or 0 if no move available - float arcCentre[MAX_AXES]; + float arcCentre[MaxAxes]; float arcRadius; float arcCurrentAngle; float arcAngleIncrement; @@ -288,9 +289,10 @@ private: 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 numTotalAxes; // How many axes we have + size_t numVisibleAxes; // How many axes are visible 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 axisScaleFactors[MaxAxes]; // 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 diff --git a/src/GCodes/GCodes2.cpp b/src/GCodes/GCodes2.cpp index 03d64b15..6a375cb3 100644 --- a/src/GCodes/GCodes2.cpp +++ b/src/GCodes/GCodes2.cpp @@ -107,13 +107,13 @@ bool GCodes::HandleGcode(GCodeBuffer& gb, StringRef& reply) { return false; } - for (size_t axis = 0; axis < numAxes; ++axis) + for (size_t axis = 0; axis < numVisibleAxes; ++axis) { float offset = gb.Seen(axisLetters[axis]) ? gb.GetFValue() * distanceScale : 0.0; moveBuffer.coords[axis] = rp->moveCoords[axis] + offset; } // For now we don't handle extrusion at the same time - for (size_t drive = numAxes; drive < DRIVES; ++drive) + for (size_t drive = numTotalAxes; drive < DRIVES; ++drive) { moveBuffer.coords[drive] = 0.0; } @@ -335,7 +335,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) } { bool seen = false; - for (size_t axis = 0; axis < numAxes; axis++) + for (size_t axis = 0; axis < numTotalAxes; axis++) { if (gb.Seen(axisLetters[axis])) { @@ -359,7 +359,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) error = true; break; } - platform.DisableDrive(numAxes + eDrive[i]); + platform.DisableDrive(numTotalAxes + eDrive[i]); } } @@ -827,7 +827,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) move.GetCurrentUserPosition(positionNow, 0, reprap.GetCurrentXAxes()); bool seen = false; - for (size_t axis = 0; axis < numAxes; axis++) + for (size_t axis = 0; axis < numTotalAxes; axis++) { if (gb.Seen(axisLetters[axis])) { @@ -854,7 +854,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) // The user may not have as many extruders as we allow for, so just set the ones for which a value is provided for (size_t e = 0; e < eCount; e++) { - platform.SetDriveStepsPerUnit(numAxes + e, eVals[e]); + platform.SetDriveStepsPerUnit(numTotalAxes + e, eVals[e]); } } @@ -866,7 +866,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) else { reply.copy("Steps/mm: "); - for (size_t axis = 0; axis < numAxes; ++axis) + for (size_t axis = 0; axis < numTotalAxes; ++axis) { reply.catf("%c: %.3f, ", axisLetters[axis], platform.DriveStepsPerUnit(axis)); } @@ -874,7 +874,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) char sep = ' '; for (size_t extruder = 0; extruder < numExtruders; extruder++) { - reply.catf("%c%.3f", sep, platform.DriveStepsPerUnit(extruder + numAxes)); + reply.catf("%c%.3f", sep, platform.DriveStepsPerUnit(extruder + numTotalAxes)); sep = ':'; } } @@ -941,144 +941,44 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) bool seenFanNum = false; int32_t fanNum = 0; // Default to the first fan gb.TryGetIValue('P', fanNum, seenFanNum); - if (fanNum < 0 || fanNum > (int)NUM_FANS) + const bool processed = platform.ConfigureFan(code, fanNum, gb, reply, error); + + // ConfigureFan only processes S parameters if there were other parameters to process + if (!processed && gb.Seen('S')) { - reply.printf("Fan number %d is invalid, must be between 0 and %u", fanNum, NUM_FANS); + const float f = constrain<float>(gb.GetFValue(), 0.0, 255.0); + if (seenFanNum) + { + platform.SetFanValue(fanNum, f); + } + else + { + // We are processing an M106 S### command with no other recognised parameters and we have a tool selected. + // Apply the fan speed setting to the fans in the fan mapping for the current tool. + lastDefaultFanSpeed = f; + SetMappedFanSpeed(); + } } - else + + // ConfigureFan doesn't process R parameters + if (gb.Seen('R')) { - Fan& fan = platform.GetFan(fanNum); - if (!fan.IsEnabled()) + // Restore fan speed to value when print was paused + if (seenFanNum) { - reply.printf("Fan number %d is disabled", fanNum); + platform.SetFanValue(fanNum, pausedFanSpeeds[fanNum]); } else { - bool seen = false; - if (gb.Seen('I')) // Invert cooling - { - const int invert = gb.GetIValue(); - if (invert < 0) - { - fan.Disable(); - } - else - { - fan.SetInverted(invert > 0); - } - seen = true; - } - - if (gb.Seen('F')) // Set PWM frequency - { - fan.SetPwmFrequency(gb.GetFValue()); - seen = true; - } - - if (gb.Seen('T')) // Set thermostatic trigger temperature - { - seen = true; - fan.SetTriggerTemperature(gb.GetFValue()); - } - - if (gb.Seen('B')) // Set blip time - { - seen = true; - fan.SetBlipTime(gb.GetFValue()); - } - - if (gb.Seen('L')) // Set minimum speed - { - seen = true; - fan.SetMinValue(gb.GetFValue()); - } - - if (gb.Seen('H')) // Set thermostatically-controlled heaters - { - seen = true; - long heaters[HEATERS]; - size_t numH = HEATERS; - gb.GetLongArray(heaters, numH); - // Note that M106 H-1 disables thermostatic mode. The following code implements that automatically. - uint16_t hh = 0; - for (size_t h = 0; h < numH; ++h) - { - const int hnum = heaters[h]; - if (hnum >= 0 && hnum < HEATERS) - { - hh |= (1u << (unsigned int)hnum); - } - else if (hnum >= (int)FirstVirtualHeater && hnum < (int)(FirstVirtualHeater + NumVirtualHeaters)) - { - // Heaters 100, 101... are virtual heaters i.e. CPU and driver temperatures - hh |= (1u << (HEATERS + (unsigned int)hnum - FirstVirtualHeater)); - } - } - if (hh != 0) - { - platform.SetFanValue(fanNum, 1.0); // default the fan speed to full for safety - } - fan.SetHeatersMonitored(hh); - } - - if (gb.Seen('S')) // Set new fan value - process this after processing 'H' or it may not be acted on - { - const float f = constrain<float>(gb.GetFValue(), 0.0, 255.0); - if (seen || seenFanNum) - { - platform.SetFanValue(fanNum, f); - } - else - { - // We are processing an M106 S### command with no other recognised parameters and we have a tool selected. - // Apply the fan speed setting to the fans in the fan mapping for the current tool. - lastDefaultFanSpeed = f; - SetMappedFanSpeed(); - } - } - else if (gb.Seen('R')) - { - // Restore fan speed to value when print was paused - if (seenFanNum) - { - platform.SetFanValue(fanNum, pausedFanSpeeds[fanNum]); - } - else - { - lastDefaultFanSpeed = pausedDefaultFanSpeed; - SetMappedFanSpeed(); - } - } - else if (!seen) - { - // Report the configuration of the specified fan - reply.printf("Fan%i frequency: %dHz, speed: %d%%, min: %d%%, blip: %.2f, inverted: %s", - fanNum, - (int)(fan.GetPwmFrequency()), - (int)(fan.GetValue() * 100.0), - (int)(fan.GetMinValue() * 100.0), - fan.GetBlipTime(), - (fan.GetInverted()) ? "yes" : "no"); - uint16_t hh = fan.GetHeatersMonitored(); - if (hh != 0) - { - reply.catf(", trigger: %dC, heaters:", (int)fan.GetTriggerTemperature()); - for (unsigned int i = 0; i < HEATERS + NumVirtualHeaters; ++i) - { - if ((hh & (1u << i)) != 0) - { - reply.catf(" %u", (i < HEATERS) ? i : FirstVirtualHeater + i - HEATERS); - } - } - } - } + lastDefaultFanSpeed = pausedDefaultFanSpeed; + SetMappedFanSpeed(); } } } break; - case 107: // Fan off - deprecated - platform.SetFanValue(0, 0.0); //T3P3 as deprecated only applies to fan0 + case 107: // Fan 0 off - deprecated + platform.SetFanValue(0, 0.0); break; case 108: // Cancel waiting for temperature @@ -1213,8 +1113,8 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) if (gb.Seen('H')) { // Wait for specified heaters to be ready - long heaters[HEATERS]; - size_t heaterCount = HEATERS; + long heaters[Heaters]; + size_t heaterCount = Heaters; gb.GetLongArray(heaters, heaterCount); if (!cancelWait) { @@ -1269,7 +1169,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) case 119: reply.copy("Endstops - "); - for (size_t axis = 0; axis < numAxes; axis++) + for (size_t axis = 0; axis < numTotalAxes; axis++) { reply.catf("%c: %s, ", axisLetters[axis], TranslateEndStopResult(platform.Stopped(axis))); } @@ -1324,7 +1224,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) // If we're disabling the hot bed, make sure the old heater is turned off heat.SwitchOff(heat.GetBedHeater()); } - else if (bedHeater >= HEATERS) + else if (bedHeater >= (int)Heaters) { reply.copy("Invalid heater number!"); error = true; @@ -1388,7 +1288,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) heat.SetChamberHeater(-1); } - else if (heater < HEATERS) + else if (heater < (int)Heaters) { heat.SetChamberHeater(heater); } @@ -1443,7 +1343,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) case 143: // Set temperature limit { const int heater = (gb.Seen('H')) ? gb.GetIValue() : 1; // default to extruder 1 if no heater number provided - if (heater < 0 || heater >= HEATERS) + if (heater < 0 || heater >= (int)Heaters) { reply.copy("Invalid heater number"); error = true; @@ -1519,7 +1419,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) case 201: // Set/print axis accelerations { bool seen = false; - for (size_t axis = 0; axis < numAxes; axis++) + for (size_t axis = 0; axis < numVisibleAxes; axis++) { if (gb.Seen(axisLetters[axis])) { @@ -1536,14 +1436,14 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) gb.GetFloatArray(eVals, eCount, true); for (size_t e = 0; e < eCount; e++) { - platform.SetAcceleration(numAxes + e, eVals[e] * distanceScale); + platform.SetAcceleration(numTotalAxes + e, eVals[e] * distanceScale); } } if (!seen) { reply.printf("Accelerations: "); - for (size_t axis = 0; axis < numAxes; ++axis) + for (size_t axis = 0; axis < numVisibleAxes; ++axis) { reply.catf("%c: %.1f, ", axisLetters[axis], platform.Acceleration(axis) / distanceScale); } @@ -1551,7 +1451,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) char sep = ' '; for (size_t extruder = 0; extruder < numExtruders; extruder++) { - reply.catf("%c%.1f", sep, platform.Acceleration(extruder + numAxes) / distanceScale); + reply.catf("%c%.1f", sep, platform.Acceleration(extruder + numTotalAxes) / distanceScale); sep = ':'; } } @@ -1561,7 +1461,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) case 203: // Set/print maximum feedrates { bool seen = false; - for (size_t axis = 0; axis < numAxes; ++axis) + for (size_t axis = 0; axis < numVisibleAxes; ++axis) { if (gb.Seen(axisLetters[axis])) { @@ -1578,14 +1478,14 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) gb.GetFloatArray(eVals, eCount, true); for (size_t e = 0; e < eCount; e++) { - platform.SetMaxFeedrate(numAxes + e, eVals[e] * distanceScale * SecondsToMinutes); + platform.SetMaxFeedrate(numTotalAxes + e, eVals[e] * distanceScale * SecondsToMinutes); } } if (!seen) { reply.copy("Maximum feedrates: "); - for (size_t axis = 0; axis < numAxes; ++axis) + for (size_t axis = 0; axis < numVisibleAxes; ++axis) { reply.catf("%c: %.1f, ", axisLetters[axis], platform.MaxFeedrate(axis) / (distanceScale * SecondsToMinutes)); } @@ -1593,7 +1493,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) char sep = ' '; for (size_t extruder = 0; extruder < numExtruders; extruder++) { - reply.catf("%c%.1f", sep, platform.MaxFeedrate(extruder + numAxes) / (distanceScale * SecondsToMinutes)); + reply.catf("%c%.1f", sep, platform.MaxFeedrate(extruder + numTotalAxes) / (distanceScale * SecondsToMinutes)); sep = ':'; } } @@ -1672,7 +1572,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) { bool setMin = (gb.Seen('S') ? (gb.GetIValue() == 1) : false); bool seen = false; - for (size_t axis = 0; axis < numAxes; axis++) + for (size_t axis = 0; axis < numVisibleAxes; axis++) { if (gb.Seen(axisLetters[axis])) { @@ -1693,7 +1593,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) { reply.copy("Axis limits "); char sep = '-'; - for (size_t axis = 0; axis < numAxes; axis++) + for (size_t axis = 0; axis < numVisibleAxes; axis++) { reply.catf("%c %c: %.1f min, %.1f max", sep, axisLetters[axis], platform.AxisMinimum(axis), platform.AxisMaximum(axis)); @@ -1758,7 +1658,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) { if (segmentsLeft != 0 && !moveBuffer.isFirmwareRetraction) { - moveBuffer.coords[extruder + numAxes] *= extrusionFactor/extrusionFactors[extruder]; // last move not gone, so update it + moveBuffer.coords[extruder + numTotalAxes] *= extrusionFactor/extrusionFactors[extruder]; // last move not gone, so update it } extrusionFactors[extruder] = extrusionFactor; } @@ -1870,7 +1770,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) : heater == reprap.GetHeat().GetChamberHeater() ? 50.0 : 200.0; const float maxPwm = (gb.Seen('P')) ? gb.GetFValue() : 1.0; - if (heater < 0 || heater >= HEATERS) + if (heater < 0 || heater >= (int)Heaters) { reply.copy("Bad heater number in M303 command"); } @@ -1904,14 +1804,14 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) break; case 305: // Set/report specific heater parameters - SetHeaterParameters(gb, reply); + error = SetHeaterParameters(gb, reply); break; case 307: // Set heater process model parameters if (gb.Seen('H')) { - size_t heater = gb.GetIValue(); - if (heater < HEATERS) + int heater = gb.GetIValue(); + if (heater >= 0 && heater < (int)Heaters) { const FopDt& model = reprap.GetHeat().GetHeaterModel(heater); bool seen = false; @@ -1966,7 +1866,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) gb.TryGetIValue('I', mode, dummy); bool seen = false; - for (size_t axis = 0; axis < numAxes; axis++) + for (size_t axis = 0; axis < numTotalAxes; axis++) { if (gb.Seen(axisLetters[axis])) { @@ -2000,7 +1900,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) gb.GetLongArray(eVals, eCount); for (size_t e = 0; e < eCount; e++) { - if (!ChangeMicrostepping(numAxes + e, (int)eVals[e], mode)) + if (!ChangeMicrostepping(numTotalAxes + e, (int)eVals[e], mode)) { platform.MessageF(GENERIC_MESSAGE, "Drive E%u does not support %dx microstepping%s\n", e, (int)eVals[e], (mode) ? " with interpolation" : ""); @@ -2011,7 +1911,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) if (!seen) { reply.copy("Microstepping - "); - for (size_t axis = 0; axis < numAxes; ++axis) + for (size_t axis = 0; axis < numTotalAxes; ++axis) { bool interp; const int microsteps = platform.GetMicrostepping(axis, mode, interp); @@ -2021,7 +1921,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) for (size_t extruder = 0; extruder < numExtruders; extruder++) { bool interp; - const int microsteps = platform.GetMicrostepping(extruder + numAxes, mode, interp); + const int microsteps = platform.GetMicrostepping(extruder + numTotalAxes, mode, interp); reply.catf(":%d%s", microsteps, (interp) ? "(on)" : ""); } } @@ -2360,7 +2260,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) { bool seenAxes = false, seenType = false, seenParam = false; uint32_t zProbeAxes = platform.GetZProbeAxes(); - for (size_t axis = 0; axis < numAxes; axis++) + for (size_t axis = 0; axis < numVisibleAxes; axis++) { if (gb.Seen(axisLetters[axis])) { @@ -2421,12 +2321,8 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) reply.printf("Z Probe type %d, invert %s, dive height %.1fmm, probe speed %dmm/min, travel speed %dmm/min, recovery time %.2f sec", platform.GetZProbeType(), (params.invertReading) ? "yes" : "no", params.diveHeight, (int)(params.probeSpeed * MinutesToSeconds), (int)(params.travelSpeed * MinutesToSeconds), params.recoveryTime); - if (platform.GetZProbeType() == ZProbeTypeDelta) - { - reply.catf(", extra parameter %.2f", params.extraParam); - } reply.cat(", used for axes:"); - for (size_t axis = 0; axis < numAxes; axis++) + for (size_t axis = 0; axis < numVisibleAxes; axis++) { if ((zProbeAxes & (1u << axis)) != 0) { @@ -2477,7 +2373,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) if (gb.Seen('P')) { const int heater = gb.GetIValue(); - if (heater >= 0 && heater < HEATERS) + if (heater >= 0 && heater < (int)Heaters) { reprap.ClearTemperatureFault(heater); } @@ -2507,7 +2403,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) case 566: // Set/print maximum jerk speeds { bool seen = false; - for (size_t axis = 0; axis < numAxes; axis++) + for (size_t axis = 0; axis < numVisibleAxes; axis++) { if (gb.Seen(axisLetters[axis])) { @@ -2524,13 +2420,13 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) gb.GetFloatArray(eVals, eCount, true); for (size_t e = 0; e < eCount; e++) { - platform.SetInstantDv(numAxes + e, eVals[e] * distanceScale * SecondsToMinutes); + platform.SetInstantDv(numTotalAxes + e, eVals[e] * distanceScale * SecondsToMinutes); } } else if (!seen) { reply.copy("Maximum jerk rates: "); - for (size_t axis = 0; axis < numAxes; ++axis) + for (size_t axis = 0; axis < numVisibleAxes; ++axis) { reply.catf("%c: %.1f, ", axisLetters[axis], platform.ConfiguredInstantDv(axis) / (distanceScale * SecondsToMinutes)); } @@ -2538,7 +2434,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) char sep = ' '; for (size_t extruder = 0; extruder < numExtruders; extruder++) { - reply.catf("%c%.1f", sep, platform.ConfiguredInstantDv(extruder + numAxes) / (distanceScale * SecondsToMinutes)); + reply.catf("%c%.1f", sep, platform.ConfiguredInstantDv(extruder + numTotalAxes) / (distanceScale * SecondsToMinutes)); sep = ':'; } } @@ -2629,7 +2525,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) seen = true; } bool badParameter = false; - for (size_t axis = 0; axis < numAxes; ++axis) + for (size_t axis = 0; axis < numTotalAxes; ++axis) { if (gb.Seen(axisLetters[axis])) { @@ -2658,9 +2554,9 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) case 570: // Set/report heater timeout if (gb.Seen('H')) { - const size_t heater = gb.GetIValue(); + const int heater = gb.GetIValue(); bool seen = false; - if (heater < HEATERS) + if (heater >= 0 && heater < (int)Heaters) { float maxTempExcursion, maxFaultTime; reprap.GetHeat().GetHeaterProtection(heater, maxTempExcursion, maxFaultTime); @@ -2734,7 +2630,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) if (gb.Seen('P')) { const int heater = gb.GetIValue(); - if (heater >= 0 && heater < HEATERS) + if (heater >= 0 && heater < (int)Heaters) { reply.printf("Average heater %d PWM: %.3f", heater, reprap.GetHeat().GetAveragePWM(heater)); } @@ -2745,7 +2641,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) { bool seen = false; const bool logicLevel = (gb.Seen('S')) ? (gb.GetIValue() != 0) : true; - for (size_t axis = 0; axis < numAxes; ++axis) + for (size_t axis = 0; axis < numTotalAxes; ++axis) { if (gb.Seen(axisLetters[axis])) { @@ -2762,7 +2658,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) reply.copy("Endstop configuration:"); EndStopType config; bool logic; - for (size_t axis = 0; axis < numAxes; ++axis) + for (size_t axis = 0; axis < numTotalAxes; ++axis) { platform.GetEndStopConfiguration(axis, config, logic); reply.catf(" %c %s (active %s),", axisLetters[axis], @@ -2834,7 +2730,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) } // Axis endstops - for (size_t axis=0; axis < numAxes; axis++) + for (size_t axis=0; axis < numTotalAxes; axis++) { if (gb.Seen(axisLetters[axis])) { @@ -2889,7 +2785,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) case 579: // Scale Cartesian axes (mostly for Delta configurations) { bool seen = false; - for (size_t axis = 0; axis < numAxes; axis++) + for (size_t axis = 0; axis < numVisibleAxes; axis++) { gb.TryGetFValue(axisLetters[axis], axisScaleFactors[axis], seen); } @@ -2898,7 +2794,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) { char sep = ':'; reply.copy("Axis scale factors"); - for(size_t axis = 0; axis < numAxes; axis++) + for(size_t axis = 0; axis < numVisibleAxes; axis++) { reply.catf("%c %c: %.3f", sep, axisLetters[axis], axisScaleFactors[axis]); sep = ','; @@ -2963,7 +2859,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) seen = true; int sval = gb.GetIValue(); TriggerMask triggerMask = 0; - for (size_t axis = 0; axis < numAxes; ++axis) + for (size_t axis = 0; axis < numTotalAxes; ++axis) { if (gb.Seen(axisLetters[axis])) { @@ -3037,7 +2933,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) } { bool seen = false, badDrive = false; - for (size_t drive = 0; drive < MAX_AXES; ++drive) + for (size_t drive = 0; drive < MaxAxes; ++drive) { if (gb.Seen(axisLetters[drive])) { @@ -3067,16 +2963,17 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) } else { - while (numAxes <= drive) + while (numTotalAxes <= drive) { - moveBuffer.coords[numAxes] = 0.0; // user has defined a new axis, so set its position - ++numAxes; + moveBuffer.coords[numTotalAxes] = 0.0; // user has defined a new axis, so set its position + ++numTotalAxes; } - SetPositions(moveBuffer.coords); // tell the Move system where any new axes are + numVisibleAxes = numTotalAxes; // assume all axes are visible unless there is a P parameter + SetPositions(moveBuffer.coords); // tell the Move system where any new axes are platform.SetAxisDriversConfig(drive, config); - if (numAxes + numExtruders > DRIVES) + if (numTotalAxes + numExtruders > DRIVES) { - numExtruders = DRIVES - numAxes; // if we added axes, we may have fewer extruders now + numExtruders = DRIVES - numTotalAxes; // if we added axes, we may have fewer extruders now } } } @@ -3085,7 +2982,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) if (gb.Seen(extrudeLetter)) { seen = true; - size_t numValues = DRIVES - numAxes; + size_t numValues = DRIVES - numTotalAxes; long drivers[MaxExtruders]; gb.GetLongArray(drivers, numValues); numExtruders = numValues; @@ -3104,28 +3001,47 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) if (badDrive) { - platform.Message(GENERIC_MESSAGE, "Error: invalid drive number in M584 command\n"); + reply.copy("Error: invalid drive number in M584 command\n"); + error = true; } - else if (!seen) + else { - reply.copy("Driver assignments:"); - for (size_t drive = 0; drive < numAxes; ++ drive) + if (gb.Seen('P')) { - reply.cat(' '); - const AxisDriversConfig& axisConfig = platform.GetAxisDriversConfig(drive); - char c = axisLetters[drive]; - for (size_t i = 0; i < axisConfig.numDrivers; ++i) + seen = true; + const int nva = gb.GetIValue(); + if (nva >= (int)MinAxes && (unsigned int)nva <= numTotalAxes) { - reply.catf("%c%u", c, axisConfig.driverNumbers[i]); - c = ':'; + numVisibleAxes = (size_t)nva; + } + else + { + reply.copy("Error: invalid number of visible axes in M584 command\n"); + error = true; } } - reply.cat(' '); - char c = extrudeLetter; - for (size_t extruder = 0; extruder < numExtruders; ++extruder) + + if (!seen) { - reply.catf("%c%u", c, platform.GetExtruderDriver(extruder)); - c = ':'; + reply.copy("Driver assignments:"); + for (size_t drive = 0; drive < numTotalAxes; ++ drive) + { + reply.cat(' '); + const AxisDriversConfig& axisConfig = platform.GetAxisDriversConfig(drive); + char c = axisLetters[drive]; + for (size_t i = 0; i < axisConfig.numDrivers; ++i) + { + reply.catf("%c%u", c, axisConfig.driverNumbers[i]); + c = ':'; + } + } + reply.cat(' '); + char c = extrudeLetter; + for (size_t extruder = 0; extruder < numExtruders; ++extruder) + { + reply.catf("%c%u", c, platform.GetExtruderDriver(extruder)); + c = ':'; + } } } } @@ -3162,10 +3078,10 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) { WirelessConfigurationData config; memset(&config, 0, sizeof(config)); - bool ok = gb.GetString(config.ssid, ARRAY_SIZE(config.ssid)); + bool ok = gb.GetQuotedString(config.ssid, ARRAY_SIZE(config.ssid)); if (ok) { - ok = gb.SeenAfterSpace('P') && gb.GetString(config.password, ARRAY_SIZE(config.password)); + ok = gb.SeenAfterSpace('P') && gb.GetQuotedString(config.password, ARRAY_SIZE(config.password)); } if (ok && gb.SeenAfterSpace('I')) { @@ -3239,7 +3155,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) if (gb.SeenAfterSpace('S')) { uint32_t ssid[NumDwords(SsidLength)]; - if (gb.GetString(reinterpret_cast<char*>(ssid), SsidLength)) + if (gb.GetQuotedString(reinterpret_cast<char*>(ssid), SsidLength)) { const char* const pssid = reinterpret_cast<const char*>(ssid); if (strcmp(pssid, "ALL") == 0) @@ -3274,10 +3190,10 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) { WirelessConfigurationData config; memset(&config, 0, sizeof(config)); - bool ok = gb.GetString(config.ssid, ARRAY_SIZE(config.ssid)); + bool ok = gb.GetQuotedString(config.ssid, ARRAY_SIZE(config.ssid)); if (ok) { - ok = gb.SeenAfterSpace('P') && gb.GetString(config.password, ARRAY_SIZE(config.password)); + ok = gb.SeenAfterSpace('P') && gb.GetQuotedString(config.password, ARRAY_SIZE(config.password)); } if (ok && gb.SeenAfterSpace('I')) { @@ -3319,10 +3235,10 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) changedMode = true; move.SetKinematics(KinematicsType::linearDelta); } - const bool changed = move.GetKinematics().SetOrReportParameters(code, gb, reply, error); + const bool changed = move.GetKinematics().Configure(code, gb, reply, error); if (changedMode) { - move.GetKinematics().GetAssumedInitialPosition(numAxes, positionNow); + move.GetKinematics().GetAssumedInitialPosition(numVisibleAxes, positionNow); } if (changed || changedMode) { @@ -3338,7 +3254,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) return false; } { - const bool changed = reprap.GetMove().GetKinematics().SetOrReportParameters(code, gb, reply, error); + const bool changed = reprap.GetMove().GetKinematics().Configure(code, gb, reply, error); if (changed) { SetAllAxesNotHomed(); @@ -3388,7 +3304,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) if (!changedToCartesian) // don't ask the kinematics to process M667 if we switched to Cartesian mode { - if (move.GetKinematics().SetOrReportParameters(667, gb, reply, error)) + if (move.GetKinematics().Configure(667, gb, reply, error)) { seen = true; } @@ -3399,7 +3315,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) // We changed something, so reset the positions and set all axes not homed if (move.GetKinematics().GetKinematicsType() != oldK) { - move.GetKinematics().GetAssumedInitialPosition(numAxes, positionNow); + move.GetKinematics().GetAssumedInitialPosition(numVisibleAxes, positionNow); } SetPositions(positionNow); SetAllAxesNotHomed(); @@ -3430,7 +3346,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) } seen = true; } - if (move.GetKinematics().SetOrReportParameters(code, gb, reply, error)) + if (move.GetKinematics().Configure(code, gb, reply, error)) { seen = true; } @@ -3440,7 +3356,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) // We changed something, so reset the positions and set all axes not homed if (move.GetKinematics().GetKinematicsType() != oldK) { - move.GetKinematics().GetAssumedInitialPosition(numAxes, positionNow); + move.GetKinematics().GetAssumedInitialPosition(numVisibleAxes, positionNow); } SetPositions(positionNow); SetAllAxesNotHomed(); @@ -3676,7 +3592,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) case 913: // Set/report motor current percent { bool seen = false; - for (size_t axis = 0; axis < numAxes; axis++) + for (size_t axis = 0; axis < numTotalAxes; axis++) { if (gb.Seen(axisLetters[axis])) { @@ -3702,7 +3618,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) // 2014-09-29 DC42: we no longer insist that the user supplies values for all possible extruder drives for (size_t e = 0; e < eCount; e++) { - platform.SetMotorCurrent(numAxes + e, eVals[e], code == 913); + platform.SetMotorCurrent(numTotalAxes + e, eVals[e], code == 913); } seen = true; } @@ -3720,14 +3636,14 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply) if (!seen) { reply.copy((code == 913) ? "Motor current % of normal - " : "Motor current (mA) - "); - for (size_t axis = 0; axis < numAxes; ++axis) + for (size_t axis = 0; axis < numTotalAxes; ++axis) { reply.catf("%c:%d, ", axisLetters[axis], (int)platform.GetMotorCurrent(axis, code == 913)); } reply.cat("E"); for (size_t extruder = 0; extruder < numExtruders; extruder++) { - reply.catf(":%d", (int)platform.GetMotorCurrent(extruder + numAxes, code == 913)); + reply.catf(":%d", (int)platform.GetMotorCurrent(extruder + numTotalAxes, code == 913)); } if (code == 906) { diff --git a/src/Heating/Heat.cpp b/src/Heating/Heat.cpp index ecd184d0..eb5b5ff9 100644 --- a/src/Heating/Heat.cpp +++ b/src/Heating/Heat.cpp @@ -19,14 +19,14 @@ Licence: GPL ****************************************************************************************************/ #include "Heat.h" - #include "Platform.h" #include "RepRap.h" +#include "Sensors/TemperatureSensor.h" Heat::Heat(Platform& p) : platform(p), active(false), coldExtrude(false), bedHeater(DefaultBedHeater), chamberHeater(DefaultChamberHeater), heaterBeingTuned(-1), lastHeaterTuned(-1) { - for (size_t heater = 0; heater < HEATERS; heater++) + for (size_t heater : ARRAY_INDICES(pids)) { pids[heater] = new PID(platform, heater); } @@ -35,11 +35,11 @@ Heat::Heat(Platform& p) // Reset all heater models to defaults. Called when running M502. void Heat::ResetHeaterModels() { - for (int heater = 0; heater < HEATERS; heater++) + for (size_t heater : ARRAY_INDICES(pids)) { if (pids[heater]->IsHeaterEnabled()) { - if (heater == DefaultBedHeater || heater == DefaultChamberHeater) + if ((int)heater == DefaultBedHeater || (int)heater == DefaultChamberHeater) { pids[heater]->SetModel(DefaultBedHeaterGain, DefaultBedHeaterTimeConstant, DefaultBedHeaterDeadTime, 1.0, false); } @@ -53,27 +53,44 @@ void Heat::ResetHeaterModels() void Heat::Init() { - for (int heater = 0; heater < HEATERS; heater++) + // Set up the real heaters and the corresponding PIDs + for (size_t heater : ARRAY_INDICES(pids)) { - if (heater == DefaultBedHeater || heater == DefaultChamberHeater) + heaterSensors[heater] = nullptr; // no temperature sensor assigned yet + if ((int)heater == DefaultBedHeater || (int)heater == DefaultChamberHeater) { - pids[heater]->Init(DefaultBedHeaterGain, DefaultBedHeaterTimeConstant, DefaultBedHeaterDeadTime, - DefaultBedTemperatureLimit, false); + pids[heater]->Init(DefaultBedHeaterGain, DefaultBedHeaterTimeConstant, DefaultBedHeaterDeadTime, DefaultBedTemperatureLimit, false); } #if !defined(DUET_NG) && !defined(__RADDS__) && !defined(__ALLIGATOR__) - else if (heater == HEATERS - 1) + else if (heater == Heaters - 1) { - // Heater 6 pin is shared with fan 1. By default we support fan 1, so disable heater 6. + // On the Duet 085, the heater 6 pin is also the fan 1 pin. By default we support fan 1, so disable heater 6. pids[heater]->Init(-1.0, -1.0, -1.0, DefaultExtruderTemperatureLimit, true); } #endif else { - pids[heater]->Init(DefaultHotEndHeaterGain, DefaultHotEndHeaterTimeConstant, DefaultHotEndHeaterDeadTime, - DefaultExtruderTemperatureLimit, true); + pids[heater]->Init(DefaultHotEndHeaterGain, DefaultHotEndHeaterTimeConstant, DefaultHotEndHeaterDeadTime, DefaultExtruderTemperatureLimit, true); } } + // Set up the virtual heaters + // Clear the user-defined virtual heaters + for (TemperatureSensor* &v : virtualHeaterSensors) + { + v = nullptr; + } + + // Set up default virtual heaters for MCU temperature and TMC driver overheat sensors +#ifndef __RADDS + virtualHeaterSensors[0] = TemperatureSensor::Create(CpuTemperatureSenseChannel); + virtualHeaterSensors[0]->SetHeaterName("MCU"); // name this virtual heater so that it appears in DWC +#endif +#ifdef DUET_NG + virtualHeaterSensors[1] = TemperatureSensor::Create(FirstTmcDriversSenseChannel); + virtualHeaterSensors[2] = TemperatureSensor::Create(FirstTmcDriversSenseChannel + 1); +#endif + lastTime = millis() - platform.HeatSampleInterval(); // flag the PIDS as due for spinning longWait = platform.Time(); coldExtrude = false; @@ -82,9 +99,9 @@ void Heat::Init() void Heat::Exit() { - for (size_t heater = 0; heater < HEATERS; heater++) + for (PID *pid : pids) { - pids[heater]->SwitchOff(); + pid->SwitchOff(); } platform.Message(HOST_MESSAGE, "Heat class exited.\n"); active = false; @@ -99,7 +116,7 @@ void Heat::Spin() if (now - lastTime >= platform.HeatSampleInterval()) { lastTime = now; - for (size_t heater=0; heater < HEATERS; heater++) + for (size_t heater=0; heater < Heaters; heater++) { pids[heater]->Spin(); } @@ -118,7 +135,7 @@ void Heat::Spin() void Heat::Diagnostics(MessageType mtype) { platform.MessageF(mtype, "=== Heat ===\nBed heater = %d, chamber heater = %d\n", bedHeater, chamberHeater); - for (size_t heater=0; heater < HEATERS; heater++) + for (size_t heater : ARRAY_INDICES(pids)) { if (pids[heater]->Active()) { @@ -129,9 +146,9 @@ void Heat::Diagnostics(MessageType mtype) bool Heat::AllHeatersAtSetTemperatures(bool includingBed) const { - for(int8_t heater = 0; heater < HEATERS; heater++) + for (size_t heater : ARRAY_INDICES(pids)) { - if (!HeaterAtSetTemperature(heater, true) && (includingBed || heater != bedHeater)) + if (!HeaterAtSetTemperature(heater, true) && (includingBed || (int)heater != bedHeater)) { return false; } @@ -143,7 +160,7 @@ bool Heat::AllHeatersAtSetTemperatures(bool includingBed) const bool Heat::HeaterAtSetTemperature(int8_t heater, bool waitWhenCooling) const { // If it hasn't anything to do, it must be right wherever it is... - if (heater < 0 || heater >= HEATERS || pids[heater]->SwitchedOff() || pids[heater]->FaultOccurred()) + if (heater < 0 || heater >= (int)Heaters || pids[heater]->SwitchedOff() || pids[heater]->FaultOccurred()) { return true; } @@ -157,7 +174,7 @@ bool Heat::HeaterAtSetTemperature(int8_t heater, bool waitWhenCooling) const Heat::HeaterStatus Heat::GetStatus(int8_t heater) const { - if (heater < 0 || heater >= HEATERS) + if (heater < 0 || heater >= (int)Heaters) { return HS_off; } @@ -171,7 +188,7 @@ Heat::HeaterStatus Heat::GetStatus(int8_t heater) const void Heat::SetActiveTemperature(int8_t heater, float t) { - if (heater >= 0 && heater < HEATERS) + if (heater >= 0 && heater < (int)Heaters) { pids[heater]->SetActiveTemperature(t); } @@ -179,12 +196,12 @@ void Heat::SetActiveTemperature(int8_t heater, float t) float Heat::GetActiveTemperature(int8_t heater) const { - return (heater >= 0 && heater < HEATERS) ? pids[heater]->GetActiveTemperature() : ABS_ZERO; + return (heater >= 0 && heater < (int)Heaters) ? pids[heater]->GetActiveTemperature() : ABS_ZERO; } void Heat::SetStandbyTemperature(int8_t heater, float t) { - if (heater >= 0 && heater < HEATERS) + if (heater >= 0 && heater < (int)Heaters) { pids[heater]->SetStandbyTemperature(t); } @@ -192,12 +209,12 @@ void Heat::SetStandbyTemperature(int8_t heater, float t) float Heat::GetStandbyTemperature(int8_t heater) const { - return (heater >= 0 && heater < HEATERS) ? pids[heater]->GetStandbyTemperature() : ABS_ZERO; + return (heater >= 0 && heater < (int)Heaters) ? pids[heater]->GetStandbyTemperature() : ABS_ZERO; } void Heat::SetTemperatureLimit(int8_t heater, float t) { - if (heater >= 0 && heater < HEATERS) + if (heater >= 0 && heater < (int)Heaters) { pids[heater]->SetTemperatureLimit(t); } @@ -205,17 +222,17 @@ void Heat::SetTemperatureLimit(int8_t heater, float t) float Heat::GetTemperatureLimit(int8_t heater) const { - return (heater >= 0 && heater < HEATERS) ? pids[heater]->GetTemperatureLimit() : ABS_ZERO; + return (heater >= 0 && heater < (int)Heaters) ? pids[heater]->GetTemperatureLimit() : ABS_ZERO; } float Heat::GetTemperature(int8_t heater) const { - return (heater >= 0 && heater < HEATERS) ? pids[heater]->GetTemperature() : ABS_ZERO; + return (heater >= 0 && heater < (int)Heaters) ? pids[heater]->GetTemperature() : ABS_ZERO; } void Heat::Activate(int8_t heater) { - if (heater >= 0 && heater < HEATERS) + if (heater >= 0 && heater < (int)Heaters) { pids[heater]->Activate(); } @@ -223,7 +240,7 @@ void Heat::Activate(int8_t heater) void Heat::SwitchOff(int8_t heater) { - if (heater >= 0 && heater < HEATERS) + if (heater >= 0 && heater < (int)Heaters) { pids[heater]->SwitchOff(); } @@ -231,7 +248,7 @@ void Heat::SwitchOff(int8_t heater) void Heat::SwitchOffAll() { - for (size_t heater = 0; heater < HEATERS; ++heater) + for (size_t heater = 0; heater < Heaters; ++heater) { pids[heater]->SwitchOff(); } @@ -239,7 +256,7 @@ void Heat::SwitchOffAll() void Heat::Standby(int8_t heater) { - if (heater >= 0 && heater < HEATERS) + if (heater >= 0 && heater < (int)Heaters) { pids[heater]->Standby(); } @@ -247,7 +264,7 @@ void Heat::Standby(int8_t heater) void Heat::ResetFault(int8_t heater) { - if (heater >= 0 && heater < HEATERS) + if (heater >= 0 && heater < (int)Heaters) { pids[heater]->ResetFault(); } @@ -305,7 +322,7 @@ void Heat::GetAutoTuneStatus(StringRef& reply) const float Heat::GetHighestTemperatureLimit() const { float limit = ABS_ZERO; - for (size_t h = 0; h < HEATERS; ++h) + for (size_t h : ARRAY_INDICES(pids)) { if (h < reprap.GetToolHeatersInUse() || (int)h == bedHeater || (int)h == chamberHeater) { @@ -329,7 +346,7 @@ void Heat::SetM301PidParameters(size_t heater, const M301PidParameters& params) bool Heat::WriteModelParameters(FileStore *f) const { bool ok = f->Write("; Heater model parameters\n"); - for (size_t h = 0; ok && h < HEATERS; ++h) + for (size_t h : ARRAY_INDICES(pids)) { const FopDt& model = pids[h]->GetModel(); if (model.IsEnabled()) @@ -340,4 +357,105 @@ bool Heat::WriteModelParameters(FileStore *f) const return ok; } +// Return the channel used by a particular heater, or -1 if not configured +int Heat::GetHeaterChannel(size_t heater) const +{ + const TemperatureSensor * const * const spp = GetSensor(heater); + return (spp != nullptr && *spp != nullptr) ? (*spp)->GetSensorChannel() : -1; +} + +// Set the channel used by a heater, returning true if bad heater or channel number +bool Heat::SetHeaterChannel(size_t heater, int channel) +{ + TemperatureSensor ** const spp = GetSensor(heater); + if (spp == nullptr) + { + return true; // bad heater number + } + + TemperatureSensor *sp = TemperatureSensor::Create(channel); + if (sp == nullptr) + { + return true; // bad channel number + } + + delete *spp; // release the old sensor object, if any + *spp = sp; + return false; +} + +// Configure the temperature sensor for a channel +bool Heat::ConfigureHeaterSensor(unsigned int mcode, size_t heater, GCodeBuffer& gb, StringRef& reply, bool& error) +{ + TemperatureSensor ** const spp = GetSensor(heater); + if (spp == nullptr || *spp == nullptr) + { + reply.printf("heater %d is not configured", heater); + error = true; + return false; + } + + return (*spp)->Configure(mcode, heater, gb, reply, error); +} + +// Get a pointer to the temperature sensor entry, or nullptr if the heater number is bad +TemperatureSensor **Heat::GetSensor(size_t heater) +{ + if (heater < Heaters) + { + return &heaterSensors[heater]; + } + if (heater >= FirstVirtualHeater && heater < FirstVirtualHeater + ARRAY_SIZE(virtualHeaterSensors)) + { + return &virtualHeaterSensors[heater - FirstVirtualHeater]; + } + return nullptr; +} + +// Get a pointer to the temperature sensor entry, or nullptr if the heater number is bad (const version of above) +TemperatureSensor * const *Heat::GetSensor(size_t heater) const +{ + if (heater < Heaters) + { + return &heaterSensors[heater]; + } + if (heater >= FirstVirtualHeater && heater < FirstVirtualHeater + ARRAY_SIZE(virtualHeaterSensors)) + { + return &virtualHeaterSensors[heater - FirstVirtualHeater]; + } + return nullptr; +} + +// Get the name of a heater, or nullptr if it hasn't been named +const char *Heat::GetHeaterName(size_t heater) const +{ + const TemperatureSensor * const * const spp = GetSensor(heater); + return (spp == nullptr || *spp == nullptr) ? nullptr : (*spp)->GetHeaterName(); +} + +// Get the temperature of a real or virtual heater +float Heat::GetTemperature(size_t heater, TemperatureError& err) +{ + TemperatureSensor ** const spp = GetSensor(heater); + if (spp == nullptr) + { + err = TemperatureError::unknownHeater; + return BAD_ERROR_TEMPERATURE; + } + + if (*spp == nullptr) + { + err = TemperatureError::unknownChannel; + return BAD_ERROR_TEMPERATURE; + } + + float t; + err = (*spp)->GetTemperature(t); + if (err != TemperatureError::success) + { + t = BAD_ERROR_TEMPERATURE; + } + return t; +} + // End diff --git a/src/Heating/Heat.h b/src/Heating/Heat.h index 2c487344..3ebb5c6d 100644 --- a/src/Heating/Heat.h +++ b/src/Heating/Heat.h @@ -29,6 +29,9 @@ Licence: GPL #include "Pid.h" #include "MessageType.h" +class TemperatureSensor; +class GCodeBuffer; + class Heat { public: @@ -45,16 +48,16 @@ public: void AllowColdExtrude(bool b); // Allow or deny cold extrusion int8_t GetBedHeater() const // Get hot bed heater number - post(-1 <= result; result < HEATERS); + post(-1 <= result; result < Heaters); void SetBedHeater(int8_t heater) // Set hot bed heater number - pre(-1 <= heater; heater < HEATERS); + pre(-1 <= heater; heater < Heaters); int8_t GetChamberHeater() const // Get chamber heater number - post(-1 <= result; result < HEATERS); + post(-1 <= result; result < Heaters); void SetChamberHeater(int8_t heater) // Set chamber heater number - pre(-1 <= heater; heater < HEATERS); + pre(-1 <= heater; heater < Heaters); void SetActiveTemperature(int8_t heater, float t); float GetActiveTemperature(int8_t heater) const; @@ -74,48 +77,60 @@ public: void Diagnostics(MessageType mtype); // Output useful information float GetAveragePWM(size_t heater) const // Return the running average PWM to the heater as a fraction in [0, 1]. - pre(heater < HEATERS); + pre(heater < Heaters); bool UseSlowPwm(int8_t heater) const; // Queried by the Platform class uint32_t GetLastSampleTime(size_t heater) const - pre(heater < HEATERS); + pre(heater < Heaters); void StartAutoTune(size_t heater, float temperature, float maxPwm, StringRef& reply) // Auto tune a PID - pre(heater < HEATERS); + pre(heater < Heaters); bool IsTuning(size_t heater) const // Return true if the specified heater is auto tuning - pre(heater < HEATERS); + pre(heater < Heaters); void GetAutoTuneStatus(StringRef& reply) const; // Get the status of the current or last auto tune const FopDt& GetHeaterModel(size_t heater) const // Get the process model for the specified heater - pre(heater < HEATERS); + pre(heater < Heaters); bool SetHeaterModel(size_t heater, float gain, float tc, float td, float maxPwm, bool usePid) // Set the heater process model - pre(heater < HEATERS); + pre(heater < Heaters); void GetHeaterProtection(size_t heater, float& maxTempExcursion, float& maxFaultTime) const - pre(heater < HEATERS); + pre(heater < Heaters); void SetHeaterProtection(size_t heater, float maxTempExcursion, float maxFaultTime) - pre(heater < HEATERS); + pre(heater < Heaters); bool IsHeaterEnabled(size_t heater) const // Is this heater enabled? - pre(heater < HEATERS); + pre(heater < Heaters); float GetHighestTemperatureLimit() const; // Get the highest temperature limit of any heater void SetM301PidParameters(size_t heater, const M301PidParameters& params) - pre(heater < HEATERS); + pre(heater < Heaters); bool WriteModelParameters(FileStore *f) const; // Write heater model parameters to file returning true if no error + int GetHeaterChannel(size_t heater) const; // Return the channel used by a particular heater, or -1 if not configured + bool SetHeaterChannel(size_t heater, int channel); // Set the channel used by a heater, returning true if bad heater or channel number + bool ConfigureHeaterSensor(size_t heater, unsigned int mcode, GCodeBuffer& gb, StringRef& reply, bool& error); // Configure the temperature sensor for a channel + const char *GetHeaterName(size_t heater) const; // Get the name of a heater, or nullptr if it hasn't been named + + float GetTemperature(size_t heater, TemperatureError& err); // Result is in degrees Celsius + private: - Heat(const Heat&); // private copy constructor to prevent copying + Heat(const Heat&); // Private copy constructor to prevent copying + TemperatureSensor **GetSensor(size_t heater); // Get a pointer to the temperature sensor entry + TemperatureSensor * const *GetSensor(size_t heater) const; // Get a pointer to the temperature sensor entry Platform& platform; // The instance of the RepRap hardware class - PID* pids[HEATERS]; // A PID controller for each heater + + PID* pids[Heaters]; // A PID controller for each heater + TemperatureSensor *heaterSensors[Heaters]; // The sensor used by the real heaters + TemperatureSensor *virtualHeaterSensors[MaxVirtualHeaters]; // Sensors for virtual heaters uint32_t lastTime; // The last time our Spin() was called float longWait; // Long time for things that happen occasionally diff --git a/src/Heating/Pid.cpp b/src/Heating/Pid.cpp index 88ca87ec..145ff014 100644 --- a/src/Heating/Pid.cpp +++ b/src/Heating/Pid.cpp @@ -83,7 +83,7 @@ bool PID::SetModel(float gain, float tc, float td, float maxPwm, bool usePid) if (rslt) { #if !defined(DUET_NG) && !defined(__RADDS__) && !defined(__ALLIGATOR__) - if (heater == HEATERS - 1) + if (heater == Heaters - 1) { // The last heater on the Duet 0.8.5 + DueX4 shares its pin with Fan1 platform.EnableSharedFan(!model.IsEnabled()); @@ -112,17 +112,10 @@ bool PID::SetModel(float gain, float tc, float td, float maxPwm, bool usePid) TemperatureError PID::ReadTemperature() { TemperatureError err = TemperatureError::success; // assume no error - temperature = platform.GetTemperature(heater, err); // in the event of an error, err is set and BAD_ERROR_TEMPERATURE is returned - if (err == TemperatureError::success) + temperature = reprap.GetHeat().GetTemperature(heater, err); // in the event of an error, err is set and BAD_ERROR_TEMPERATURE is returned + if (err == TemperatureError::success && temperature > temperatureLimit) { - if (temperature < BAD_LOW_TEMPERATURE) - { - err = TemperatureError::openCircuit; - } - else if (temperature > temperatureLimit) - { - err = TemperatureError::tooHigh; - } + err = TemperatureError::tooHigh; } return err; } diff --git a/src/Heating/Sensors/CpuTemperatureSensor.cpp b/src/Heating/Sensors/CpuTemperatureSensor.cpp new file mode 100644 index 00000000..85ff00ba --- /dev/null +++ b/src/Heating/Sensors/CpuTemperatureSensor.cpp @@ -0,0 +1,31 @@ +/* + * CpuTemperatureSensor.cpp + * + * Created on: 8 Jun 2017 + * Author: David + */ + +#include "CpuTemperatureSensor.h" +#include "Platform.h" +#include "RepRap.h" + +#ifndef __RADDS__ + +CpuTemperatureSensor::CpuTemperatureSensor(unsigned int channel) : TemperatureSensor(channel, "microcontroller embedded temperature sensor") +{ +} + +void CpuTemperatureSensor::Init() +{ +} + +TemperatureError CpuTemperatureSensor::GetTemperature(float& t) +{ + float minT, maxT; + reprap.GetPlatform().GetMcuTemperatures(minT, t, maxT); + return TemperatureError::success; +} + +#endif + +// End diff --git a/src/Heating/Sensors/CpuTemperatureSensor.h b/src/Heating/Sensors/CpuTemperatureSensor.h new file mode 100644 index 00000000..7e23ac77 --- /dev/null +++ b/src/Heating/Sensors/CpuTemperatureSensor.h @@ -0,0 +1,25 @@ +/* + * CpuTemperatureSensor.h + * + * Created on: 8 Jun 2017 + * Author: David + */ + +#ifndef SRC_HEATING_SENSORS_CPUTEMPERATURESENSOR_H_ +#define SRC_HEATING_SENSORS_CPUTEMPERATURESENSOR_H_ + +#include "TemperatureSensor.h" + +#ifndef __RADDS__ + +class CpuTemperatureSensor : public TemperatureSensor +{ +public: + CpuTemperatureSensor(unsigned int channel); + void Init() override; + TemperatureError GetTemperature(float& t) override; +}; + +#endif + +#endif /* SRC_HEATING_SENSORS_CPUTEMPERATURESENSOR_H_ */ diff --git a/src/Heating/Sensors/CurrentLoopTemperatureSensor.cpp b/src/Heating/Sensors/CurrentLoopTemperatureSensor.cpp new file mode 100644 index 00000000..388fdbc8 --- /dev/null +++ b/src/Heating/Sensors/CurrentLoopTemperatureSensor.cpp @@ -0,0 +1,123 @@ +/* + * LinearAdcTemperatureSensor.cpp + * + * Created on: 8 Jun 2017 + * Author: David + */ + +#include <Heating/Sensors/CurrentLoopTemperatureSensor.h> +#include "RepRap.h" +#include "Platform.h" +#include "GCodes/GCodeBuffer.h" + +const uint32_t MCP3204_Frequency = 1000000; // maximum for MCP3204 is 1MHz @ 2.7V, will be slightly higher at 3.3V + +// The MCP3204 samples input data on the rising edge and changes the output data on the rising edge. +const uint8_t MCP3204_SpiMode = SPI_MODE_0; + +// Define the minimum interval between readings +const uint32_t MinimumReadInterval = 100; // minimum interval between reads, in milliseconds + +CurrentLoopTemperatureSensor::CurrentLoopTemperatureSensor(unsigned int channel) + : SpiTemperatureSensor(channel, "Current Loop", channel - FirstLinearAdcChannel, MCP3204_SpiMode, MCP3204_Frequency), + tempAt4mA(DefaultTempAt4mA), tempAt20mA(DefaultTempAt20mA) +{ + CalcDerivedParameters(); +} + +// Initialise the linear ADC +void CurrentLoopTemperatureSensor::Init() +{ + InitSpi(); + + for (unsigned int i = 0; i < 3; ++i) // try 3 times + { + TryGetLinearAdcTemperature(); + if (lastResult == TemperatureError::success) + { + break; + } + delay(MinimumReadInterval); + } + + lastReadingTime = millis(); + + if (lastResult != TemperatureError::success) + { + reprap.GetPlatform().MessageF(GENERIC_MESSAGE, "Error: failed to initialise daughter board ADC: %s\n", TemperatureErrorString(lastResult)); + } +} + +// Configure this temperature sensor +bool CurrentLoopTemperatureSensor::Configure(unsigned int mCode, unsigned int heater, GCodeBuffer& gb, StringRef& reply, bool& error) +{ + if (mCode == 305) + { + bool seen = false; + gb.TryGetFValue('L', tempAt4mA, seen); + gb.TryGetFValue('H', tempAt20mA, seen); + TryConfigureHeaterName(gb, seen); + + if (seen) + { + CalcDerivedParameters(); + } + else if (!gb.Seen('X')) + { + CopyBasicHeaterDetails(heater, reply); + reply.catf(", temperature range %.1f to %.1fC", tempAt4mA, tempAt20mA); + } + } + return false; +} + +TemperatureError CurrentLoopTemperatureSensor::GetTemperature(float& t) +{ + if (!inInterrupt() && millis() - lastReadingTime >= MinimumReadInterval) + { + TryGetLinearAdcTemperature(); + } + + t = lastTemperature; + return lastResult; +} + +void CurrentLoopTemperatureSensor::CalcDerivedParameters() +{ + minLinearAdcTemp = tempAt4mA - 0.25 * (tempAt20mA - tempAt4mA); + linearAdcDegCPerCount = (tempAt20mA - minLinearAdcTemp) / 4096.0; +} + +// Try to get a temperature reading from the linear ADC by doing an SPI transaction +void CurrentLoopTemperatureSensor::TryGetLinearAdcTemperature() +{ + // The MCP3204 waits for a high input input bit before it does anything. Call this clock 1. + // The next input bit it high for single-ended operation, low for differential. This is clock 2. + // The next 3 input bits are the channel selection bits. These are clocks 3..5. + // Clock 6 produces a null bit on its trailing edge, which is read by the processor on clock 7. + // Clocks 7..18 produce data bits B11..B0 on their trailing edges, which are read by the MCU on the leading edges of clocks 8-19. + // If we supply further clocks, then clocks 18..29 are the same data but LSB first, omitting bit 0. + // Clocks 30 onwards will be zeros. + // So we need to use at least 19 clocks. We round this up to 24 clocks, and we check that the extra 5 bits we receive are the 5 least significant data bits in reverse order. + + static const uint8_t adcData[] = { 0xC0, 0x00, 0x00 }; // start bit, single ended, channel 0 + uint32_t rawVal; + lastResult = DoSpiTransaction(adcData, 3, rawVal); + //debugPrintf("ADC data %u\n", rawVal); + + if (lastResult == TemperatureError::success) + { + const uint32_t adcVal1 = (rawVal >> 5) & ((1 << 13) - 1); + const uint32_t adcVal2 = ((rawVal & 1) << 5) | ((rawVal & 2) << 3) | ((rawVal & 4) << 1) | ((rawVal & 8) >> 1) | ((rawVal & 16) >> 3) | ((rawVal & 32) >> 5); + if (adcVal1 >= 4096 || adcVal2 != (adcVal1 & ((1 << 6) - 1))) + { + lastResult = TemperatureError::badResponse; + } + else + { + lastTemperature = minLinearAdcTemp + (linearAdcDegCPerCount * (float)adcVal1); + } + } +} + +// End diff --git a/src/Heating/Sensors/CurrentLoopTemperatureSensor.h b/src/Heating/Sensors/CurrentLoopTemperatureSensor.h new file mode 100644 index 00000000..92815f2e --- /dev/null +++ b/src/Heating/Sensors/CurrentLoopTemperatureSensor.h @@ -0,0 +1,35 @@ +/* + * LinearAdcTemperatureSensor.h + * + * Created on: 8 Jun 2017 + * Author: David + */ + +#ifndef SRC_HEATING_LINEARADCTEMPERATURESENSOR_H_ +#define SRC_HEATING_LINEARADCTEMPERATURESENSOR_H_ + +#include "SpiTemperatureSensor.h" + +class CurrentLoopTemperatureSensor : public SpiTemperatureSensor +{ +public: + CurrentLoopTemperatureSensor(unsigned int channel); + bool Configure(unsigned int mCode, unsigned int heater, GCodeBuffer& gb, StringRef& reply, bool& error) override; + void Init() override; + TemperatureError GetTemperature(float& t) override; + +private: + void TryGetLinearAdcTemperature(); + void CalcDerivedParameters(); + + // Configurable parameters + float tempAt4mA, tempAt20mA; + + // Derived parameters + float minLinearAdcTemp, linearAdcDegCPerCount; + + static constexpr float DefaultTempAt4mA = 385.0; + static constexpr float DefaultTempAt20mA = 1600.0; +}; + +#endif /* SRC_HEATING_LINEARADCTEMPERATURESENSOR_H_ */ diff --git a/src/Heating/Sensors/RtdSensor31865.cpp b/src/Heating/Sensors/RtdSensor31865.cpp new file mode 100644 index 00000000..35c4d2f7 --- /dev/null +++ b/src/Heating/Sensors/RtdSensor31865.cpp @@ -0,0 +1,207 @@ +/* + * RtdSensor31865.cpp + * + * Created on: 8 Jun 2017 + * Author: David + */ + +#include "RtdSensor31865.h" +#include "RepRap.h" +#include "Platform.h" +#include "Core.h" + +const uint32_t MAX31865_Frequency = 4000000; // maximum for MAX31865 is also 5MHz + +// SPI modes: +// If the inactive state of SCL is LOW (CPOL = 0) (in the case of the MAX31865, this is sampled on the falling edge of CS): +// The MAX31865 changes data after the rising edge of CLK, and samples input data on the falling edge. +// This requires NCPHA = 0. +const uint8_t MAX31865_SpiMode = SPI_MODE_1; + +// Define the minimum interval between readings. The MAX31865 needs 62.5ms in 50Hz filter mode. +const uint32_t MinimumReadInterval = 100; // minimum interval between reads, in milliseconds + +// Table of temperature vs. MAX31865 result for PT100 thermistor, from the MAX31865 datasheet +struct TempTableEntry +{ + int16_t temperature; + uint16_t adcReading; +}; + +static const TempTableEntry tempTable[] = +{ + {-30, 7227}, + {-20, 7550}, + {-10, 7871}, + {0, 8192}, + {10, 8512}, + {20, 8830}, + {30, 9148}, + {40, 9465}, + {50, 9781}, + {60, 10096}, + {70, 10410}, + {80, 10723}, + {90, 11035}, + {100, 11346}, + {110, 11657}, + {120, 11966}, + {130, 12274}, + {140, 12582}, + {150, 12888}, + {160, 13194}, + {170, 13498}, + {180, 13802}, + {190, 14104}, + {200, 14406}, + {225, 15156}, + {250, 15901}, + {275, 16639}, + {300, 17371}, + {325, 18098}, + {350, 18818}, + {375, 19533}, + {400, 20242}, + {425, 20945}, + {450, 21642}, + {475, 22333}, + {500, 23018}, + {525, 23697}, + {550, 24370} +}; + +const size_t NumTempTableEntries = sizeof(tempTable)/sizeof(tempTable[0]); + +RtdSensor31865::RtdSensor31865(unsigned int channel) + : SpiTemperatureSensor(channel, "PT100 (MAX31865)", channel - FirstRtdChannel, MAX31865_SpiMode, MAX31865_Frequency) +{ +} + +// Perform the actual hardware initialization for attaching and using this device on the SPI hardware bus. +void RtdSensor31865::Init() +{ + InitSpi(); + + TemperatureError rslt; + for (unsigned int i = 0; i < 3; ++i) // try 3 times + { + rslt = TryInitRtd(); + if (rslt == TemperatureError::success) + { + break; + } + delay(MinimumReadInterval); + } + + lastReadingTime = millis(); + lastResult = rslt; + lastTemperature = 0.0; + + if (rslt != TemperatureError::success) + { + reprap.GetPlatform().MessageF(GENERIC_MESSAGE, "Error: failed to initialise RTD: %s\n", TemperatureErrorString(rslt)); + } +} + +// Try to initialise the RTD +TemperatureError RtdSensor31865::TryInitRtd() const +{ + // Note that to get the MAX31865 to do continuous conversions, we need to set the bias bit as well as the continuous-conversion bit + static const uint8_t modeData[2] = { 0x80, 0xC3 }; // write register 0, bias on, auto conversion, clear errors, 50Hz + uint32_t rawVal; + TemperatureError sts = DoSpiTransaction(modeData, 2, rawVal); + + if (sts == TemperatureError::success) + { + static const uint8_t readData[2] = { 0x00, 0x00 }; // read register 0 + sts = DoSpiTransaction(readData, 2, rawVal); + } + + //debugPrintf("Status %d data %04x\n", (int)sts, rawVal); + return (sts == TemperatureError::success && (uint8_t)rawVal != 0xC1) + ? TemperatureError::badResponse + : sts; +} + +TemperatureError RtdSensor31865::GetTemperature(float& t) +{ + if (inInterrupt() || millis() - lastReadingTime < MinimumReadInterval) + { + t = lastTemperature; + } + else + { + static const uint8_t dataOut[4] = {0, 55, 55, 55}; // read registers 0 (control), 1 (MSB) and 2 (LSB) + uint32_t rawVal; + TemperatureError sts = DoSpiTransaction(dataOut, 4, rawVal); + + if (sts != TemperatureError::success) + { + lastResult = sts; + } + else + { + lastReadingTime = millis(); + if (((rawVal & 0x00C10000) != 0xC10000) +#if 0 + // We no longer check the error status bit, because it seems to be impossible to clear it once it has been set. + // Perhaps we would need to exit continuous reading mode to do so, and then re-enable it afterwards. But this would + // take to long. +#else + || (rawVal & 1) != 0 +#endif + ) + { + // Either the continuous conversion bit has got cleared, or the fault bit has been set + TryInitRtd(); + lastResult = TemperatureError::hardwareError; + } + else + { + uint16_t adcVal = (rawVal >> 1) & 0x7FFF; + + // Formally-verified binary search routine, adapted from one of the eCv examples + size_t low = 0u, high = NumTempTableEntries; + while (high > low) + keep(low <= high; high <= NumTempTableEntries) + keep(low == 0u || tempTable[low - 1u].adcReading < adcVal) + keep(high == NumTempTableEntries || adcVal <= tempTable[high].adcReading) + decrease(high - low) + { + size_t mid = (high - low)/2u + low; // get the mid point, avoiding arithmetic overflow + if (adcVal <= tempTable[mid].adcReading) + { + high = mid; + } + else + { + low = mid + 1u; + } + } + assert(low <= NumTempTableEntries); + assert(low == 0 || tempTable[low - 1] < adcVal); + assert(low == NumTempTableEntries || adcVal <= tempTable[low]); + + if (low == 0) // if off the bottom of the table + { + lastResult = TemperatureError::shortCircuit; + } + else if (low >= NumTempTableEntries) // if off the top of the table + { + lastResult = TemperatureError::openCircuit; + } + else + { + const float interpolationFraction = (float)(adcVal - tempTable[low - 1].adcReading)/(float)(tempTable[low].adcReading - tempTable[low - 1].adcReading); + t = lastTemperature = ((float)(tempTable[low].temperature - tempTable[low - 1].temperature) * interpolationFraction) + + (float)tempTable[low - 1].temperature; + //debugPrintf("raw %u low %u interp %f temp %f\n", adcVal, low, interpolationFraction, *t); + lastResult = TemperatureError::success; + } + } + } + } + return lastResult; +} + +// End diff --git a/src/Heating/Sensors/RtdSensor31865.h b/src/Heating/Sensors/RtdSensor31865.h new file mode 100644 index 00000000..0ff0a110 --- /dev/null +++ b/src/Heating/Sensors/RtdSensor31865.h @@ -0,0 +1,24 @@ +/* + * RtdSensor31865.h + * + * Created on: 8 Jun 2017 + * Author: David + */ + +#ifndef SRC_HEATING_RTDSENSOR31865_H_ +#define SRC_HEATING_RTDSENSOR31865_H_ + +#include "SpiTemperatureSensor.h" + +class RtdSensor31865 : public SpiTemperatureSensor +{ +public: + RtdSensor31865(unsigned int channel); + void Init() override; + TemperatureError GetTemperature(float& t) override; + +private: + TemperatureError TryInitRtd() const; +}; + +#endif /* SRC_HEATING_RTDSENSOR31865_H_ */ diff --git a/src/Heating/Sensors/SpiTemperatureSensor.cpp b/src/Heating/Sensors/SpiTemperatureSensor.cpp new file mode 100644 index 00000000..dbf6c5b7 --- /dev/null +++ b/src/Heating/Sensors/SpiTemperatureSensor.cpp @@ -0,0 +1,63 @@ +/* + * SpiTemperatureSensor.cpp + * + * Created on: 8 Jun 2017 + * Author: David + */ + +#include "SpiTemperatureSensor.h" + +SpiTemperatureSensor::SpiTemperatureSensor(unsigned int channel, const char *name, unsigned int relativeChannel, uint8_t spiMode, uint32_t clockFrequency) + : TemperatureSensor(channel, name) +{ + device.csPin = SpiTempSensorCsPins[relativeChannel]; + device.spiMode = spiMode; + device.clockFrequency = clockFrequency; + lastTemperature = 0.0; + lastResult = TemperatureError::notInitialised; +} + +void SpiTemperatureSensor::InitSpi() +{ + sspi_master_init(&device, 8); + lastReadingTime = millis(); +} + +// Send and receive 1 to 4 bytes of data and return the result as a single 32-bit word +TemperatureError SpiTemperatureSensor::DoSpiTransaction(const uint8_t dataOut[], size_t nbytes, uint32_t& rslt) const +{ + if (!sspi_acquire()) + { + return TemperatureError::busBusy; + } + + sspi_master_setup_device(&device); + delayMicroseconds(1); + sspi_select_device(&device); + delayMicroseconds(1); + + uint8_t rawBytes[4]; + spi_status_t sts = sspi_transceive_packet(dataOut, rawBytes, nbytes); + + delayMicroseconds(1); + sspi_deselect_device(&device); + delayMicroseconds(1); + + sspi_release(); + + if (sts != SPI_OK) + { + return TemperatureError::timeout; + } + + rslt = rawBytes[0]; + for (size_t i = 1; i < nbytes; ++i) + { + rslt <<= 8; + rslt |= rawBytes[i]; + } + + return TemperatureError::success; +} + +// End diff --git a/src/Heating/Sensors/SpiTemperatureSensor.h b/src/Heating/Sensors/SpiTemperatureSensor.h new file mode 100644 index 00000000..81399cbf --- /dev/null +++ b/src/Heating/Sensors/SpiTemperatureSensor.h @@ -0,0 +1,27 @@ +/* + * SpiTemperatureSensor.h + * + * Created on: 8 Jun 2017 + * Author: David + */ + +#ifndef SRC_HEATING_SPITEMPERATURESENSOR_H_ +#define SRC_HEATING_SPITEMPERATURESENSOR_H_ + +#include "TemperatureSensor.h" +#include "SharedSpi.h" // for sspi_device + +class SpiTemperatureSensor : public TemperatureSensor +{ +protected: + SpiTemperatureSensor(unsigned int channel, const char *name, unsigned int relativeChannel, uint8_t spiMode, uint32_t clockFrequency); + void InitSpi(); + TemperatureError DoSpiTransaction(const uint8_t dataOut[], size_t nbytes, uint32_t& rslt) const; + + sspi_device device; + uint32_t lastReadingTime; + float lastTemperature; + TemperatureError lastResult; +}; + +#endif /* SRC_HEATING_SPITEMPERATURESENSOR_H_ */ diff --git a/src/Heating/Sensors/TemperatureSensor.cpp b/src/Heating/Sensors/TemperatureSensor.cpp new file mode 100644 index 00000000..9fa8637e --- /dev/null +++ b/src/Heating/Sensors/TemperatureSensor.cpp @@ -0,0 +1,120 @@ +#include <Heating/Sensors/CurrentLoopTemperatureSensor.h> +#include "TemperatureSensor.h" +#include "Thermistor.h" +#include "ThermocoupleSensor31855.h" +#include "RtdSensor31865.h" +#include "GCodes/GCodeBuffer.h" + +#ifndef __RADDS__ +#include "CpuTemperatureSensor.h" +#endif + +#ifdef DUET_NG +#include "TmcDriverTemperatureSensor.h" +#endif + +// Constructor +TemperatureSensor::TemperatureSensor(unsigned int chan, const char *t) : sensorChannel(chan), sensorType(t), heaterName(nullptr) {} + +// Virtual destructor +TemperatureSensor::~TemperatureSensor() +{ + delete heaterName; +} + +// Set the name - normally called only once +void TemperatureSensor::SetHeaterName(const char *newName) +{ + // Change the heater name in a thread-safe manner + const char *oldName = heaterName; + heaterName = nullptr; + delete oldName; + + if (newName != nullptr) + { + char *temp = new char[strlen(newName)]; + strcpy(temp, newName); + heaterName = temp; + } +} + +// Default implementation of Configure, for sensors that have no configurable parameters +bool TemperatureSensor::Configure(unsigned int mCode, unsigned int heater, GCodeBuffer& gb, StringRef& reply, bool& error) +{ + bool seen = false; + if (mCode == 305) + { + TryConfigureHeaterName(gb, seen); + if (!seen && !gb.Seen('X')) + { + // No parameters provided, so report the current configuration + CopyBasicHeaterDetails(heater, reply); + } + } + return seen; +} + +void TemperatureSensor::CopyBasicHeaterDetails(unsigned int heater, StringRef& reply) const +{ + reply.printf("Heater %u", heater); + if (heaterName != nullptr) + { + reply.catf(" (%s)", heaterName); + } + reply.catf(" uses %s sensor channel %u", sensorType, sensorChannel); +} + +// Configure then heater name, if it is provided +void TemperatureSensor::TryConfigureHeaterName(GCodeBuffer& gb, bool& seen) +{ + char buf[MaxHeaterNameLength + 1]; + bool localSeen = false; + gb.TryGetQuotedString('H', buf, ARRAY_SIZE(buf), localSeen); + if (localSeen) + { + SetHeaterName(buf); + seen = true; + } +} + +// Factory method +TemperatureSensor *TemperatureSensor::Create(unsigned int channel) +{ + TemperatureSensor *ts = nullptr; + if (channel < Heaters) + { + ts = new Thermistor(channel); + } + else if (FirstThermocoupleChannel <= channel && channel < FirstThermocoupleChannel + MaxSpiTempSensors) + { + ts = new ThermocoupleSensor31855(channel); + } + else if (FirstRtdChannel <= channel && channel < FirstRtdChannel + MaxSpiTempSensors) + { + ts = new RtdSensor31865(channel); + } + else if (FirstLinearAdcChannel <= channel && channel < FirstLinearAdcChannel + MaxSpiTempSensors) + { + ts = new CurrentLoopTemperatureSensor(channel); + } +#ifndef __RADDS__ + else if (channel == CpuTemperatureSenseChannel) + { + ts = new CpuTemperatureSensor(channel); + } +#endif +#ifdef DUET_NG + else if (channel >= FirstTmcDriversSenseChannel && channel < FirstTmcDriversSenseChannel + 2) + { + ts = new TmcDriverTemperatureSensor(channel); + } +#endif + + if (ts != nullptr) + { + ts->Init(); + } + return ts; +} + +// End diff --git a/src/Heating/Sensors/TemperatureSensor.h b/src/Heating/Sensors/TemperatureSensor.h new file mode 100644 index 00000000..26aec74e --- /dev/null +++ b/src/Heating/Sensors/TemperatureSensor.h @@ -0,0 +1,55 @@ +#ifndef TEMPERATURESENSOR_H +#define TEMPERATURESENSOR_H + +#include "RepRapFirmware.h" +#include "Heating/TemperatureError.h" // for result codes + +class GCodeBuffer; + +class TemperatureSensor +{ +public: + TemperatureSensor(unsigned int chan, const char *type); + + // Configure the sensor from M305 parameters. + // If we find any parameters, process them and return true. If an error occurs while processing them, set 'error' to true and write an error message to 'reply. + // if we find no relevant parameters, report the current parameters to 'reply' and return 'false'. + virtual bool Configure(unsigned int mCode, unsigned int heater, GCodeBuffer& gb, StringRef& reply, bool& error); + + // Initialise or re-initialise the temperature sensor + virtual void Init() = 0; + + // Try to get a temperature reading + virtual TemperatureError GetTemperature(float& t) = 0; + + // Return the channel number + unsigned int GetSensorChannel() const { return sensorChannel; } + + // Return the sensor type + const char *GetSensorType() const { return sensorType; } + + // Configure then heater name, if it is provided + void TryConfigureHeaterName(GCodeBuffer& gb, bool& seen); + + // Virtual destructor + virtual ~TemperatureSensor(); + + // Set the name - normally called only once + void SetHeaterName(const char *newName); + + // Get the name. Returns nullptr if no name has been assigned. + const char *GetHeaterName() const { return heaterName; } + + // Factory method + static TemperatureSensor *Create(unsigned int channel); + +protected: + void CopyBasicHeaterDetails(unsigned int heater, StringRef& reply) const; + +private: + const unsigned int sensorChannel; + const char * const sensorType; + const char *heaterName; +}; + +#endif // TEMPERATURESENSOR_H diff --git a/src/Heating/Sensors/Thermistor.cpp b/src/Heating/Sensors/Thermistor.cpp new file mode 100644 index 00000000..83e967df --- /dev/null +++ b/src/Heating/Sensors/Thermistor.cpp @@ -0,0 +1,139 @@ +/* + * Thermistor.cpp + * + * Created on: 10 Nov 2016 + * Author: David + */ + +#include "Thermistor.h" +#include "Platform.h" +#include "RepRap.h" +#include "GCodes/GCodeBuffer.h" + +// The Steinhart-Hart equation for thermistor resistance is: +// 1/T = A + B ln(R) + C [ln(R)]^3 +// +// The simplified (beta) equation assumes C=0 and is: +// 1/T = A + (1/Beta) ln(R) +// +// The parameters that can be configured in RRF are R25 (the resistance at 25C), Beta, and optionally C. + +// Create an instance with default values +Thermistor::Thermistor(unsigned int channel) + : TemperatureSensor(channel - FirstThermistorChannel, "Thermistor"), adcLowOffset(0), adcHighOffset(0) +{ + r25 = (channel == FirstThermistorChannel) ? BED_R25 : EXT_R25; + beta = (channel == FirstThermistorChannel) ? BED_BETA : EXT_BETA; + shC = (channel == FirstThermistorChannel) ? BED_SHC : EXT_SHC; + seriesR = THERMISTOR_SERIES_RS; + CalcDerivedParameters(); +} + +void Thermistor::Init() +{ + reprap.GetPlatform().GetThermistorFilter(GetSensorChannel() - FirstThermistorChannel).Init((1 << AdcBits) - 1); +} + +// Configure the temperature sensor +bool Thermistor::Configure(unsigned int mCode, unsigned int heater, GCodeBuffer& gb, StringRef& reply, bool& error) +{ + bool seen = false; + if (mCode == 305) + { + // We must set the 25C resistance and beta together in order to calculate Rinf. Check for these first. + + gb.TryGetFValue('T', r25, seen); + gb.TryGetFValue('B', beta, seen); + gb.TryGetFValue('C', shC, seen); + gb.TryGetFValue('R', seriesR, seen); + if (seen) + { + CalcDerivedParameters(); + } + + if (gb.Seen('L')) + { + adcLowOffset = (int8_t)constrain<int>(gb.GetIValue(), -100, 100); + seen = true; + } + if (gb.Seen('H')) + { + adcHighOffset = (int8_t)constrain<int>(gb.GetIValue(), -100, 100); + seen = true; + } + + TryConfigureHeaterName(gb, seen); + + if (!seen && !gb.Seen('X')) + { + CopyBasicHeaterDetails(heater, reply); + reply.catf(", T:%.1f B:%.1f C:%.2e R:%.1f L:%d H:%d", + r25, beta, shC, seriesR, adcLowOffset, adcHighOffset); + } + } + + return seen; +} + +// Get the temperature +TemperatureError Thermistor::GetTemperature(float& t) +{ + const volatile ThermistorAveragingFilter& filter = reprap.GetPlatform().GetThermistorFilter(GetSensorChannel() - FirstThermistorChannel); + if (filter.IsValid()) + { + const int32_t averagedReading = filter.GetSum()/(ThermistorAverageReadings >> Thermistor::AdcOversampleBits); + const float temp = CalcTemperature(averagedReading); + + if (temp < MinimumConnectedTemperature) + { + // thermistor is disconnected + t = ABS_ZERO; + return TemperatureError::openCircuit; + } + + t = temp; + return TemperatureError::success; + } + + // Filter is not ready yet + t = BAD_ERROR_TEMPERATURE; + return TemperatureError::busBusy; +} + +// Calculate temperature from an ADC reading in the range 0..1 +float Thermistor::CalcTemperature(int32_t adcReading) const +{ + const float denom = (float)(AdcRange + (int)adcHighOffset - adcReading) - 0.5; + if (denom <= 0.0) + { + return ABS_ZERO; + } + const float resistance = seriesR * ((float)(adcReading - (int)adcLowOffset) + 0.5)/denom; + const float logResistance = log(resistance); + const float recipT = shA + shB * logResistance + shC * logResistance * logResistance * logResistance; + return (recipT > 0.0) ? (1.0/recipT) + ABS_ZERO : BAD_ERROR_TEMPERATURE; +} + +// Calculate expected ADC reading at a particular temperature, rounded down as the ADC does +int32_t Thermistor::CalcAdcReading(float temperature) const +{ + const double bDFiv3c = shB/(3.0 * shC); + const double halfY = (shA - 1.0/(temperature - ABS_ZERO))/(2.0 * shC); + const double x = sqrt((bDFiv3c * bDFiv3c * bDFiv3c) + (halfY * halfY)); + const double oneThird = 1.0/3.0; + const float resistance = exp(pow(x - halfY, oneThird) - pow(x + halfY, oneThird)); + const float fraction = resistance/(resistance + seriesR); + const int32_t actualAdcRange = AdcRange + (int)adcHighOffset - (int)adcLowOffset; + const int32_t val = (int32_t)(fraction * (float)actualAdcRange) + (int)adcLowOffset; + return constrain<int>(val, 0, AdcRange - 1); +} + +// Calculate shA and shB from the other parameters +void Thermistor::CalcDerivedParameters() +{ + shB = 1.0/beta; + const double lnR25 = log(r25); + shA = 1.0/(25.0 - ABS_ZERO) - shB * lnR25 - shC * lnR25 * lnR25 * lnR25; +} + +// End diff --git a/src/Heating/Thermistor.h b/src/Heating/Sensors/Thermistor.h index eabc45f9..1c002c34 100644 --- a/src/Heating/Thermistor.h +++ b/src/Heating/Sensors/Thermistor.h @@ -8,7 +8,7 @@ #ifndef SRC_HEATING_THERMISTOR_H_ #define SRC_HEATING_THERMISTOR_H_ -#include "RepRapFirmware.h" +#include "TemperatureSensor.h" // The Steinhart-Hart equation for thermistor resistance is: // 1/T = A + B ln(R) + C [ln(R)]^3 @@ -18,10 +18,15 @@ // // The parameters that can be configured in RRF are R25 (the resistance at 25C), Beta, and optionally C. -class Thermistor +class Thermistor : public TemperatureSensor { public: - Thermistor(); // create an instance with default values + Thermistor(unsigned int channel); // create an instance with default values + bool Configure(unsigned int mCode, unsigned int heater, GCodeBuffer& gb, StringRef& reply, bool& error) override; // configure the sensor from M305 parameters + void Init() override; + TemperatureError GetTemperature(float& t) override; + +private: float CalcTemperature(int32_t adcReading) const; // calculate temperature from an ADC reading in the range 0..1 int32_t CalcAdcReading(float temperature) const; // calculate expected ADC reading at a particular temperature @@ -32,14 +37,12 @@ public: int8_t GetLowOffset() const { return adcLowOffset; } int8_t GetHighOffset() const { return adcHighOffset; } - void SetParameters(float p_r25, float p_beta, float p_shC, float p_seriesR); // initialise the main parameters void SetLowOffset(int8_t p_offset) { adcLowOffset = p_offset; } void SetHighOffset(int8_t p_offset) { adcHighOffset = p_offset; } // For the theory behind ADC oversampling, see http://www.atmel.com/Images/doc8003.pdf static const unsigned int AdcOversampleBits = 1 ; // we use 1-bit oversampling -private: void CalcDerivedParameters(); // calculate shA and shB // The following are configurable parameters diff --git a/src/Heating/Sensors/ThermocoupleSensor31855.cpp b/src/Heating/Sensors/ThermocoupleSensor31855.cpp new file mode 100644 index 00000000..10d6f2bc --- /dev/null +++ b/src/Heating/Sensors/ThermocoupleSensor31855.cpp @@ -0,0 +1,156 @@ +/* + * ThermocoupleSensor31855.cpp + * + * Created on: 8 Jun 2017 + * Author: David + */ + +// MAX31855 thermocouple chip +// +// The MAX31855 continuously samples a Type K thermocouple. When the MAX31855 +// is selected via its chip select (CS) pin, it unconditionally writes a 32 bit +// sequence onto the bus. This sequence is designed such that we need only +// interpret the high 16 bits in order to ascertain the temperature reading and +// whether there a fault condition exists. The low 16 bits provide the +// MAX31855's cold junction temperature (and thus the board temperature) as +// well as finer detail on any existing fault condition. +// +// The temperature read from the chip is a signed, two's-complement integer. +// As it is a 14 bit value (in units of one-quarter degrees Celsius), we +// convert it to a proper signed 16 bit value by adding two high bits. The +// high bits added should both be zero if the value is positive (highest bit +// of the 14 bit value is zero), or both be one if the value is negative +// (highest bit of the 14 bit value is one). +// +// Note Bene: there's a Arduino Due sketch floating about the internet which +// gets this wrong and for negative temperatures generates incorrect values. +// E.g, -2047C for what should be -1C; -1798C for what should be -250C. The +// values of -1C and -250C are shown as examples in Table 4 of the datasheet +// for the MAX21855.) The incorrect Arduino Due sketch appears in, and may be +// from, the book Arduino Sketches: Tools and Techniques for Programming +// Wizardry, James A. Langbridge, January 12, 2015, John Wiley & Sons. + +// Bits -- Interpretation +// ----- ----------------------------------------------------------------- +// 31:18 -- 14 bit, signed thermocouple temperature data. Units of 0.25 C +// 17 -- Reserved +// 16 -- Fault indicator (1 if fault detected; 0 otherwise) +// 15:04 -- 12 bit, signed cold junction temperature data. Units of 0.0625 C +// 03 -- Reserved +// 02 -- SCV fault; reads 1 if the thermocouple is shorted to Vcc +// 01 -- SCG fault; reads 1 if the thermocouple is shorted to ground +// 00 -- OC fault; reads 1 if the thermocouple is not connected (open) + +// For purposes of setting bit transfer widths and timings, we need to use a +// Peripheral Channel Select (PCS). Use channel #3 as it is unlikely to be +// used by anything else as the Arduino Due leaves pin 78 unconnected. +// +#include "ThermocoupleSensor31855.h" +#include "RepRap.h" +#include "Platform.h" +#include "Core.h" + +const uint32_t MAX31855_Frequency = 4000000; // maximum for MAX31855 is 5MHz + +// SPI modes: +// If the inactive state of SCL is LOW (CPOL = 0) (in the case of the MAX31865, this is sampled on the falling edge of CS): +// The MAX31855 sets up the first data bit after the falling edge of CLK, and changes the data on each falling clock edge. +// So the SAM needs to sample data on the rising clock edge. This requires NCPHA = 1. +const uint8_t MAX31855_SpiMode = SPI_MODE_0; + +// Define the minimum interval between readings +const uint32_t MinimumReadInterval = 100; // minimum interval between reads, in milliseconds + +ThermocoupleSensor31855::ThermocoupleSensor31855(unsigned int channel) + : SpiTemperatureSensor(channel, "Thermocouple (MAX31855)", channel - FirstThermocoupleChannel, MAX31855_SpiMode, MAX31855_Frequency) +{ +} + +// Perform the actual hardware initialization for attaching and using this device on the SPI hardware bus. +void ThermocoupleSensor31855::Init() +{ + InitSpi(); + lastReadingTime = millis(); +} + +TemperatureError ThermocoupleSensor31855::GetTemperature(float& t) +{ + if (inInterrupt() || millis() - lastReadingTime < MinimumReadInterval) + { + t = lastTemperature; + } + else + { + uint32_t rawVal; + TemperatureError sts = DoSpiTransaction(nullptr, 4, rawVal); + if (sts != TemperatureError::success) + { + lastResult = sts; + } + else + { + lastReadingTime = millis(); + + if ((rawVal & 0x00020008) != 0) + { + // These two bits should always read 0. Likely the entire read was 0xFF 0xFF which is not uncommon when first powering up + lastResult = TemperatureError::ioError; + } + else if ((rawVal & 0x00010007) != 0) // check the fault bits + { + // Check for three more types of bad reads as we set the response code: + // 1. A read in which the fault indicator bit (16) is set but the fault reason bits (0:2) are all clear; + // 2. A read in which the fault indicator bit (16) is clear, but one or more of the fault reason bits (0:2) are set; and, + // 3. A read in which more than one of the fault reason bits (0:1) are set. + if ((rawVal & 0x00010000) == 0) + { + // One or more fault reason bits are set but the fault indicator bit is clear + lastResult = TemperatureError::ioError; + } + else + { + // At this point we are assured that bit 16 (fault indicator) is set and that at least one of the fault reason bits (0:2) are set. + // We now need to ensure that only one fault reason bit is set. + uint8_t nbits = 0; + if (rawVal & 0x01) + { + // Open Circuit + ++nbits; + lastResult = TemperatureError::openCircuit; + } + if (rawVal & 0x02) + { + // Short to ground; + ++nbits; + lastResult = TemperatureError::shortToGround; + } + if (rawVal && 0x04) + { + // Short to Vcc + ++nbits; + lastResult = TemperatureError::shortToVcc; + } + + if (nbits != 1) + { + // Fault indicator was set but a fault reason was not set (nbits == 0) or too many fault reason bits were set (nbits > 1). + // Assume that a communication error with the MAX31855 has occurred. + lastResult = TemperatureError::ioError; + } + } + } + else + { + rawVal >>= 18; // shift the 14-bit temperature data to the bottom of the word + rawVal |= (0 - (rawVal & 0x2000)); // sign-extend the sign bit + + // And convert to from units of 1/4C to 1C + t = lastTemperature = (float)(0.25 * (float)(int32_t)rawVal); + lastResult = TemperatureError::success; + } + } + } + return lastResult; +} + +// End diff --git a/src/Heating/Sensors/ThermocoupleSensor31855.h b/src/Heating/Sensors/ThermocoupleSensor31855.h new file mode 100644 index 00000000..0b877f62 --- /dev/null +++ b/src/Heating/Sensors/ThermocoupleSensor31855.h @@ -0,0 +1,21 @@ +/* + * ThermocoupleSensor31855.h + * + * Created on: 8 Jun 2017 + * Author: David + */ + +#ifndef SRC_HEATING_THERMOCOUPLESENSOR31855_H_ +#define SRC_HEATING_THERMOCOUPLESENSOR31855_H_ + +#include "SpiTemperatureSensor.h" + +class ThermocoupleSensor31855 : public SpiTemperatureSensor +{ +public: + ThermocoupleSensor31855(unsigned int channel); + void Init() override; + TemperatureError GetTemperature(float& t) override; +}; + +#endif /* SRC_HEATING_THERMOCOUPLESENSOR31855_H_ */ diff --git a/src/Heating/Sensors/TmcDriverTemperatureSensor.cpp b/src/Heating/Sensors/TmcDriverTemperatureSensor.cpp new file mode 100644 index 00000000..fe2ccbf9 --- /dev/null +++ b/src/Heating/Sensors/TmcDriverTemperatureSensor.cpp @@ -0,0 +1,30 @@ +/* + * TmcDriverTemperatureSensor.cpp + * + * Created on: 8 Jun 2017 + * Author: David + */ + +#include "TmcDriverTemperatureSensor.h" +#include "Platform.h" +#include "RepRap.h" + +#ifdef DUET_NG + +TmcDriverTemperatureSensor::TmcDriverTemperatureSensor(unsigned int channel) : TemperatureSensor(channel, "TMC2660 temperature warnings") +{ +} + +void TmcDriverTemperatureSensor::Init() +{ +} + +TemperatureError TmcDriverTemperatureSensor::GetTemperature(float& t) +{ + t = reprap.GetPlatform().GetTmcDriversTemperature(GetSensorChannel() - FirstTmcDriversSenseChannel); + return TemperatureError::success; +} + +#endif + +// End diff --git a/src/Heating/Sensors/TmcDriverTemperatureSensor.h b/src/Heating/Sensors/TmcDriverTemperatureSensor.h new file mode 100644 index 00000000..be18dd5c --- /dev/null +++ b/src/Heating/Sensors/TmcDriverTemperatureSensor.h @@ -0,0 +1,25 @@ +/* + * TmcDriverTemperatureSensor.h + * + * Created on: 8 Jun 2017 + * Author: David + */ + +#ifndef SRC_HEATING_SENSORS_TMCDRIVERTEMPERATURESENSOR_H_ +#define SRC_HEATING_SENSORS_TMCDRIVERTEMPERATURESENSOR_H_ + +#include "TemperatureSensor.h" + +#ifdef DUET_NG + +class TmcDriverTemperatureSensor : public TemperatureSensor +{ +public: + TmcDriverTemperatureSensor(unsigned int channel); + void Init() override; + TemperatureError GetTemperature(float& t) override; +}; + +#endif + +#endif /* SRC_HEATING_SENSORS_TMCDRIVERTEMPERATURESENSOR_H_ */ diff --git a/src/Heating/TemperatureError.cpp b/src/Heating/TemperatureError.cpp index 294c37bd..f50d1c0c 100644 --- a/src/Heating/TemperatureError.cpp +++ b/src/Heating/TemperatureError.cpp @@ -23,6 +23,8 @@ const char* TemperatureErrorString(TemperatureError err) case TemperatureError::busBusy: return "sensor bus busy"; case TemperatureError::badResponse: return "bad response from sensor"; case TemperatureError::unknownChannel: return "unknown temperature sensor channel"; + case TemperatureError::notInitialised: return "sensor not initialised"; + case TemperatureError::unknownHeater: return "unknown heater"; default: return "unknown temperature sense error"; } } diff --git a/src/Heating/TemperatureError.h b/src/Heating/TemperatureError.h index c9f3a09a..24ae9a41 100644 --- a/src/Heating/TemperatureError.h +++ b/src/Heating/TemperatureError.h @@ -24,7 +24,9 @@ enum class TemperatureError : uint8_t hardwareError, busBusy, badResponse, - unknownChannel + unknownChannel, + notInitialised, + unknownHeater }; const char* TemperatureErrorString(TemperatureError err); diff --git a/src/Heating/TemperatureSensor.cpp b/src/Heating/TemperatureSensor.cpp deleted file mode 100644 index 74a9c399..00000000 --- a/src/Heating/TemperatureSensor.cpp +++ /dev/null @@ -1,449 +0,0 @@ -#include "TemperatureSensor.h" -#include "Platform.h" -#include "RepRap.h" - -// MAX31855 thermocouple chip -// -// The MAX31855 continuously samples a Type K thermocouple. When the MAX31855 -// is selected via its chip select (CS) pin, it unconditionally writes a 32 bit -// sequence onto the bus. This sequence is designed such that we need only -// interpret the high 16 bits in order to ascertain the temperature reading and -// whether there a fault condition exists. The low 16 bits provide the -// MAX31855's cold junction temperature (and thus the board temperature) as -// well as finer detail on any existing fault condition. -// -// The temperature read from the chip is a signed, two's-complement integer. -// As it is a 14 bit value (in units of one-quarter degrees Celsius), we -// convert it to a proper signed 16 bit value by adding two high bits. The -// high bits added should both be zero if the value is positive (highest bit -// of the 14 bit value is zero), or both be one if the value is negative -// (highest bit of the 14 bit value is one). -// -// Note Bene: there's a Arduino Due sketch floating about the internet which -// gets this wrong and for negative temperatures generates incorrect values. -// E.g, -2047C for what should be -1C; -1798C for what should be -250C. The -// values of -1C and -250C are shown as examples in Table 4 of the datasheet -// for the MAX21855.) The incorrect Arduino Due sketch appears in, and may be -// from, the book Arduino Sketches: Tools and Techniques for Programming -// Wizardry, James A. Langbridge, January 12, 2015, John Wiley & Sons. - -// Bits -- Interpretation -// ----- ----------------------------------------------------------------- -// 31:18 -- 14 bit, signed thermocouple temperature data. Units of 0.25 C -// 17 -- Reserved -// 16 -- Fault indicator (1 if fault detected; 0 otherwise) -// 15:04 -- 12 bit, signed cold junction temperature data. Units of 0.0625 C -// 03 -- Reserved -// 02 -- SCV fault; reads 1 if the thermocouple is shorted to Vcc -// 01 -- SCG fault; reads 1 if the thermocouple is shorted to ground -// 00 -- OC fault; reads 1 if the thermocouple is not connected (open) - -// For purposes of setting bit transfer widths and timings, we need to use a -// Peripheral Channel Select (PCS). Use channel #3 as it is unlikely to be -// used by anything else as the Arduino Due leaves pin 78 unconnected. -// -// No warranty given or implied, use at your own risk. -// dan.newman@mtbaldy.us -// GPL v3 - -const uint32_t MAX31855_Frequency = 4000000; // maximum for MAX31855 is 5MHz -const uint32_t MAX31865_Frequency = 4000000; // maximum for MAX31865 is also 5MHz -const uint32_t MCP3204_Frequency = 1000000; // maximum for MCP3204 is 1MHz @ 2.7V, will be slightly higher at 3.3V - -// SPI modes: -// If the inactive state of SCL is LOW (CPOL = 0) (in the case of the MAX31865, this is sampled on the falling edge of CS): -// The MAX31855 sets up the first data bit after the falling edge of CLK, and changes the data on each falling clock edge. -// So the SAM needs to sample data on the rising clock edge. This requires NCPHA = 1. -// The MAX31865 changes data after the rising edge of CLK, and samples input data on the falling edge. -// This requires NCPHA = 0. -// The MCP3204 samples input data on the rising edge and changes the output data on the rising edge. - -const uint8_t MAX31855_SpiMode = SPI_MODE_0; -const uint8_t MAX31865_SpiMode = SPI_MODE_1; -const uint8_t MCP3204_SpiMode = SPI_MODE_0; - -// Define the minimum interval between readings. The MAX31865 needs 62.5ms in 50Hz filter mode. -const uint32_t MinimumReadInterval = 100; // minimum interval between reads, in milliseconds - -// Table of temperature vs. MAX31865 result for PT100 thermistor, from the MAX31865 datasheet -struct TempTableEntry -{ - int16_t temperature; - uint16_t adcReading; -}; - -static const TempTableEntry tempTable[] = -{ - {-30, 7227}, - {-20, 7550}, - {-10, 7871}, - {0, 8192}, - {10, 8512}, - {20, 8830}, - {30, 9148}, - {40, 9465}, - {50, 9781}, - {60, 10096}, - {70, 10410}, - {80, 10723}, - {90, 11035}, - {100, 11346}, - {110, 11657}, - {120, 11966}, - {130, 12274}, - {140, 12582}, - {150, 12888}, - {160, 13194}, - {170, 13498}, - {180, 13802}, - {190, 14104}, - {200, 14406}, - {225, 15156}, - {250, 15901}, - {275, 16639}, - {300, 17371}, - {325, 18098}, - {350, 18818}, - {375, 19533}, - {400, 20242}, - {425, 20945}, - {450, 21642}, - {475, 22333}, - {500, 23018}, - {525, 23697}, - {550, 24370} -}; - -const size_t NumTempTableEntries = sizeof(tempTable)/sizeof(tempTable[0]); - -// Perform the actual hardware initialization for attaching and using this device on the SPI hardware bus. -void TemperatureSensor::InitThermocouple(uint8_t cs) -{ - device.csPin = cs; - device.spiMode = MAX31855_SpiMode; - device.clockFrequency = MAX31855_Frequency; - sspi_master_init(&device, 8); - - lastReadingTime = millis(); - lastResult = TemperatureError::success; - lastTemperature = 0.0; -} - -// Perform the actual hardware initialization for attaching and using this device on the SPI hardware bus. -void TemperatureSensor::InitRtd(uint8_t cs) -{ - device.csPin = cs; - device.spiMode = MAX31865_SpiMode; - device.clockFrequency = MAX31865_Frequency; - sspi_master_init(&device, 8); - - TemperatureError rslt; - for (unsigned int i = 0; i < 3; ++i) // try 3 times - { - rslt = TryInitRtd(); - if (rslt == TemperatureError::success) - { - break; - } - delay(MinimumReadInterval); - } - - lastReadingTime = millis(); - lastResult = rslt; - lastTemperature = 0.0; - - if (rslt != TemperatureError::success) - { - reprap.GetPlatform().MessageF(GENERIC_MESSAGE, "Error: failed to initialise RTD: %s\n", TemperatureErrorString(rslt)); - } -} - -// Try to initialise the RTD -TemperatureError TemperatureSensor::TryInitRtd() const -{ - // Note that to get the MAX31865 to do continuous conversions, we need to set the bias bit as well as the continuous-conversion bit - static const uint8_t modeData[2] = { 0x80, 0xC3 }; // write register 0, bias on, auto conversion, clear errors, 50Hz - uint32_t rawVal; - TemperatureError sts = DoSpiTransaction(modeData, 2, rawVal); - - if (sts == TemperatureError::success) - { - static const uint8_t readData[2] = { 0x00, 0x00 }; // read register 0 - sts = DoSpiTransaction(readData, 2, rawVal); - } - - //debugPrintf("Status %d data %04x\n", (int)sts, rawVal); - return (sts == TemperatureError::success && (uint8_t)rawVal != 0xC1) - ? TemperatureError::badResponse - : sts; -} - -// Initialise the linear ADC -void TemperatureSensor::InitLinearAdc(uint8_t cs) -{ - device.csPin = cs; - device.spiMode = MCP3204_SpiMode; - device.clockFrequency = MCP3204_Frequency; - sspi_master_init(&device, 8); - - for (unsigned int i = 0; i < 3; ++i) // try 3 times - { - TryGetLinearAdcTemperature(); - if (lastResult == TemperatureError::success) - { - break; - } - delay(MinimumReadInterval); - } - - lastReadingTime = millis(); - - if (lastResult != TemperatureError::success) - { - reprap.GetPlatform().MessageF(GENERIC_MESSAGE, "Error: failed to initialise daughter board ADC: %s\n", TemperatureErrorString(lastResult)); - } - -} - -TemperatureError TemperatureSensor::GetThermocoupleTemperature(float& t) -{ - if (inInterrupt() || millis() - lastReadingTime < MinimumReadInterval) - { - t = lastTemperature; - } - else - { - uint32_t rawVal; - TemperatureError sts = DoSpiTransaction(nullptr, 4, rawVal); - if (sts != TemperatureError::success) - { - lastResult = sts; - } - else - { - lastReadingTime = millis(); - - if ((rawVal & 0x00020008) != 0) - { - // These two bits should always read 0. Likely the entire read was 0xFF 0xFF which is not uncommon when first powering up - lastResult = TemperatureError::ioError; - } - else if ((rawVal & 0x00010007) != 0) // check the fault bits - { - // Check for three more types of bad reads as we set the response code: - // 1. A read in which the fault indicator bit (16) is set but the fault reason bits (0:2) are all clear; - // 2. A read in which the fault indicator bit (16) is clear, but one or more of the fault reason bits (0:2) are set; and, - // 3. A read in which more than one of the fault reason bits (0:1) are set. - if ((rawVal & 0x00010000) == 0) - { - // One or more fault reason bits are set but the fault indicator bit is clear - lastResult = TemperatureError::ioError; - } - else - { - // At this point we are assured that bit 16 (fault indicator) is set and that at least one of the fault reason bits (0:2) are set. - // We now need to ensure that only one fault reason bit is set. - uint8_t nbits = 0; - if (rawVal & 0x01) - { - // Open Circuit - ++nbits; - lastResult = TemperatureError::openCircuit; - } - if (rawVal & 0x02) - { - // Short to ground; - ++nbits; - lastResult = TemperatureError::shortToGround; - } - if (rawVal && 0x04) - { - // Short to Vcc - ++nbits; - lastResult = TemperatureError::shortToVcc; - } - - if (nbits != 1) - { - // Fault indicator was set but a fault reason was not set (nbits == 0) or too many fault reason bits were set (nbits > 1). - // Assume that a communication error with the MAX31855 has occurred. - lastResult = TemperatureError::ioError; - } - } - } - else - { - rawVal >>= 18; // shift the 14-bit temperature data to the bottom of the word - rawVal |= (0 - (rawVal & 0x2000)); // sign-extend the sign bit - - // And convert to from units of 1/4C to 1C - t = lastTemperature = (float)(0.25 * (float)(int32_t)rawVal); - lastResult = TemperatureError::success; - } - } - } - return lastResult; -} - -TemperatureError TemperatureSensor::GetRtdTemperature(float& t) -{ - if (inInterrupt() || millis() - lastReadingTime < MinimumReadInterval) - { - t = lastTemperature; - } - else - { - static const uint8_t dataOut[4] = {0, 55, 55, 55}; // read registers 0 (control), 1 (MSB) and 2 (LSB) - uint32_t rawVal; - TemperatureError sts = DoSpiTransaction(dataOut, 4, rawVal); - - if (sts != TemperatureError::success) - { - lastResult = sts; - } - else - { - lastReadingTime = millis(); - if (((rawVal & 0x00C10000) != 0xC10000) -#if 0 - // We no longer check the error status bit, because it seems to be impossible to clear it once it has been set. - // Perhaps we would need to exit continuous reading mode to do so, and then re-enable it afterwards. But this would - // take to long. -#else - || (rawVal & 1) != 0 -#endif - ) - { - // Either the continuous conversion bit has got cleared, or the fault bit has been set - TryInitRtd(); - lastResult = TemperatureError::hardwareError; - } - else - { - uint16_t adcVal = (rawVal >> 1) & 0x7FFF; - - // Formally-verified binary search routine, adapted from one of the eCv examples - size_t low = 0u, high = NumTempTableEntries; - while (high > low) - keep(low <= high; high <= NumTempTableEntries) - keep(low == 0u || tempTable[low - 1u].adcReading < adcVal) - keep(high == NumTempTableEntries || adcVal <= tempTable[high].adcReading) - decrease(high - low) - { - size_t mid = (high - low)/2u + low; // get the mid point, avoiding arithmetic overflow - if (adcVal <= tempTable[mid].adcReading) - { - high = mid; - } - else - { - low = mid + 1u; - } - } - assert(low <= NumTempTableEntries); - assert(low == 0 || tempTable[low - 1] < adcVal); - assert(low == NumTempTableEntries || adcVal <= tempTable[low]); - - if (low == 0) // if off the bottom of the table - { - lastResult = TemperatureError::shortCircuit; - } - else if (low >= NumTempTableEntries) // if off the top of the table - { - lastResult = TemperatureError::openCircuit; - } - else - { - const float interpolationFraction = (float)(adcVal - tempTable[low - 1].adcReading)/(float)(tempTable[low].adcReading - tempTable[low - 1].adcReading); - t = lastTemperature = ((float)(tempTable[low].temperature - tempTable[low - 1].temperature) * interpolationFraction) - + (float)tempTable[low - 1].temperature; - //debugPrintf("raw %u low %u interp %f temp %f\n", adcVal, low, interpolationFraction, *t); - lastResult = TemperatureError::success; - } - } - } - } - return lastResult; -} - -TemperatureError TemperatureSensor::GetLinearAdcTemperature(float& t) -{ - if (!inInterrupt() && millis() - lastReadingTime >= MinimumReadInterval) - { - TryGetLinearAdcTemperature(); - } - - t = lastTemperature; - return lastResult; -} - -// Try to get a temperature reading from the linear ADC by doing an SPI transaction -void TemperatureSensor::TryGetLinearAdcTemperature() -{ - // The MCP3204 waits for a high input input bit before it does anything. Call this clock 1. - // The next input bit it high for single-ended operation, low for differential. This is clock 2. - // The next 3 input bits are the channel selection bits. These are clocks 3..5. - // Clock 6 produces a null bit on its trailing edge, which is read by the processor on clock 7. - // Clocks 7..18 produce data bits B11..B0 on their trailing edges, which are read by the MCU on the leading edges of clocks 8-19. - // If we supply further clocks, then clocks 18..29 are the same data but LSB first, omitting bit 0. - // Clocks 30 onwards will be zeros. - // So we need to use at least 19 clocks. We round this up to 24 clocks, and we check that the extra 5 bits we receive are the 5 least significant data bits in reverse order. - - static const uint8_t adcData[] = { 0xC0, 0x00, 0x00 }; // start bit, single ended, channel 0 - uint32_t rawVal; - lastResult = DoSpiTransaction(adcData, 3, rawVal); - //debugPrintf("ADC data %u\n", rawVal); - - if (lastResult == TemperatureError::success) - { - const uint32_t adcVal1 = (rawVal >> 5) & ((1 << 13) - 1); - const uint32_t adcVal2 = ((rawVal & 1) << 5) | ((rawVal & 2) << 3) | ((rawVal & 4) << 1) | ((rawVal & 8) >> 1) | ((rawVal & 16) >> 3) | ((rawVal & 32) >> 5); - if (adcVal1 >= 4096 || adcVal2 != (adcVal1 & ((1 << 6) - 1))) - { - lastResult = TemperatureError::badResponse; - } - else - { - lastTemperature = MinLinearAdcTemp + (LinearAdcDegCPerCount * (float)adcVal1); - } - } -} - -// Send and receive 1 to 4 bytes of data and return the result as a single 32-bit word -TemperatureError TemperatureSensor::DoSpiTransaction(const uint8_t dataOut[], size_t nbytes, uint32_t& rslt) const -{ - if (!sspi_acquire()) - { - return TemperatureError::busBusy; - } - - sspi_master_setup_device(&device); - delayMicroseconds(1); - sspi_select_device(&device); - delayMicroseconds(1); - - uint8_t rawBytes[4]; - spi_status_t sts = sspi_transceive_packet(dataOut, rawBytes, nbytes); - - delayMicroseconds(1); - sspi_deselect_device(&device); - delayMicroseconds(1); - - sspi_release(); - - if (sts != SPI_OK) - { - return TemperatureError::timeout; - } - - rslt = rawBytes[0]; - for (size_t i = 1; i < nbytes; ++i) - { - rslt <<= 8; - rslt |= rawBytes[i]; - } - - return TemperatureError::success; -} - -// End diff --git a/src/Heating/TemperatureSensor.h b/src/Heating/TemperatureSensor.h deleted file mode 100644 index d54338df..00000000 --- a/src/Heating/TemperatureSensor.h +++ /dev/null @@ -1,33 +0,0 @@ -#ifndef TEMPERATURESENSOR_H -#define TEMPERATURESENSOR_H - -#include "RepRapFirmware.h" -#include "TemperatureError.h" // for result codes -#include "SharedSpi.h" // for sspi_device - -class TemperatureSensor -{ -public: - TemperatureSensor() {} - void InitThermocouple(uint8_t cs); - void InitRtd(uint8_t cs); - void InitLinearAdc(uint8_t cs); - TemperatureError GetThermocoupleTemperature(float& t); - TemperatureError GetRtdTemperature(float& t); - TemperatureError GetLinearAdcTemperature(float& t); - -private: - TemperatureError DoSpiTransaction(const uint8_t dataOut[], size_t nbytes, uint32_t& rslt) const; - TemperatureError TryInitRtd() const; - void TryGetLinearAdcTemperature(); - - sspi_device device; - uint32_t lastReadingTime; - float lastTemperature; - TemperatureError lastResult; - - static constexpr float MinLinearAdcTemp = 385.0 - (1600.0 - 385.0) * (4.0/16.0); - static constexpr float LinearAdcDegCPerCount = (1600.0 - 385.0)/3200.0; -}; - -#endif // TEMPERATURESENSOR_H diff --git a/src/Heating/Thermistor.cpp b/src/Heating/Thermistor.cpp deleted file mode 100644 index d8357573..00000000 --- a/src/Heating/Thermistor.cpp +++ /dev/null @@ -1,70 +0,0 @@ -/* - * Thermistor.cpp - * - * Created on: 10 Nov 2016 - * Author: David - */ - -#include "Thermistor.h" - -// The Steinhart-Hart equation for thermistor resistance is: -// 1/T = A + B ln(R) + C [ln(R)]^3 -// -// The simplified (beta) equation assumes C=0 and is: -// 1/T = A + (1/Beta) ln(R) -// -// The parameters that can be configured in RRF are R25 (the resistance at 25C), Beta, and optionally C. - -// Create an instance with default values -Thermistor::Thermistor() : adcLowOffset(0), adcHighOffset(0) -{ - SetParameters(EXT_R25, EXT_BETA, EXT_SHC, THERMISTOR_SERIES_RS); -} - -// Initialise the instance -void Thermistor::SetParameters(float p_r25, float p_beta, float p_shC, float p_seriesR) -{ - r25 = p_r25; - beta = p_beta; - shC = p_shC; - seriesR = p_seriesR; - CalcDerivedParameters(); -} - -// Calculate temperature from an ADC reading in the range 0..1 -float Thermistor::CalcTemperature(int32_t adcReading) const -{ - const float denom = (float)(AdcRange + (int)adcHighOffset - adcReading) - 0.5; - if (denom <= 0.0) - { - return ABS_ZERO; - } - const float resistance = seriesR * ((float)(adcReading - (int)adcLowOffset) + 0.5)/denom; - const float logResistance = log(resistance); - const float recipT = shA + shB * logResistance + shC * logResistance * logResistance * logResistance; - return (recipT > 0.0) ? (1.0/recipT) + ABS_ZERO : BAD_ERROR_TEMPERATURE; -} - -// Calculate expected ADC reading at a particular temperature, rounded down as the ADC does -int32_t Thermistor::CalcAdcReading(float temperature) const -{ - const double bDFiv3c = shB/(3.0 * shC); - const double halfY = (shA - 1.0/(temperature - ABS_ZERO))/(2.0 * shC); - const double x = sqrt((bDFiv3c * bDFiv3c * bDFiv3c) + (halfY * halfY)); - const double oneThird = 1.0/3.0; - const float resistance = exp(pow(x - halfY, oneThird) - pow(x + halfY, oneThird)); - const float fraction = resistance/(resistance + seriesR); - const int32_t actualAdcRange = AdcRange + (int)adcHighOffset - (int)adcLowOffset; - const int32_t val = (int32_t)(fraction * (float)actualAdcRange) + (int)adcLowOffset; - return constrain<int>(val, 0, AdcRange - 1); -} - -// Calculate shA and shB from the other parameters -void Thermistor::CalcDerivedParameters() -{ - shB = 1.0/beta; - const double lnR25 = log(r25); - shA = 1.0/(25.0 - ABS_ZERO) - shB * lnR25 - shC * lnR25 * lnR25 * lnR25; -} - -// End diff --git a/src/Movement/DDA.cpp b/src/Movement/DDA.cpp index 6e8f7c9c..6217d5fe 100644 --- a/src/Movement/DDA.cpp +++ b/src/Movement/DDA.cpp @@ -61,15 +61,15 @@ static size_t savedMovePointer = 0; #if DDA_LOG_PROBE_CHANGES size_t DDA::numLoggedProbePositions = 0; -int32_t DDA::loggedProbePositions[CART_AXES * MaxLoggedProbePositions]; +int32_t DDA::loggedProbePositions[XYZ_AXES * MaxLoggedProbePositions]; bool DDA::probeTriggered = false; void DDA::LogProbePosition() { if (numLoggedProbePositions < MaxLoggedProbePositions) { - int32_t *p = loggedProbePositions + (numLoggedProbePositions * CART_AXES); - for (size_t drive = 0; drive < CART_AXES; ++drive) + int32_t *p = loggedProbePositions + (numLoggedProbePositions * XYZ_AXES); + for (size_t drive = 0; drive < XYZ_AXES; ++drive) { DriveMovement& dm = ddm[drive]; if (dm.state == DMState::moving) @@ -146,11 +146,11 @@ void DDA::DebugPrintVector(const char *name, const float *vec, size_t len) const void DDA::DebugPrint() const { - const size_t numAxes = reprap.GetGCodes().GetNumAxes(); + const size_t numAxes = reprap.GetGCodes().GetTotalAxes(); debugPrintf("DDA:"); if (endCoordinatesValid) { - float startCoordinates[MAX_AXES]; + float startCoordinates[MaxAxes]; for (size_t i = 0; i < numAxes; ++i) { startCoordinates[i] = endCoordinates[i] - (totalDistance * directionVector[i]); @@ -224,7 +224,7 @@ bool DDA::Init(const GCodes::RawMove &nextMove, bool doMotorMapping) const bool isSpecialDeltaMove = (move.IsDeltaMode() && !doMotorMapping); float accelerations[DRIVES]; const float * const normalAccelerations = reprap.GetPlatform().Accelerations(); - const size_t numAxes = reprap.GetGCodes().GetNumAxes(); + const size_t numAxes = reprap.GetGCodes().GetTotalAxes(); for (size_t drive = 0; drive < DRIVES; drive++) { accelerations[drive] = normalAccelerations[drive]; @@ -739,22 +739,21 @@ void DDA::CalcNewSpeeds() // This is called by Move::CurrentMoveCompleted to update the live coordinates from the move that has just finished bool DDA::FetchEndPosition(volatile int32_t ep[DRIVES], volatile float endCoords[DRIVES]) { - const size_t numAxes = reprap.GetGCodes().GetNumAxes(); - for (size_t drive = 0; drive < DRIVES; ++drive) { ep[drive] = endPoint[drive]; } if (endCoordinatesValid) { - for (size_t axis = 0; axis < numAxes; ++axis) + const size_t visibleAxes = reprap.GetGCodes().GetVisibleAxes(); + for (size_t axis = 0; axis < visibleAxes; ++axis) { endCoords[axis] = endCoordinates[axis]; } } // Extrusion amounts are always valid - for (size_t eDrive = numAxes; eDrive < DRIVES; ++eDrive) + for (size_t eDrive = reprap.GetGCodes().GetTotalAxes(); eDrive < DRIVES; ++eDrive) { endCoords[eDrive] += endCoordinates[eDrive]; } @@ -765,7 +764,7 @@ bool DDA::FetchEndPosition(volatile int32_t ep[DRIVES], volatile float endCoords void DDA::SetPositions(const float move[DRIVES], size_t numDrives) { reprap.GetMove().EndPointToMachine(move, endPoint, numDrives); - const size_t numAxes = reprap.GetGCodes().GetNumAxes(); + const size_t numAxes = reprap.GetGCodes().GetVisibleAxes(); for (size_t axis = 0; axis < numAxes; ++axis) { endCoordinates[axis] = move[axis]; @@ -775,7 +774,7 @@ void DDA::SetPositions(const float move[DRIVES], size_t numDrives) // Get a Cartesian end coordinate from this move float DDA::GetEndCoordinate(size_t drive, bool disableDeltaMapping) -pre(disableDeltaMapping || drive < MAX_AXES) +pre(disableDeltaMapping || drive < MaxAxes) { if (disableDeltaMapping) { @@ -783,10 +782,10 @@ pre(disableDeltaMapping || drive < MAX_AXES) } else { - const size_t numAxes = reprap.GetGCodes().GetNumAxes(); - if (drive < numAxes && !endCoordinatesValid) + const size_t visibleAxes = reprap.GetGCodes().GetVisibleAxes(); + if (drive < visibleAxes && !endCoordinatesValid) { - reprap.GetMove().MotorStepsToCartesian(endPoint, numAxes, endCoordinates); + reprap.GetMove().MotorStepsToCartesian(endPoint, visibleAxes, reprap.GetGCodes().GetTotalAxes(), endCoordinates); endCoordinatesValid = true; } return endCoordinates[drive]; @@ -905,7 +904,7 @@ void DDA::Prepare() goingSlow = false; firstDM = nullptr; - const size_t numAxes = reprap.GetGCodes().GetNumAxes(); + const size_t numAxes = reprap.GetGCodes().GetTotalAxes(); for (size_t drive = 0; drive < DRIVES; ++drive) { DriveMovement& dm = ddm[drive]; @@ -1027,7 +1026,7 @@ float DDA::NormaliseXYZ() // First calculate the magnitude of the vector. If there is more than one X axis, take an average of their movements (they should be equal). float magSquared = 0.0; unsigned int numXaxes = 0; - for (size_t d = 0; d < MAX_AXES; ++d) + for (size_t d = 0; d < MaxAxes; ++d) { if (((1 << d) & xAxes) != 0) { @@ -1129,7 +1128,7 @@ void DDA::CheckEndstops(Platform& platform) } #endif - const size_t numAxes = reprap.GetGCodes().GetNumAxes(); + const size_t numAxes = reprap.GetGCodes().GetTotalAxes(); for (size_t drive = 0; drive < numAxes; ++drive) { if ((endStopsToCheck & (1 << drive)) != 0) @@ -1200,7 +1199,7 @@ pre(state == frozen) if (firstDM != nullptr) { unsigned int extrusions = 0, retractions = 0; // bitmaps of extruding and retracting drives - const size_t numAxes = reprap.GetGCodes().GetNumAxes(); + const size_t numAxes = reprap.GetGCodes().GetTotalAxes(); for (size_t i = 0; i < DRIVES; ++i) { DriveMovement& dm = ddm[i]; @@ -1376,7 +1375,7 @@ void DDA::StopDrive(size_t drive) { endPoint[drive] -= dm.GetNetStepsLeft(); dm.state = DMState::idle; - if (drive < reprap.GetGCodes().GetNumAxes()) + if (drive < reprap.GetGCodes().GetTotalAxes()) { endCoordinatesValid = false; // the XYZ position is no longer valid } diff --git a/src/Movement/DDA.h b/src/Movement/DDA.h index ecb2f632..49f21bb0 100644 --- a/src/Movement/DDA.h +++ b/src/Movement/DDA.h @@ -91,7 +91,7 @@ public: #if DDA_LOG_PROBE_CHANGES static const size_t MaxLoggedProbePositions = 40; static size_t numLoggedProbePositions; - static int32_t loggedProbePositions[CART_AXES * MaxLoggedProbePositions]; + static int32_t loggedProbePositions[XYZ_AXES * MaxLoggedProbePositions]; #endif private: diff --git a/src/Movement/DeltaProbe.cpp b/src/Movement/DeltaProbe.cpp deleted file mode 100644 index 37a2f0d8..00000000 --- a/src/Movement/DeltaProbe.cpp +++ /dev/null @@ -1,139 +0,0 @@ -/* - * DeltaProbe.cpp - * - * Created on: 20 Apr 2015 - * Author: David - */ - -#include "DeltaProbe.h" -#include "DDA.h" -#include "Platform.h" -#include "RepRap.h" - -// Set up to probe -bool DeltaProbe::Init(float frequency, float amplitude, float rate, float height) -{ -debugPrintf("Start probe f=%.1f a=%.2f r=%.2f h=%.1f\n", frequency, amplitude, rate, height); - // Sanity check the inputs (we check the max amplitude later) - if (frequency < 50.0 || frequency > 1000.0 || amplitude < 0.02 || rate < 0.1 || rate > 10.0 || height < 0.5) - { - return false; - } - -debugPrintf("ok so far\n"); - // Calculate the number of steps for the peak to peak amplitude - const float zRate = reprap.GetPlatform().DriveStepsPerUnit(Z_AXIS); - normalSteps = (size_t)(amplitude * zRate); - if (normalSteps > MaxSteps) - { - return false; - } - -debugPrintf("normalSteps=%u\n", normalSteps); - // Build the tables of step times for sinusoidal motion - const float recipOmega = (float)DDA::stepClockRate/(frequency * 2.0 * PI); - - for (size_t i = 0; i < normalSteps - 1; ++i) - { - normalStepTable[i] = acos(1.0 - (float)(2 * (i + 1))/(float)normalSteps) * recipOmega; - } - - for (size_t i = 0; i < normalSteps; ++i) - { - incStepTable[i] = acos(1.0 - (float)(2 * (i + 1))/(float)(normalSteps + 1)) * recipOmega; - } - - halfCycleTime = (uint32_t)((float)DDA::stepClockRate/(2.0 * frequency)); - incStepTable[normalSteps] = normalStepTable[normalSteps - 1] = halfCycleTime; - - halfCyclesPerIncrement = 2 * (unsigned int)((frequency / (rate * zRate)) + 0.5); - if (halfCyclesPerIncrement < 4) - { - halfCyclesPerIncrement = 4; - } - maxIncrements = height * zRate; - -const float peakAccel = fsquare(2.0 * PI * frequency) * amplitude * 0.5; -debugPrintf("halfCycleTime=%u halfCyclesPerIncrement=%u peak accel=%.1f\n", halfCycleTime, halfCyclesPerIncrement, peakAccel); -debugPrintf("normalTable="); -for (unsigned int i = 0; i < normalSteps; ++i) -{ - debugPrintf(" %u", normalStepTable[i]); -} -debugPrintf(" incStepTable="); -for (unsigned int i = 0; i <= normalSteps; ++i) -{ - debugPrintf(" %u", incStepTable[i]); -} -debugPrintf("\n"); - return true; -} - -// Start probing, and return the time that the next step is due -uint32_t DeltaProbe::Start() -{ - // Initialise the dynamic values - stepsDone = 0; - halfCycleCount = 0; - numIncrements = 0; - incrementing = false; - state = State::normal; - return normalStepTable[0]; -} - -bool DeltaProbe::GetDirection() const -{ - return (halfCycleCount & 1) ? FORWARDS : BACKWARDS; -} - -// Calculate the next step time. Returns 0xFFFFFFFF to stop. -uint32_t DeltaProbe::CalcNextStepTime() -{ - if (state == State::stopped || state == State::overran) - { - return 0xFFFFFFFF; - } - - ++stepsDone; - if (stepsDone == ((incrementing) ? normalSteps + 1 : normalSteps)) - { - stepsDone = 0; - ++halfCycleCount; - if (state == State::stopping && (halfCycleCount & 1) == 0) - { - state = State::stopped; - return 0xFFFFFFFF; - } - - if (incrementing) - { - ++numIncrements; - incrementing = false; - } - - if (halfCycleCount == halfCyclesPerIncrement) - { - if (numIncrements == maxIncrements) - { - state = State::overran; // another increment is due, but we have already gone down as far as we were asked to - return 0xFFFFFFFF; - } - halfCycleCount = 0; - incrementing = true; - } - } - - return (incrementing) - ? (halfCyclesPerIncrement * numIncrements * halfCycleTime) + incStepTable[stepsDone] - : (halfCyclesPerIncrement * numIncrements * halfCycleTime) + normalStepTable[stepsDone]; -} - -void DeltaProbe::Trigger() -{ - if (state == State::normal) - { - state = State::stopping; - } -} - -// End diff --git a/src/Movement/DeltaProbe.h b/src/Movement/DeltaProbe.h deleted file mode 100644 index 90b2fb49..00000000 --- a/src/Movement/DeltaProbe.h +++ /dev/null @@ -1,46 +0,0 @@ -/* - * DeltaProbe.h - * - * Created on: 20 Apr 2015 - * Author: David - */ - -#ifndef DELTAPROBE_H_ -#define DELTAPROBE_H_ - -#include "RepRapFirmware.h" - -// Class to hold the parameters for my new Z probing method -class DeltaProbe -{ - enum class State { normal, stopping, stopped, overran }; - - // Fixed parameters - static const unsigned int MaxSteps = 30; // 15 corresponds to 0.375mm p-p movement @ 80 steps/mm - - // Static parameters, set up before we start probing and unchanged during probing - unsigned int normalSteps; // the number of steps we use to achieve the requested amplitude - unsigned int halfCyclesPerIncrement; // how many half cycles between lowering the head by 1 step - unsigned int maxIncrements; // max number of steps we lower the head - uint32_t halfCycleTime; // how many interrupt clocks per quarter cycle - uint32_t normalStepTable[MaxSteps]; // table of step times for the first half cycle, in interrupt clocks from start - uint32_t incStepTable[MaxSteps + 1]; // table of step times for the first half cycle, when we are moving down a step - - // Dynamic parameters, to track the progress of the probe - unsigned int stepsDone; // how many steps since the start of this quarter cycle - unsigned int halfCycleCount; // how many quarter cycles since we started or lowered the head - unsigned int numIncrements; // how many steps we have lowered the head since we started - bool incrementing; // true if we are lowering the head 2 step in this half cycle - State state; // what state the probe is in - -public: - bool Init(float frequency, float amplitude, float rate, float height); // Get ready to probe - uint32_t Start(); // start the process, return the next step time - bool GetDirection() const; // get the direction for the current step - uint32_t CalcNextStepTime(); // calculate when the next step is due - void Trigger(); // cease probing - bool Finished() const { return state == State::stopped || state == State::overran; } - bool Overran() const { return state == State::overran; } -}; - -#endif /* DELTAPROBE_H_ */ diff --git a/src/Movement/DriveMovement.cpp b/src/Movement/DriveMovement.cpp index f9b6061b..e208443a 100644 --- a/src/Movement/DriveMovement.cpp +++ b/src/Movement/DriveMovement.cpp @@ -85,7 +85,7 @@ void DriveMovement::PrepareExtruder(const DDA& dda, const PrepParams& params, bo mp.cart.twoCsquaredTimesMmPerStepDivA = (uint64_t)(((float)DDA::stepClockRate * (float)DDA::stepClockRate)/(stepsPerMm * dda.acceleration)) * 2; // Calculate the pressure advance parameter - const float compensationTime = (doCompensation && dv > 0.0) ? reprap.GetPlatform().GetPressureAdvance(drive - reprap.GetGCodes().GetNumAxes()) : 0.0; + const float compensationTime = (doCompensation && dv > 0.0) ? reprap.GetPlatform().GetPressureAdvance(drive - reprap.GetGCodes().GetTotalAxes()) : 0.0; const uint32_t compensationClocks = (uint32_t)(compensationTime * DDA::stepClockRate); // Calculate the net total step count to allow for compensation. It may be negative. diff --git a/src/Movement/Kinematics/CartesianKinematics.cpp b/src/Movement/Kinematics/CartesianKinematics.cpp index a6a75994..5aa8a1f9 100644 --- a/src/Movement/Kinematics/CartesianKinematics.cpp +++ b/src/Movement/Kinematics/CartesianKinematics.cpp @@ -18,9 +18,9 @@ const char *CartesianKinematics::GetName(bool forStatusReport) const } // Convert Cartesian coordinates to motor coordinates -bool CartesianKinematics::CartesianToMotorSteps(const float machinePos[], const float stepsPerMm[], size_t numAxes, int32_t motorPos[]) const +bool CartesianKinematics::CartesianToMotorSteps(const float machinePos[], const float stepsPerMm[], size_t numVisibleAxes, size_t numTotalAxes, int32_t motorPos[]) const { - for (size_t axis = 0; axis < numAxes; ++axis) + for (size_t axis = 0; axis < numVisibleAxes; ++axis) { motorPos[axis] = (int32_t)roundf(machinePos[axis] * stepsPerMm[axis]); } @@ -28,10 +28,10 @@ bool CartesianKinematics::CartesianToMotorSteps(const float machinePos[], const } // Convert motor coordinates to machine coordinates. Used after homing and after individual motor moves. -void CartesianKinematics::MotorStepsToCartesian(const int32_t motorPos[], const float stepsPerMm[], size_t numDrives, float machinePos[]) const +void CartesianKinematics::MotorStepsToCartesian(const int32_t motorPos[], const float stepsPerMm[], size_t numVisibleAxes, size_t numTotalAxes, float machinePos[]) const { - // Convert all axes and the extruders - for (size_t drive = 0; drive < numDrives; ++drive) + // Convert all axes + for (size_t drive = 0; drive < numVisibleAxes; ++drive) { machinePos[drive] = motorPos[drive]/stepsPerMm[drive]; } diff --git a/src/Movement/Kinematics/CartesianKinematics.h b/src/Movement/Kinematics/CartesianKinematics.h index 58a4397b..d2bd6118 100644 --- a/src/Movement/Kinematics/CartesianKinematics.h +++ b/src/Movement/Kinematics/CartesianKinematics.h @@ -17,8 +17,8 @@ public: // Overridden base class functions. See Kinematics.h for descriptions. const char *GetName(bool forStatusReport) const override; - bool CartesianToMotorSteps(const float machinePos[], const float stepsPerMm[], size_t numAxes, int32_t motorPos[]) const override; - void MotorStepsToCartesian(const int32_t motorPos[], const float stepsPerMm[], size_t numDrives, float machinePos[]) const override; + bool CartesianToMotorSteps(const float machinePos[], const float stepsPerMm[], size_t numVisibleAxes, size_t numTotalAxes, int32_t motorPos[]) const override; + void MotorStepsToCartesian(const int32_t motorPos[], const float stepsPerMm[], size_t numVisibleAxes, size_t numTotalAxes, float machinePos[]) const override; bool SupportsAutoCalibration() const override { return false; } }; diff --git a/src/Movement/Kinematics/CoreBaseKinematics.cpp b/src/Movement/Kinematics/CoreBaseKinematics.cpp index 1054d285..15013557 100644 --- a/src/Movement/Kinematics/CoreBaseKinematics.cpp +++ b/src/Movement/Kinematics/CoreBaseKinematics.cpp @@ -10,16 +10,16 @@ CoreBaseKinematics::CoreBaseKinematics(KinematicsType t) : Kinematics(t) { - for (size_t axis = 0; axis < CART_AXES; ++axis) + for (size_t axis = 0; axis < XYZ_AXES; ++axis) { axisFactors[axis] = 1.0; } } // Convert Cartesian coordinates to motor coordinates -bool CoreBaseKinematics::CartesianToMotorSteps(const float machinePos[], const float stepsPerMm[], size_t numAxes, int32_t motorPos[]) const +bool CoreBaseKinematics::CartesianToMotorSteps(const float machinePos[], const float stepsPerMm[], size_t numVisibleAxes, size_t numTotalAxes, int32_t motorPos[]) const { - for (size_t axis = 0; axis < numAxes; ++axis) + for (size_t axis = 0; axis < numVisibleAxes; ++axis) { motorPos[axis] = (int32_t)roundf(MotorFactor(axis, machinePos) * stepsPerMm[axis]); } @@ -28,12 +28,12 @@ bool CoreBaseKinematics::CartesianToMotorSteps(const float machinePos[], const f // Set the parameters from a M665, M666 or M669 command // Return true if we changed any parameters. Set 'error' true if there was an error, otherwise leave it alone. -bool CoreBaseKinematics::SetOrReportParameters(unsigned int mCode, GCodeBuffer& gb, StringRef& reply, bool& error) /*override*/ +bool CoreBaseKinematics::Configure(unsigned int mCode, GCodeBuffer& gb, StringRef& reply, bool& error) /*override*/ { if (mCode == 667) { bool seen = false; - for (size_t axis = 0; axis < CART_AXES; ++axis) + for (size_t axis = 0; axis < XYZ_AXES; ++axis) { if (gb.Seen(GCodes::axisLetters[axis])) { @@ -44,7 +44,7 @@ bool CoreBaseKinematics::SetOrReportParameters(unsigned int mCode, GCodeBuffer& if (!seen && !gb.Seen('S')) { reply.printf("Printer mode is %s with axis factors", GetName()); - for (size_t axis = 0; axis < CART_AXES; ++axis) + for (size_t axis = 0; axis < XYZ_AXES; ++axis) { reply.catf(" %c:%f", GCodes::axisLetters[axis], axisFactors[axis]); } @@ -53,7 +53,7 @@ bool CoreBaseKinematics::SetOrReportParameters(unsigned int mCode, GCodeBuffer& } else { - return Kinematics::SetOrReportParameters(mCode, gb, reply, error); + return Kinematics::Configure(mCode, gb, reply, error); } } diff --git a/src/Movement/Kinematics/CoreBaseKinematics.h b/src/Movement/Kinematics/CoreBaseKinematics.h index c532f0ba..1d684830 100644 --- a/src/Movement/Kinematics/CoreBaseKinematics.h +++ b/src/Movement/Kinematics/CoreBaseKinematics.h @@ -16,8 +16,8 @@ public: CoreBaseKinematics(KinematicsType t); // Overridden base class functions. See Kinematics.h for descriptions. - bool CartesianToMotorSteps(const float machinePos[], const float stepsPerMm[], size_t numAxes, int32_t motorPos[]) const override final; - bool SetOrReportParameters(unsigned int mCode, GCodeBuffer& gb, StringRef& reply, bool& error) override final; + bool CartesianToMotorSteps(const float machinePos[], const float stepsPerMm[], size_t numVisibleAxes, size_t numTotalAxes, int32_t motorPos[]) const override final; + bool Configure(unsigned int mCode, GCodeBuffer& gb, StringRef& reply, bool& error) override final; bool SupportsAutoCalibration() const override final { return false; } protected: @@ -25,7 +25,7 @@ protected: // The default implementation just returns directionVector[drive] but this needs to be overridden for CoreXY and CoreXZ printers. virtual float MotorFactor(size_t drive, const float directionVector[]) const = 0; - float axisFactors[CART_AXES]; + float axisFactors[XYZ_AXES]; }; #endif /* SRC_MOVEMENT_KINEMATICS_COREBASEKINEMATICS_H_ */ diff --git a/src/Movement/Kinematics/CoreXYKinematics.cpp b/src/Movement/Kinematics/CoreXYKinematics.cpp index 583b370d..55258509 100644 --- a/src/Movement/Kinematics/CoreXYKinematics.cpp +++ b/src/Movement/Kinematics/CoreXYKinematics.cpp @@ -18,7 +18,7 @@ const char *CoreXYKinematics::GetName(bool forStatusReport) const } // Convert motor coordinates to machine coordinates. Used after homing and after individual motor moves. -void CoreXYKinematics::MotorStepsToCartesian(const int32_t motorPos[], const float stepsPerMm[], size_t numDrives, float machinePos[]) const +void CoreXYKinematics::MotorStepsToCartesian(const int32_t motorPos[], const float stepsPerMm[], size_t numVisibleAxes, size_t numTotalAxes, float machinePos[]) const { // Convert the axes machinePos[X_AXIS] = ((motorPos[X_AXIS] * stepsPerMm[Y_AXIS]) - (motorPos[Y_AXIS] * stepsPerMm[X_AXIS])) @@ -27,8 +27,8 @@ void CoreXYKinematics::MotorStepsToCartesian(const int32_t motorPos[], const flo /(2 * axisFactors[Y_AXIS] * stepsPerMm[X_AXIS] * stepsPerMm[Y_AXIS]); machinePos[Z_AXIS] = motorPos[Z_AXIS]/stepsPerMm[Z_AXIS]; - // Convert any additional axes and the extruders - for (size_t drive = MIN_AXES; drive < numDrives; ++drive) + // Convert any additional axes + for (size_t drive = XYZ_AXES; drive < numVisibleAxes; ++drive) { machinePos[drive] = motorPos[drive]/stepsPerMm[drive]; } diff --git a/src/Movement/Kinematics/CoreXYKinematics.h b/src/Movement/Kinematics/CoreXYKinematics.h index b68fc3cc..d9166904 100644 --- a/src/Movement/Kinematics/CoreXYKinematics.h +++ b/src/Movement/Kinematics/CoreXYKinematics.h @@ -17,7 +17,7 @@ public: // Overridden base class functions. See Kinematics.h for descriptions. const char *GetName(bool forStatusReport) const override; - void MotorStepsToCartesian(const int32_t motorPos[], const float stepsPerMm[], size_t numDrives, float machinePos[]) const override; + void MotorStepsToCartesian(const int32_t motorPos[], const float stepsPerMm[], size_t numVisibleAxes, size_t numTotalAxes, float machinePos[]) const override; protected: float MotorFactor(size_t drive, const float directionVector[]) const override; diff --git a/src/Movement/Kinematics/CoreXZKinematics.cpp b/src/Movement/Kinematics/CoreXZKinematics.cpp index a72a49a5..f9baf985 100644 --- a/src/Movement/Kinematics/CoreXZKinematics.cpp +++ b/src/Movement/Kinematics/CoreXZKinematics.cpp @@ -18,7 +18,7 @@ const char *CoreXZKinematics::GetName(bool forStatusReport) const } // Convert motor coordinates to machine coordinates. Used after homing and after individual motor moves. -void CoreXZKinematics::MotorStepsToCartesian(const int32_t motorPos[], const float stepsPerMm[], size_t numDrives, float machinePos[]) const +void CoreXZKinematics::MotorStepsToCartesian(const int32_t motorPos[], const float stepsPerMm[], size_t numVisibleAxes, size_t numTotalAxes, float machinePos[]) const { machinePos[X_AXIS] = ((motorPos[X_AXIS] * stepsPerMm[Z_AXIS]) - (motorPos[Z_AXIS] * stepsPerMm[X_AXIS])) /(2 * axisFactors[X_AXIS] * stepsPerMm[X_AXIS] * stepsPerMm[Z_AXIS]); @@ -26,8 +26,8 @@ void CoreXZKinematics::MotorStepsToCartesian(const int32_t motorPos[], const flo machinePos[Z_AXIS] = ((motorPos[X_AXIS] * stepsPerMm[Z_AXIS]) + (motorPos[Z_AXIS] * stepsPerMm[X_AXIS])) /(2 * axisFactors[Z_AXIS] * stepsPerMm[X_AXIS] * stepsPerMm[Z_AXIS]); - // Convert any additional axes and the extruders - for (size_t drive = MIN_AXES; drive < numDrives; ++drive) + // Convert any additional axes linearly + for (size_t drive = XYZ_AXES; drive < numVisibleAxes; ++drive) { machinePos[drive] = motorPos[drive]/stepsPerMm[drive]; } diff --git a/src/Movement/Kinematics/CoreXZKinematics.h b/src/Movement/Kinematics/CoreXZKinematics.h index 1bdb3074..5809f9f3 100644 --- a/src/Movement/Kinematics/CoreXZKinematics.h +++ b/src/Movement/Kinematics/CoreXZKinematics.h @@ -17,7 +17,7 @@ public: // Overridden base class functions. See Kinematics.h for descriptions. const char *GetName(bool forStatusReport) const override; - void MotorStepsToCartesian(const int32_t motorPos[], const float stepsPerMm[], size_t numDrives, float machinePos[]) const override; + void MotorStepsToCartesian(const int32_t motorPos[], const float stepsPerMm[], size_t numVisibleAxes, size_t numTotalAxes, float machinePos[]) const override; uint16_t AxesToHomeBeforeProbing() const override { return (1 << X_AXIS) | (1 << Y_AXIS) | (1 << Z_AXIS); } protected: diff --git a/src/Movement/Kinematics/Kinematics.cpp b/src/Movement/Kinematics/Kinematics.cpp index 139a283a..058aef71 100644 --- a/src/Movement/Kinematics/Kinematics.cpp +++ b/src/Movement/Kinematics/Kinematics.cpp @@ -28,7 +28,7 @@ Kinematics::Kinematics(KinematicsType t, float segsPerSecond, float minSegLength // Set or report the parameters from a M665, M666 or M669 command // This is the fallback function for when the derived class doesn't use the specified M-code -bool Kinematics::SetOrReportParameters(unsigned int mCode, GCodeBuffer& gb, StringRef& reply, bool& error) +bool Kinematics::Configure(unsigned int mCode, GCodeBuffer& gb, StringRef& reply, bool& error) { reply.printf("M%u parameters do not apply to %s kinematics", mCode, GetName()); error = true; @@ -45,10 +45,10 @@ bool Kinematics::IsReachable(float x, float y) const // Limit the Cartesian position that the user wants to move to // This default implementation just applies the rectangular limits set up by M208 to those axes that have been homed. -void Kinematics::LimitPosition(float coords[], size_t numAxes, uint16_t axesHomed) const +void Kinematics::LimitPosition(float coords[], size_t numVisibleAxes, uint16_t axesHomed) const { const Platform& platform = reprap.GetPlatform(); - for (size_t axis = 0; axis < numAxes; axis++) + for (size_t axis = 0; axis < numVisibleAxes; axis++) { if ((axesHomed & (1 << axis)) != 0) { diff --git a/src/Movement/Kinematics/Kinematics.h b/src/Movement/Kinematics/Kinematics.h index 7cec8338..75f5b327 100644 --- a/src/Movement/Kinematics/Kinematics.h +++ b/src/Movement/Kinematics/Kinematics.h @@ -44,11 +44,11 @@ public: // Set or report the parameters from a M665, M666 or M669 command // If 'mCode' is an M-code used to set parameters for the current kinematics (which should only ever be 665, 666, 667 or 669) - // then search for parameters used to configure the current kinematics. if any are found, perform appropriate actions and return true. + // then search for parameters used to configure the current kinematics. If any are found, perform appropriate actions and return true. // If errors were discovered while processing parameters, put an appropriate error message in 'reply' and set 'error' to true. // If no relevant parameters are found, print the existing ones to 'reply' and return false. - // if 'mCode' does not apply to this kinematics, call the base class version of this function, which will print a suitable error message. - virtual bool SetOrReportParameters(unsigned int mCode, GCodeBuffer& gb, StringRef& reply, bool& error); + // If 'mCode' does not apply to this kinematics, call the base class version of this function, which will print a suitable error message. + virtual bool Configure(unsigned int mCode, GCodeBuffer& gb, StringRef& reply, bool& error); // Convert Cartesian coordinates to motor positions measured in steps from reference position // 'machinePos' is a set of axis and extruder positions to convert @@ -56,14 +56,14 @@ public: // 'numAxes' is the number of machine axes to convert, which will always be at least 3 // 'motorPos' is the output vector of motor positions // Return true if successful, false if we were unable to convert - virtual bool CartesianToMotorSteps(const float machinePos[], const float stepsPerMm[], size_t numAxes, int32_t motorPos[]) const = 0; + virtual bool CartesianToMotorSteps(const float machinePos[], const float stepsPerMm[], size_t numVisibleAxes, size_t numTotalAxes, int32_t motorPos[]) const = 0; // Convert motor positions (measured in steps from reference position) to Cartesian coordinates // 'motorPos' is the input vector of motor positions // 'stepsPerMm' is as configured in M92. On a Scara or polar machine this would actually be steps per degree. // 'numDrives' is the number of machine drives to convert, which will always be at least 3 // 'machinePos' is the output set of converted axis and extruder positions - virtual void MotorStepsToCartesian(const int32_t motorPos[], const float stepsPerMm[], size_t numDrives, float machinePos[]) const = 0; + virtual void MotorStepsToCartesian(const int32_t motorPos[], const float stepsPerMm[], size_t numVisibleAxes, size_t numTotalAxes, float machinePos[]) const = 0; // Return true if the kinematics supports auto calibration based on bed probing. // Normally returns false, but overridden for delta kinematics. @@ -91,7 +91,7 @@ public: // Limit the Cartesian position that the user wants to move to // The default implementation just applies the rectangular limits set up by M208 to those axes that have been homed. - virtual void LimitPosition(float coords[], size_t numAxes, uint16_t axesHomed) const; + virtual void LimitPosition(float coords[], size_t numVisibleAxes, uint16_t axesHomed) const; // Return the set of axes that must have been homed before bed probing is allowed // The default implementation requires just X and Y, but some kinematics require additional axes to be homed (e.g. delta, CoreXZ) @@ -100,10 +100,16 @@ public: // Return the initial Cartesian coordinates we assume after switching to this kinematics virtual void GetAssumedInitialPosition(size_t numAxes, float positions[]) const; - // Override this one if any axes do not use the line motion (e.g. for segmentation-free delta motion) + // Override this one if any axes do not use the linear motion code (e.g. for segmentation-free delta motion) virtual MotionType GetMotionType(size_t axis) const { return MotionType::linear; } - // Override the virtual destructor if your constructor allocates any dynamic memory + // Override this if the number of homing buttons (excluding the home all button) is not the same as the number of visible axes (e.g. on a delta printer) + virtual size_t NumHomingButtons(size_t numVisibleAxes) const { return numVisibleAxes; } + + // Override this if the homing buttons are not named after the axes (e.g. SCARA printer) + virtual const char* HomingButtonNames() const { return "XYZUVW"; } + + // Override this virtual destructor if your constructor allocates any dynamic memory virtual ~Kinematics() { } // Factory function to create a particular kinematics object and return a pointer to it. diff --git a/src/Movement/Kinematics/LinearDeltaKinematics.cpp b/src/Movement/Kinematics/LinearDeltaKinematics.cpp index 6e084be0..c109134c 100644 --- a/src/Movement/Kinematics/LinearDeltaKinematics.cpp +++ b/src/Movement/Kinematics/LinearDeltaKinematics.cpp @@ -131,16 +131,16 @@ void LinearDeltaKinematics::InverseTransform(float Ha, float Hb, float Hc, float } // Convert Cartesian coordinates to motor steps -bool LinearDeltaKinematics::CartesianToMotorSteps(const float machinePos[], const float stepsPerMm[], size_t numAxes, int32_t motorPos[]) const +bool LinearDeltaKinematics::CartesianToMotorSteps(const float machinePos[], const float stepsPerMm[], size_t numVisibleAxes, size_t numTotalAxes, int32_t motorPos[]) const { //TODO return false if we can't transform the position - for (size_t axis = 0; axis < min<size_t>(numAxes, DELTA_AXES); ++axis) + for (size_t axis = 0; axis < min<size_t>(numVisibleAxes, DELTA_AXES); ++axis) { motorPos[axis] = (int32_t)roundf(Transform(machinePos, axis) * stepsPerMm[axis]); } // Transform any additional axes linearly - for (size_t axis = DELTA_AXES; axis < numAxes; ++axis) + for (size_t axis = DELTA_AXES; axis < numVisibleAxes; ++axis) { motorPos[axis] = (int32_t)roundf(machinePos[axis] * stepsPerMm[axis]); } @@ -148,12 +148,12 @@ bool LinearDeltaKinematics::CartesianToMotorSteps(const float machinePos[], cons } // Convert motor coordinates to machine coordinates. Used after homing and after individual motor moves. -void LinearDeltaKinematics::MotorStepsToCartesian(const int32_t motorPos[], const float stepsPerMm[], size_t numDrives, float machinePos[]) const +void LinearDeltaKinematics::MotorStepsToCartesian(const int32_t motorPos[], const float stepsPerMm[], size_t numVisibleAxes, size_t numTotalAxes, float machinePos[]) const { InverseTransform(motorPos[A_AXIS]/stepsPerMm[A_AXIS], motorPos[B_AXIS]/stepsPerMm[B_AXIS], motorPos[C_AXIS]/stepsPerMm[C_AXIS], machinePos); // Convert any additional axes linearly - for (size_t drive = DELTA_AXES; drive < numDrives; ++drive) + for (size_t drive = DELTA_AXES; drive < numVisibleAxes; ++drive) { machinePos[drive] = motorPos[drive]/stepsPerMm[drive]; } @@ -166,7 +166,7 @@ bool LinearDeltaKinematics::IsReachable(float x, float y) const } // Limit the Cartesian position that the user wants to move to -void LinearDeltaKinematics::LimitPosition(float coords[], size_t numAxes, uint16_t axesHomed) const +void LinearDeltaKinematics::LimitPosition(float coords[], size_t numVisibleAxes, uint16_t axesHomed) const { const uint16_t allAxes = (1u << X_AXIS) | (1u << Y_AXIS) | (1u << Z_AXIS); if ((axesHomed & allAxes) == allAxes) @@ -541,7 +541,7 @@ float LinearDeltaKinematics::GetTiltCorrection(size_t axis) const // Set the parameters from a M665, M666 or M669 command // Return true if we changed any parameters. Set 'error' true if there was an error, otherwise leave it alone. -bool LinearDeltaKinematics::SetOrReportParameters(unsigned int mCode, GCodeBuffer& gb, StringRef& reply, bool& error) /*override*/ +bool LinearDeltaKinematics::Configure(unsigned int mCode, GCodeBuffer& gb, StringRef& reply, bool& error) /*override*/ { switch(mCode) { @@ -643,7 +643,7 @@ bool LinearDeltaKinematics::SetOrReportParameters(unsigned int mCode, GCodeBuffe } default: - return Kinematics::SetOrReportParameters(mCode, gb, reply, error); + return Kinematics::Configure(mCode, gb, reply, error); } } diff --git a/src/Movement/Kinematics/LinearDeltaKinematics.h b/src/Movement/Kinematics/LinearDeltaKinematics.h index 1bb0ca4f..54a8371b 100644 --- a/src/Movement/Kinematics/LinearDeltaKinematics.h +++ b/src/Movement/Kinematics/LinearDeltaKinematics.h @@ -33,19 +33,20 @@ public: // Overridden base class functions. See Kinematics.h for descriptions. const char *GetName(bool forStatusReport) const override; - bool SetOrReportParameters(unsigned int mCode, GCodeBuffer& gb, StringRef& reply, bool& error) override; - bool CartesianToMotorSteps(const float machinePos[], const float stepsPerMm[], size_t numAxes, int32_t motorPos[]) const override; - void MotorStepsToCartesian(const int32_t motorPos[], const float stepsPerMm[], size_t numDrives, float machinePos[]) const override; + bool Configure(unsigned int mCode, GCodeBuffer& gb, StringRef& reply, bool& error) override; + bool CartesianToMotorSteps(const float machinePos[], const float stepsPerMm[], size_t numVisibleAxes, size_t numTotalAxes, int32_t motorPos[]) const override; + void MotorStepsToCartesian(const int32_t motorPos[], const float stepsPerMm[], size_t numVisibleAxes, size_t numTotalAxes, float machinePos[]) const override; bool SupportsAutoCalibration() const override { return true; } void DoAutoCalibration(size_t numFactors, const RandomProbePointSet& probePoints, StringRef& reply) override; void SetCalibrationDefaults() override { Init(); } bool WriteCalibrationParameters(FileStore *f) const override; float GetTiltCorrection(size_t axis) const override; bool IsReachable(float x, float y) const override; - void LimitPosition(float coords[], size_t numAxes, uint16_t axesHomed) const override; + void LimitPosition(float coords[], size_t numVisibleAxes, uint16_t axesHomed) const override; void GetAssumedInitialPosition(size_t numAxes, float positions[]) const override; uint16_t AxesToHomeBeforeProbing() const override { return (1 << X_AXIS) | (1 << Y_AXIS) | (1 << Z_AXIS); } MotionType GetMotionType(size_t axis) const override; + size_t NumHomingButtons(size_t numVisibleAxes) const override { return 0; } // Public functions specific to this class float GetDiagonalSquared() const { return D2; } diff --git a/src/Movement/Kinematics/ScaraKinematics.cpp b/src/Movement/Kinematics/ScaraKinematics.cpp index c6b29f11..f9b67772 100644 --- a/src/Movement/Kinematics/ScaraKinematics.cpp +++ b/src/Movement/Kinematics/ScaraKinematics.cpp @@ -27,7 +27,7 @@ const char *ScaraKinematics::GetName(bool forStatusReport) const // Convert Cartesian coordinates to motor coordinates // In the following, theta is the proximal arm angle relative to the X axis, psi is the distal arm angle relative to the X axis -bool ScaraKinematics::CartesianToMotorSteps(const float machinePos[], const float stepsPerMm[], size_t numAxes, int32_t motorPos[]) const +bool ScaraKinematics::CartesianToMotorSteps(const float machinePos[], const float stepsPerMm[], size_t numVisibleAxes, size_t numTotalAxes, int32_t motorPos[]) const { // No need to limit x,y to reachable positions here, we already did that in class GCodes const float x = machinePos[X_AXIS]; @@ -85,12 +85,18 @@ bool ScaraKinematics::CartesianToMotorSteps(const float machinePos[], const floa motorPos[X_AXIS] = theta * RadiansToDegrees * stepsPerMm[X_AXIS]; motorPos[Y_AXIS] = (psi * RadiansToDegrees * stepsPerMm[Y_AXIS]) - (crosstalk[0] * motorPos[X_AXIS]); motorPos[Z_AXIS] = (int32_t)((machinePos[Z_AXIS] * stepsPerMm[Z_AXIS]) - (motorPos[X_AXIS] * crosstalk[1]) - (motorPos[Y_AXIS] * crosstalk[2])); + + // Transform any additional axes linearly + for (size_t axis = XYZ_AXES; axis < numVisibleAxes; ++axis) + { + motorPos[axis] = (int32_t)roundf(machinePos[axis] * stepsPerMm[axis]); + } return true; } // Convert motor coordinates to machine coordinates. Used after homing and after individual motor moves. // For Scara, the X and Y components of stepsPerMm are actually steps per degree angle. -void ScaraKinematics::MotorStepsToCartesian(const int32_t motorPos[], const float stepsPerMm[], size_t numDrives, float machinePos[]) const +void ScaraKinematics::MotorStepsToCartesian(const int32_t motorPos[], const float stepsPerMm[], size_t numVisibleAxes, size_t numTotalAxes, float machinePos[]) const { const float arm1Angle = ((float)motorPos[X_AXIS]/stepsPerMm[X_AXIS]) * DegreesToRadians; const float arm2Angle = (((float)motorPos[Y_AXIS] + ((float)motorPos[X_AXIS] * crosstalk[0]))/stepsPerMm[Y_AXIS]) * DegreesToRadians; @@ -100,11 +106,17 @@ void ScaraKinematics::MotorStepsToCartesian(const int32_t motorPos[], const floa // On some machines (e.g. Helios), the X and/or Y arm motors also affect the Z height machinePos[Z_AXIS] = ((float)motorPos[Z_AXIS] + ((float)motorPos[X_AXIS] * crosstalk[1]) + ((float)motorPos[Y_AXIS] * crosstalk[2]))/stepsPerMm[Z_AXIS]; + + // Convert any additional axes linearly + for (size_t drive = XYZ_AXES; drive < numVisibleAxes; ++drive) + { + machinePos[drive] = motorPos[drive]/stepsPerMm[drive]; + } } // Set the parameters from a M665, M666 or M669 command // Return true if we changed any parameters. Set 'error' true if there was an error, otherwise leave it alone. -bool ScaraKinematics::SetOrReportParameters(unsigned int mCode, GCodeBuffer& gb, StringRef& reply, bool& error) /*override*/ +bool ScaraKinematics::Configure(unsigned int mCode, GCodeBuffer& gb, StringRef& reply, bool& error) /*override*/ { if (mCode == 669) { @@ -143,7 +155,7 @@ bool ScaraKinematics::SetOrReportParameters(unsigned int mCode, GCodeBuffer& gb, } else { - return Kinematics::SetOrReportParameters(mCode, gb, reply, error); + return Kinematics::Configure(mCode, gb, reply, error); } } @@ -158,7 +170,7 @@ bool ScaraKinematics::IsReachable(float x, float y) const // Limit the Cartesian position that the user wants to move to // TODO take account of arm angle limits -void ScaraKinematics::LimitPosition(float coords[], size_t numAxes, uint16_t axesHomed) const +void ScaraKinematics::LimitPosition(float coords[], size_t numVisibleAxes, uint16_t axesHomed) const { float& x = coords[X_AXIS]; float& y = coords[Y_AXIS]; diff --git a/src/Movement/Kinematics/ScaraKinematics.h b/src/Movement/Kinematics/ScaraKinematics.h index 4c22c832..8e0c13d8 100644 --- a/src/Movement/Kinematics/ScaraKinematics.h +++ b/src/Movement/Kinematics/ScaraKinematics.h @@ -27,13 +27,14 @@ public: // Overridden base class functions. See Kinematics.h for descriptions. const char *GetName(bool forStatusReport) const override; - bool SetOrReportParameters(unsigned int mCode, GCodeBuffer& gb, StringRef& reply, bool& error) override; - bool CartesianToMotorSteps(const float machinePos[], const float stepsPerMm[], size_t numAxes, int32_t motorPos[]) const override; - void MotorStepsToCartesian(const int32_t motorPos[], const float stepsPerMm[], size_t numDrives, float machinePos[]) const override; + bool Configure(unsigned int mCode, GCodeBuffer& gb, StringRef& reply, bool& error) override; + bool CartesianToMotorSteps(const float machinePos[], const float stepsPerMm[], size_t numVisibleAxes, size_t numTotalAxes, int32_t motorPos[]) const override; + void MotorStepsToCartesian(const int32_t motorPos[], const float stepsPerMm[], size_t numVisibleAxes, size_t numTotalAxes, float machinePos[]) const override; bool SupportsAutoCalibration() const override { return false; } bool IsReachable(float x, float y) const override; void LimitPosition(float position[], size_t numAxes, uint16_t axesHomed) const override; void GetAssumedInitialPosition(size_t numAxes, float positions[]) const override; + const char* HomingButtonNames() const override { return "PDZUVW"; } private: static constexpr float DefaultSegmentsPerSecond = 200.0; diff --git a/src/Movement/Move.cpp b/src/Movement/Move.cpp index de7a2658..e8c09e76 100644 --- a/src/Movement/Move.cpp +++ b/src/Movement/Move.cpp @@ -30,8 +30,6 @@ Move::Move() : currentDda(NULL), scheduledMoves(0), completedMoves(0) void Move::Init() { - deltaProbing = false; - // Empty the ring ddaRingGetPointer = ddaRingCheckPointer = ddaRingAddPointer; DDA *dda = ddaRingAddPointer; @@ -183,88 +181,85 @@ void Move::Spin() } } - if (!deltaProbing) + // See whether we need to kick off a move + if (currentDda == nullptr) { - // See whether we need to kick off a move - if (currentDda == nullptr) + // No DDA is executing, so start executing a new one if possible + if (idleCount > 10) // better to have a few moves in the queue so that we can do lookahead { - // No DDA is executing, so start executing a new one if possible - if (idleCount > 10) // better to have a few moves in the queue so that we can do lookahead + DDA *dda = ddaRingGetPointer; + if (dda->GetState() == DDA::provisional) + { + dda->Prepare(); + } + if (dda->GetState() == DDA::frozen) { - DDA *dda = ddaRingGetPointer; - if (dda->GetState() == DDA::provisional) + if (simulationMode != 0) { - dda->Prepare(); + currentDda = dda; // pretend we are executing this move } - if (dda->GetState() == DDA::frozen) + else { - if (simulationMode != 0) + Platform::DisableStepInterrupt(); // should be disabled already because we weren't executing a move, but make sure + if (StartNextMove(Platform::GetInterruptClocks())) // start the next move { - currentDda = dda; // pretend we are executing this move + Interrupt(); } - else - { - Platform::DisableStepInterrupt(); // should be disabled already because we weren't executing a move, but make sure - if (StartNextMove(Platform::GetInterruptClocks())) // start the next move - { - Interrupt(); - } - } - iState = IdleState::busy; - } - else if (!simulationMode != 0 && iState == IdleState::busy && !reprap.GetGCodes().IsPaused() && idleTimeout > 0.0) - { - lastMoveTime = reprap.GetPlatform().Time(); // record when we first noticed that the machine was idle - iState = IdleState::timing; - } - else if (!simulationMode != 0 && iState == IdleState::timing && reprap.GetPlatform().Time() - lastMoveTime >= idleTimeout) - { - reprap.GetPlatform().SetDriversIdle(); // put all drives in idle hold - iState = IdleState::idle; } + iState = IdleState::busy; + } + else if (!simulationMode != 0 && iState == IdleState::busy && !reprap.GetGCodes().IsPaused() && idleTimeout > 0.0) + { + lastMoveTime = reprap.GetPlatform().Time(); // record when we first noticed that the machine was idle + iState = IdleState::timing; + } + else if (!simulationMode != 0 && iState == IdleState::timing && reprap.GetPlatform().Time() - lastMoveTime >= idleTimeout) + { + reprap.GetPlatform().SetDriversIdle(); // put all drives in idle hold + iState = IdleState::idle; } } + } - DDA *cdda = currentDda; // currentDda is volatile, so copy it - if (cdda != nullptr) + DDA *cdda = currentDda; // currentDda is volatile, so copy it + if (cdda != nullptr) + { + // See whether we need to prepare any moves + int32_t preparedTime = 0; + uint32_t preparedCount = 0; + DDA::DDAState st; + while ((st = cdda->GetState()) == DDA::completed || st == DDA::executing || st == DDA::frozen) { - // See whether we need to prepare any moves - int32_t preparedTime = 0; - uint32_t preparedCount = 0; - DDA::DDAState st; - while ((st = cdda->GetState()) == DDA::completed || st == DDA::executing || st == DDA::frozen) + preparedTime += cdda->GetTimeLeft(); + ++preparedCount; + cdda = cdda->GetNext(); + if (cdda == ddaRingAddPointer) { - preparedTime += cdda->GetTimeLeft(); - ++preparedCount; - cdda = cdda->GetNext(); - if (cdda == ddaRingAddPointer) - { - break; - } + break; } + } - // If the number of prepared moves will execute in less than the minimum time, prepare another move - while (st == DDA::provisional - && preparedTime < (int32_t)(DDA::stepClockRate/8) // prepare moves one eighth of a second ahead of when they will be needed - && preparedCount < DdaRingLength/2 // but don't prepare more than half the ring - ) - { - cdda->Prepare(); - preparedTime += cdda->GetTimeLeft(); - ++preparedCount; - cdda = cdda->GetNext(); - st = cdda->GetState(); - } + // If the number of prepared moves will execute in less than the minimum time, prepare another move + while (st == DDA::provisional + && preparedTime < (int32_t)(DDA::stepClockRate/8) // prepare moves one eighth of a second ahead of when they will be needed + && preparedCount < DdaRingLength/2 // but don't prepare more than half the ring + ) + { + cdda->Prepare(); + preparedTime += cdda->GetTimeLeft(); + ++preparedCount; + cdda = cdda->GetNext(); + st = cdda->GetState(); + } - // If we are simulating and the move pipeline is reasonably full, simulate completion of the current move - if (simulationMode != 0 && idleCount >= 10) - { - // Simulate completion of the current move + // If we are simulating and the move pipeline is reasonably full, simulate completion of the current move + if (simulationMode != 0 && idleCount >= 10) + { + // Simulate completion of the current move //DEBUG //currentDda->DebugPrint(); - simulationTime += currentDda->CalcTime(); - CurrentMoveCompleted(); - } + simulationTime += currentDda->CalcTime(); + CurrentMoveCompleted(); } } @@ -355,7 +350,7 @@ FilePosition Move::PausePrint(float positions[DRIVES], float& pausedFeedRate, ui if (ddaRingAddPointer != savedDdaRingAddPointer) { - const size_t numAxes = reprap.GetGCodes().GetNumAxes(); + const size_t numAxes = reprap.GetGCodes().GetTotalAxes(); // We are going to skip some moves. dda points to the last move we are going to print. for (size_t axis = 0; axis < numAxes; ++axis) @@ -444,8 +439,8 @@ void Move::Diagnostics(MessageType mtype) char ch = ' '; for (size_t i = 0; i < DDA::numLoggedProbePositions; ++i) { - float xyzPos[CART_AXES]; - MotorStepsToCartesian(DDA::loggedProbePositions + (CART_AXES * i), CART_AXES, xyzPos); + float xyzPos[XYZ_AXES]; + MotorStepsToCartesian(DDA::loggedProbePositions + (XYZ_AXES * i), XYZ_AXES, XYZ_AXES, xyzPos); p.MessageF(mtype, "%c%.2f,%.2f", ch, xyzPos[X_AXIS], xyzPos[Y_AXIS]); ch = ','; } @@ -480,7 +475,7 @@ void Move::EndPointToMachine(const float coords[], int32_t ep[], size_t numDrive { if (CartesianToMotorSteps(coords, ep)) { - const size_t numAxes = reprap.GetGCodes().GetNumAxes(); + const size_t numAxes = reprap.GetGCodes().GetTotalAxes(); for (size_t drive = numAxes; drive < numDrives; ++drive) { ep[drive] = MotorEndPointToMachine(drive, coords[drive]); @@ -496,16 +491,16 @@ int32_t Move::MotorEndPointToMachine(size_t drive, float coord) // Convert motor coordinates to machine coordinates. Used after homing and after individual motor moves. // This is computationally expensive on a delta or SCARA machine, so only call it when necessary, and never from the step ISR. -void Move::MotorStepsToCartesian(const int32_t motorPos[], size_t numDrives, float machinePos[]) const +void Move::MotorStepsToCartesian(const int32_t motorPos[], size_t numVisibleAxes, size_t numTotalAxes, float machinePos[]) const { - kinematics->MotorStepsToCartesian(motorPos, reprap.GetPlatform().GetDriveStepsPerUnit(), numDrives, machinePos); + kinematics->MotorStepsToCartesian(motorPos, reprap.GetPlatform().GetDriveStepsPerUnit(), numVisibleAxes, numTotalAxes, machinePos); } // Convert Cartesian coordinates to motor steps, axes only, returning true if successful. // Used to perform movement and G92 commands. -bool Move::CartesianToMotorSteps(const float machinePos[MAX_AXES], int32_t motorPos[MAX_AXES]) const +bool Move::CartesianToMotorSteps(const float machinePos[MaxAxes], int32_t motorPos[MaxAxes]) const { - const bool b = kinematics->CartesianToMotorSteps(machinePos, reprap.GetPlatform().GetDriveStepsPerUnit(), reprap.GetGCodes().GetNumAxes(), motorPos); + const bool b = kinematics->CartesianToMotorSteps(machinePos, reprap.GetPlatform().GetDriveStepsPerUnit(), reprap.GetGCodes().GetVisibleAxes(), reprap.GetGCodes().GetTotalAxes(), motorPos); if (reprap.Debug(moduleMove) && reprap.Debug(moduleDda)) { if (b) @@ -520,7 +515,7 @@ bool Move::CartesianToMotorSteps(const float machinePos[MAX_AXES], int32_t motor return b; } -void Move::AxisAndBedTransform(float xyzPoint[MAX_AXES], uint32_t xAxes, bool useBedCompensation) const +void Move::AxisAndBedTransform(float xyzPoint[MaxAxes], uint32_t xAxes, bool useBedCompensation) const { AxisTransform(xyzPoint); if (useBedCompensation) @@ -529,14 +524,14 @@ void Move::AxisAndBedTransform(float xyzPoint[MAX_AXES], uint32_t xAxes, bool us } } -void Move::InverseAxisAndBedTransform(float xyzPoint[MAX_AXES], uint32_t xAxes) const +void Move::InverseAxisAndBedTransform(float xyzPoint[MaxAxes], uint32_t xAxes) const { InverseBedTransform(xyzPoint, xAxes); InverseAxisTransform(xyzPoint); } // Do the Axis transform BEFORE the bed transform -void Move::AxisTransform(float xyzPoint[MAX_AXES]) const +void Move::AxisTransform(float xyzPoint[MaxAxes]) const { //TODO should we transform U axis instead of/as well as X if we are in dual carriage mode? xyzPoint[X_AXIS] += tanXY*xyzPoint[Y_AXIS] + tanXZ*xyzPoint[Z_AXIS]; @@ -544,7 +539,7 @@ void Move::AxisTransform(float xyzPoint[MAX_AXES]) const } // Invert the Axis transform AFTER the bed transform -void Move::InverseAxisTransform(float xyzPoint[MAX_AXES]) const +void Move::InverseAxisTransform(float xyzPoint[MaxAxes]) const { //TODO should we transform U axis instead of/as well as X if we are in dual carriage mode? xyzPoint[Y_AXIS] -= tanYZ*xyzPoint[Z_AXIS]; @@ -552,12 +547,12 @@ void Move::InverseAxisTransform(float xyzPoint[MAX_AXES]) const } // Do the bed transform AFTER the axis transform -void Move::BedTransform(float xyzPoint[MAX_AXES], uint32_t xAxes) const +void Move::BedTransform(float xyzPoint[MaxAxes], uint32_t xAxes) const { if (!useTaper || xyzPoint[Z_AXIS] < taperHeight) { float zCorrection = 0.0; - const size_t numAxes = reprap.GetGCodes().GetNumAxes(); + const size_t numAxes = reprap.GetGCodes().GetVisibleAxes(); unsigned int numXAxes = 0; // Transform the Z coordinate based on the average correction for each axis used as an X axis. @@ -589,10 +584,10 @@ void Move::BedTransform(float xyzPoint[MAX_AXES], uint32_t xAxes) const } // Invert the bed transform BEFORE the axis transform -void Move::InverseBedTransform(float xyzPoint[MAX_AXES], uint32_t xAxes) const +void Move::InverseBedTransform(float xyzPoint[MaxAxes], uint32_t xAxes) const { float zCorrection = 0.0; - const size_t numAxes = reprap.GetGCodes().GetNumAxes(); + const size_t numAxes = reprap.GetGCodes().GetVisibleAxes(); unsigned int numXAxes = 0; // Transform the Z coordinate based on the average correction for each axis used as an X axis. @@ -759,49 +754,6 @@ void Move::AdjustMotorPositions(const float_t adjustment[], size_t numMotors) liveCoordinatesValid = false; // force the live XYZ position to be recalculated } -static void ShortDelay() -{ - for (unsigned int i = 0; i < 10; ++i) - { - asm volatile("nop"); - asm volatile("nop"); - asm volatile("nop"); - asm volatile("nop"); - asm volatile("nop"); - asm volatile("nop"); - asm volatile("nop"); - asm volatile("nop"); - asm volatile("nop"); - } -} - -// This is the function that is called by the timer interrupt to step the motors when we are using the experimental delta probe. -// The movements are quite slow so it is not time-critical. -void Move::DeltaProbeInterrupt() -{ - bool again; - do - { - if (reprap.GetPlatform().GetZProbeResult() == EndStopHit::lowHit) - { - deltaProbe.Trigger(); - } - - const bool dir = deltaProbe.GetDirection(); - Platform& platform = reprap.GetPlatform(); - platform.SetDirection(X_AXIS, dir); - platform.SetDirection(Y_AXIS, dir); - platform.SetDirection(Z_AXIS, dir); - ShortDelay(); - const uint32_t steppersMoving = platform.GetDriversBitmap(X_AXIS) | platform.GetDriversBitmap(Y_AXIS) | platform.GetDriversBitmap(Z_AXIS); - Platform::StepDriversHigh(steppersMoving); - ShortDelay(); - Platform::StepDriversLow(); - const uint32_t tim = deltaProbe.CalcNextStepTime(); - again = (tim != 0xFFFFFFFF && platform.ScheduleInterrupt(tim + deltaProbingStartTime)); - } while (again); -} - // This is called from the step ISR when the current move has been completed void Move::CurrentMoveCompleted() { @@ -837,7 +789,7 @@ bool Move::TryStartNextMove(uint32_t startTime) // This is called from the step ISR. Any variables it modifies that are also read by code outside the ISR must be declared 'volatile'. void Move::HitLowStop(size_t axis, DDA* hitDDA) { - if (axis < reprap.GetGCodes().GetNumAxes() && !IsDeltaMode()) // should always be true + if (axis < reprap.GetGCodes().GetTotalAxes() && !IsDeltaMode()) // should always be true { JustHomed(axis, reprap.GetPlatform().AxisMinimum(axis), hitDDA); } @@ -846,7 +798,7 @@ void Move::HitLowStop(size_t axis, DDA* hitDDA) // This is called from the step ISR. Any variables it modifies that are also read by code outside the ISR must be declared 'volatile'. void Move::HitHighStop(size_t axis, DDA* hitDDA) { - if (axis < reprap.GetGCodes().GetNumAxes()) // should always be true + if (axis < reprap.GetGCodes().GetTotalAxes()) // should always be true { const float hitPoint = (IsDeltaMode()) ? ((LinearDeltaKinematics*)kinematics)->GetHomedCarriageHeight(axis) // this is a delta printer, so the motor is at the homed carriage height for this drive @@ -860,13 +812,13 @@ void Move::JustHomed(size_t axisHomed, float hitPoint, DDA* hitDDA) { if (IsCoreXYAxis(axisHomed)) { - float tempCoordinates[CART_AXES]; - for (size_t axis = 0; axis < CART_AXES; ++axis) + float tempCoordinates[XYZ_AXES]; + for (size_t axis = 0; axis < XYZ_AXES; ++axis) { tempCoordinates[axis] = hitDDA->GetEndCoordinate(axis, false); } tempCoordinates[axisHomed] = hitPoint; - hitDDA->SetPositions(tempCoordinates, CART_AXES); + hitDDA->SetPositions(tempCoordinates, XYZ_AXES); } else { @@ -887,7 +839,7 @@ void Move::ZProbeTriggered(DDA* hitDDA) void Move::GetCurrentMachinePosition(float m[DRIVES], bool disableMotorMapping) const { DDA * const lastQueuedMove = ddaRingAddPointer->GetPrevious(); - const size_t numAxes = reprap.GetGCodes().GetNumAxes(); + const size_t numAxes = reprap.GetGCodes().GetVisibleAxes(); for (size_t i = 0; i < DRIVES; i++) { if (i < numAxes) @@ -930,7 +882,7 @@ void Move::GetCurrentUserPosition(float m[DRIVES], uint8_t moveType, uint32_t xA void Move::LiveCoordinates(float m[DRIVES], uint32_t xAxes) { // The live coordinates and live endpoints are modified by the ISR, so be careful to get a self-consistent set of them - const size_t numAxes = reprap.GetGCodes().GetNumAxes(); // do this before we disable interrupts + const size_t numVisibleAxes = reprap.GetGCodes().GetVisibleAxes(); // do this before we disable interrupts cpu_irq_disable(); if (liveCoordinatesValid) { @@ -940,19 +892,20 @@ void Move::LiveCoordinates(float m[DRIVES], uint32_t xAxes) } else { + const size_t numTotalAxes = reprap.GetGCodes().GetTotalAxes(); // do this before we disable interrupts // Only the extruder coordinates are valid, so we need to convert the motor endpoints to coordinates - memcpy(m + numAxes, const_cast<const float *>(liveCoordinates + numAxes), sizeof(m[0]) * (DRIVES - numAxes)); - int32_t tempEndPoints[MAX_AXES]; + memcpy(m + numTotalAxes, const_cast<const float *>(liveCoordinates + numTotalAxes), sizeof(m[0]) * (DRIVES - numTotalAxes)); + int32_t tempEndPoints[MaxAxes]; memcpy(tempEndPoints, const_cast<const int32_t*>(liveEndPoints), sizeof(tempEndPoints)); cpu_irq_enable(); - MotorStepsToCartesian(tempEndPoints, numAxes, m); // this is slow, so do it with interrupts enabled + MotorStepsToCartesian(tempEndPoints, numVisibleAxes, numTotalAxes, m); // this is slow, so do it with interrupts enabled // If the ISR has not updated the endpoints, store the live coordinates back so that we don't need to do it again cpu_irq_disable(); if (memcmp(tempEndPoints, const_cast<const int32_t*>(liveEndPoints), sizeof(tempEndPoints)) == 0) { - memcpy(const_cast<float *>(liveCoordinates), m, sizeof(m[0]) * numAxes); + memcpy(const_cast<float *>(liveCoordinates), m, sizeof(m[0]) * numVisibleAxes); liveCoordinatesValid = true; } cpu_irq_enable(); @@ -969,13 +922,13 @@ void Move::SetLiveCoordinates(const float coords[DRIVES]) liveCoordinates[drive] = coords[drive]; } liveCoordinatesValid = true; - EndPointToMachine(coords, const_cast<int32_t *>(liveEndPoints), reprap.GetGCodes().GetNumAxes()); + EndPointToMachine(coords, const_cast<int32_t *>(liveEndPoints), reprap.GetGCodes().GetVisibleAxes()); } void Move::ResetExtruderPositions() { cpu_irq_disable(); - for (size_t eDrive = reprap.GetGCodes().GetNumAxes(); eDrive < DRIVES; eDrive++) + for (size_t eDrive = reprap.GetGCodes().GetTotalAxes(); eDrive < DRIVES; eDrive++) { liveCoordinates[eDrive] = 0.0; } @@ -1055,47 +1008,4 @@ bool Move::IsCoreXYAxis(size_t axis) const } } -// Do a delta probe returning -1 if still probing, 0 if failed, 1 if success -int Move::DoDeltaProbe(float frequency, float amplitude, float rate, float distance) -{ - if (deltaProbing) - { - if (deltaProbe.Finished()) - { - deltaProbing = false; - return (deltaProbe.Overran()) ? 0 : 1; - } - } - else - { - if (currentDda != nullptr || !DDARingEmpty()) - { - return 0; - } - if (!deltaProbe.Init(frequency, amplitude, rate, distance)) - { - return 0; - } - - const uint32_t firstInterruptTime = deltaProbe.Start(); - if (firstInterruptTime != 0xFFFFFFFF) - { - Platform& platform = reprap.GetPlatform(); - platform.EnableDrive(X_AXIS); - platform.EnableDrive(Y_AXIS); - platform.EnableDrive(Z_AXIS); - deltaProbing = true; - iState = IdleState::busy; - const irqflags_t flags = cpu_irq_save(); - deltaProbingStartTime = platform.GetInterruptClocks(); - if (platform.ScheduleInterrupt(firstInterruptTime + deltaProbingStartTime)) - { - Interrupt(); - } - cpu_irq_restore(flags); - } - } - return -1; -} - // End diff --git a/src/Movement/Move.h b/src/Movement/Move.h index 06d99816..e2eeac41 100644 --- a/src/Movement/Move.h +++ b/src/Movement/Move.h @@ -15,7 +15,6 @@ #include "BedProbing/RandomProbePointSet.h" #include "BedProbing/Grid.h" #include "Kinematics/Kinematics.h" -#include "DeltaProbe.h" #ifdef DUET_NG const unsigned int DdaRingLength = 30; @@ -67,9 +66,9 @@ public: // Kinematics and related functions Kinematics& GetKinematics() const { return *kinematics; } bool SetKinematics(KinematicsType k); // Set kinematics, return true if successful - bool CartesianToMotorSteps(const float machinePos[MAX_AXES], int32_t motorPos[MAX_AXES]) const; + bool CartesianToMotorSteps(const float machinePos[MaxAxes], int32_t motorPos[MaxAxes]) const; // Convert Cartesian coordinates to delta motor coordinates, return true if successful - void MotorStepsToCartesian(const int32_t motorPos[], size_t numDrives, float machinePos[]) const; + void MotorStepsToCartesian(const int32_t motorPos[], size_t numVisibleAxes, size_t numTotalAxes, float machinePos[]) const; // Convert motor coordinates to machine coordinates void EndPointToMachine(const float coords[], int32_t ep[], size_t numDrives) const; void AdjustMotorPositions(const float_t adjustment[], size_t numMotors); // Perform motor endpoint adjustment @@ -93,8 +92,6 @@ public: FilePosition PausePrint(float positions[DRIVES], float& pausedFeedRate, uint32_t xAxes); // Pause the print as soon as we can bool NoLiveMovement() const; // Is a move running, or are there any queued? - int DoDeltaProbe(float frequency, float amplitude, float rate, float distance); - bool IsExtruding() const; // Is filament being extruded? uint32_t GetScheduledMoves() const { return scheduledMoves; } // How many moves have been scheduled? @@ -110,12 +107,11 @@ private: enum class IdleState : uint8_t { idle, busy, timing }; bool StartNextMove(uint32_t startTime); // start the next move, returning true if Step() needs to be called immediately - void BedTransform(float move[MAX_AXES], uint32_t xAxes) const; // Take a position and apply the bed compensations - void InverseBedTransform(float move[MAX_AXES], uint32_t xAxes) const; // Go from a bed-transformed point back to user coordinates - void AxisTransform(float move[MAX_AXES]) const; // Take a position and apply the axis-angle compensations - void InverseAxisTransform(float move[MAX_AXES]) const; // Go from an axis transformed point back to user coordinates + void BedTransform(float move[MaxAxes], uint32_t xAxes) const; // Take a position and apply the bed compensations + void InverseBedTransform(float move[MaxAxes], uint32_t xAxes) const; // Go from a bed-transformed point back to user coordinates + void AxisTransform(float move[MaxAxes]) const; // Take a position and apply the axis-angle compensations + void InverseAxisTransform(float move[MaxAxes]) const; // Go from an axis transformed point back to user coordinates void JustHomed(size_t axis, float hitPoint, DDA* hitDDA); // Deal with setting positions after a drive has been homed - void DeltaProbeInterrupt(); // Step ISR when using the experimental delta probe bool DDARingAdd(); // Add a processed look-ahead entry to the DDA ring DDA* DDARingGet(); // Get the next DDA ring entry to be run @@ -158,11 +154,6 @@ private: unsigned int stepErrors; // count of step errors, for diagnostics uint32_t scheduledMoves; // Move counters for the code queue volatile uint32_t completedMoves; // This one is modified by an ISR, hence volatile - - // Parameters for the experimental accoustic delta probe - DeltaProbe deltaProbe; // Delta probing state - uint32_t deltaProbingStartTime; - bool deltaProbing; }; //****************************************************************************************************** @@ -202,10 +193,6 @@ inline void Move::Interrupt() { } while (currentDda->Step()); } - else if (deltaProbing) - { - DeltaProbeInterrupt(); - } } #endif /* MOVE_H_ */ diff --git a/src/Platform.cpp b/src/Platform.cpp index ec31cae7..66eaf063 100644 --- a/src/Platform.cpp +++ b/src/Platform.cpp @@ -415,7 +415,7 @@ void Platform::Init() directions[drive] = true; // drive moves forwards by default // Map axes and extruders straight through - if (drive < MAX_AXES) + if (drive < MaxAxes) { axisDrivers[drive].numDrivers = 1; axisDrivers[drive].driverNumbers[0] = (uint8_t)drive; @@ -430,11 +430,6 @@ void Platform::Init() endStopLogicLevel[drive] = true; // assume all endstops use active high logic e.g. normally-closed switch to ground } - if (drive >= MIN_AXES) - { - extruderDrivers[drive - MIN_AXES] = (uint8_t)drive; - SetPressureAdvance(drive - MIN_AXES, 0.0); - } driveDriverBits[drive] = CalcDriverBitmap(drive); // Set up the control pins and endstops @@ -453,6 +448,12 @@ void Platform::Init() slowDriverStepPulseClocks = 0; // no extended driver timing configured yet slowDrivers = 0; // assume no drivers need extended step pulse timing + for (size_t extr = 0; extr < MaxExtruders; ++extr) + { + extruderDrivers[extr] = (uint8_t)(extr + MinAxes); // set up default extruder drive mapping + SetPressureAdvance(extr, 0.0); + } + #ifdef DUET_NG // Test for presence of a DueX2 or DueX5 expansion board and work out how many TMC2660 drivers we have // The SX1509B has an independent power on reset, so give it some time @@ -521,7 +522,7 @@ void Platform::Init() setPullup(SpiTempSensorCsPins[i], true); } - for (size_t heater = 0; heater < HEATERS; heater++) + for (size_t heater = 0; heater < Heaters; heater++) { if (heatOnPins[heater] != NoPin) { @@ -531,13 +532,6 @@ void Platform::Init() pinMode(tempSensePins[heater], AIN); thermistorAdcChannels[heater] = chan; AnalogInEnableChannel(chan, true); - - SetThermistorNumber(heater, heater); // map the thermistor straight through - thermistors[heater].SetParameters( - (heater == DefaultBedHeater) ? BED_R25 : EXT_R25, - (heater == DefaultBedHeater) ? BED_BETA : EXT_BETA, - (heater == DefaultBedHeater) ? BED_SHC : EXT_SHC, - THERMISTOR_SERIES_RS); // initialise the thermistor parameters thermistorFilters[heater].Init(0); } @@ -626,33 +620,6 @@ bool Platform::AnyFileOpen(const FATFS *fs) const return false; } -// Specify which thermistor channel a particular heater uses -void Platform::SetThermistorNumber(size_t heater, size_t thermistor) -{ - heaterTempChannels[heater] = thermistor; - - // Initialize the associated SPI temperature sensor? - if (thermistor >= FirstThermocoupleChannel && thermistor < FirstThermocoupleChannel + MaxSpiTempSensors) - { - SpiTempSensors[thermistor - FirstThermocoupleChannel].InitThermocouple(SpiTempSensorCsPins[thermistor - FirstThermocoupleChannel]); - } - else if (thermistor >= FirstRtdChannel && thermistor < FirstRtdChannel + MaxSpiTempSensors) - { - SpiTempSensors[thermistor - FirstRtdChannel].InitRtd(spiTempSenseCsPins[thermistor - FirstRtdChannel]); - } - else if (thermistor >= FirstLinearAdcChannel && thermistor < FirstLinearAdcChannel + MaxSpiTempSensors) - { - SpiTempSensors[thermistor - FirstRtdChannel].InitLinearAdc(spiTempSenseCsPins[thermistor - FirstLinearAdcChannel]); - } - - reprap.GetHeat().ResetFault(heater); -} - -int Platform::GetThermistorNumber(size_t heater) const -{ - return heaterTempChannels[heater]; -} - void Platform::SetZProbeDefaults() { switchZProbeParameters.Init(0.0); @@ -779,7 +746,7 @@ float Platform::GetZProbeTemperature() if (bedHeater >= 0) { TemperatureError err; - const float temp = GetTemperature(bedHeater, err); + const float temp = reprap.GetHeat().GetTemperature(bedHeater, err); if (err == TemperatureError::success) { return temp; @@ -811,7 +778,7 @@ float Platform::GetZProbeTravelSpeed() const void Platform::SetZProbeType(int pt) { - zProbeType = (pt >= 0 && pt <= 7) ? pt : 0; + zProbeType = (pt >= 0 && pt <= 6) ? pt : 0; InitZProbe(); } @@ -2021,164 +1988,23 @@ void Platform::ClassReport(float &lastTime) } } -//=========================================================================== -//=============================Thermal Settings ============================ -//=========================================================================== - -// See http://en.wikipedia.org/wiki/Thermistor#B_or_.CE.B2_parameter_equation - -// BETA is the B value -// RS is the value of the series resistor in ohms -// R_INF is R0.exp(-BETA/T0), where R0 is the thermistor resistance at T0 (T0 is in kelvin) -// Normally T0 is 298.15K (25 C). - -// If the A->D converter has a range of 0..1023 and the measured voltage is V (between 0 and 1023) -// then the thermistor resistance, R = V.RS/(1024 - V) -// and the temperature, T = BETA/ln(R/R_INF) -// To get degrees celsius (instead of kelvin) add -273.15 to T - -// Result is in degrees celsius - -float Platform::GetTemperature(size_t heater, TemperatureError& err) +#ifdef DUET_NG +// This is called when a fan that monitors driver temperatures is turned on when it was off +void Platform::DriverCoolingFansOn(uint32_t driverChannelsMonitored) { - // Note that at this point we're actually getting an averaged ADC read, not a "raw" temp. For thermistors, - // we're getting an averaged voltage reading which we'll convert to a temperature. - if (IsThermistorChannel(heater)) - { - const volatile ThermistorAveragingFilter& filter = thermistorFilters[heater]; - if (filter.IsValid()) - { - const int32_t averagedReading = filter.GetSum()/(ThermistorAverageReadings >> Thermistor::AdcOversampleBits); - const float temp = thermistors[heater].CalcTemperature(averagedReading); - - if (temp < MinimumConnectedTemperature) - { - // thermistor is disconnected - err = TemperatureError::openCircuit; - return ABS_ZERO; - } - - err = TemperatureError::success; - return temp; - } - - // Filter is not ready yet - err = TemperatureError::busBusy; - return BAD_ERROR_TEMPERATURE; - } - - if (IsThermocoupleChannel(heater)) + if (driverChannelsMonitored & 1) { - // MAX31855 thermocouple chip - float temp; - err = SpiTempSensors[heaterTempChannels[heater] - FirstThermocoupleChannel].GetThermocoupleTemperature(temp); - return (err == TemperatureError::success) ? temp : BAD_ERROR_TEMPERATURE; + onBoardDriversFanStartMillis = millis(); + onBoardDriversFanRunning = true; } - - if (IsRtdChannel(heater)) + if (driverChannelsMonitored & 2) { - // MAX31865 RTD chip - float temp; - err = SpiTempSensors[heaterTempChannels[heater] - FirstRtdChannel].GetRtdTemperature(temp); - return (err == TemperatureError::success) ? temp : BAD_ERROR_TEMPERATURE; + offBoardDriversFanStartMillis = millis(); + offBoardDriversFanRunning = true; } - - if (IsLinearAdcChannel(heater)) - { - // MAX31865 RTD chip - float temp; - err = SpiTempSensors[heaterTempChannels[heater] - FirstRtdChannel].GetLinearAdcTemperature(temp); - return (err == TemperatureError::success) ? temp : BAD_ERROR_TEMPERATURE; - } - - err = TemperatureError::unknownChannel; - return BAD_ERROR_TEMPERATURE; } - -// See if we need to turn on a thermostatically-controlled fan -bool Platform::AnyHeaterHot(uint16_t heaters, float t) -{ - for (size_t h = 0; h < HEATERS; ++h) - { - // Check if this heater is both monitored by this fan and in use - if ( ((1 << h) & heaters) != 0 - && (h < reprap.GetToolHeatersInUse() || (int)h == reprap.GetHeat().GetBedHeater() || (int)h == reprap.GetHeat().GetChamberHeater()) - ) - { - if (reprap.GetHeat().IsTuning(h)) - { - return true; // when turning the PID for a monitored heater, turn the fan on - } - - TemperatureError err; - const float ht = GetTemperature(h, err); - if (err != TemperatureError::success || ht >= t || ht < BAD_LOW_TEMPERATURE) - { - return true; - } - } - } - -#ifndef __RADDS__ - // All boards except RADDS have CPU temperature monitoring - if ((heaters & (1 << HEATERS)) != 0 && AdcReadingToCpuTemperature(cpuTemperatureFilter.GetSum()) >= t) - { - return true; - } #endif -#ifdef DUET_NG - // Duet NG has driver temperature monitoring too - bool turnFanOn = false; - - if ((heaters & (1 << (HEATERS + 1))) != 0) - { - const uint16_t onBoardDriversMask = (1u << 5) - 1; - const float onBoardDriversTemperature = ((temperatureShutdownDrivers & onBoardDriversMask) != 0) ? 150.0 - : ((temperatureWarningDrivers & onBoardDriversMask) != 0) ? 100.0 - : 0.0; - if (onBoardDriversTemperature >= t) - { - if (!onBoardDriversFanRunning) - { - onBoardDriversFanStartMillis = millis(); - } - onBoardDriversFanRunning = true; - turnFanOn = true; - } - else - { - onBoardDriversFanRunning = false; - } - } - - if ((heaters & (1 << (HEATERS + 2))) != 0) - { - const uint16_t offBoardDriversMask = ((1u << 5) - 1) << 5; - const float offBoardDriversTemperature = ((temperatureShutdownDrivers & offBoardDriversMask) != 0) ? 150.0 - : ((temperatureWarningDrivers & offBoardDriversMask) != 0) ? 100.0 - : 0.0; - if (offBoardDriversTemperature >= t) - { - if (!offBoardDriversFanRunning) - { - offBoardDriversFanStartMillis = millis(); - } - offBoardDriversFanRunning = true; - turnFanOn = true; - } - else - { - offBoardDriversFanRunning = false; - } - } - - return turnFanOn; -#else - return false; -#endif -} - // Power is a fraction in [0,1] void Platform::SetHeater(size_t heater, float power) { @@ -2208,7 +2034,7 @@ void Platform::UpdateConfiguredHeaters() } // Check tool heaters - for(size_t heater = 0; heater < HEATERS; heater++) + for(size_t heater = 0; heater < Heaters; heater++) { if (reprap.IsHeaterAssignedToTool(heater)) { @@ -2221,7 +2047,7 @@ EndStopHit Platform::Stopped(size_t drive) const { if (drive < DRIVES && endStopPins[drive] != NoPin) { - if (drive >= reprap.GetGCodes().GetNumAxes()) + if (drive >= reprap.GetGCodes().GetTotalAxes()) { // Endstop not used for an axis, so no configuration data available. // To allow us to see its status in DWC, pretend it is configured as a high-end active high endstop. @@ -2233,7 +2059,7 @@ EndStopHit Platform::Stopped(size_t drive) const else if (endStopType[drive] == EndStopType::noEndStop) { // No homing switch is configured for this axis, so see if we should use the Z probe - if (zProbeType > 0 && drive < reprap.GetGCodes().GetNumAxes() && (zProbeAxes & (1 << drive)) != 0) + if (zProbeType > 0 && drive < reprap.GetGCodes().GetVisibleAxes() && (zProbeAxes & (1 << drive)) != 0) { return GetZProbeResult(); // using the Z probe as a low homing stop for this axis, so just get its result } @@ -2293,7 +2119,7 @@ bool Platform::WriteZProbeParameters(FileStore *f) const // This is called from the step ISR as well as other places, so keep it fast void Platform::SetDirection(size_t drive, bool direction) { - const size_t numAxes = reprap.GetGCodes().GetNumAxes(); + const size_t numAxes = reprap.GetGCodes().GetTotalAxes(); if (drive < numAxes) { for (size_t i = 0; i < axisDrivers[drive].numDrivers; ++i) @@ -2354,7 +2180,7 @@ void Platform::DisableDriver(size_t driver) // Enable the drivers for a drive. Must not be called from an ISR, or with interrupts disabled. void Platform::EnableDrive(size_t drive) { - const size_t numAxes = reprap.GetGCodes().GetNumAxes(); + const size_t numAxes = reprap.GetGCodes().GetTotalAxes(); if (drive < numAxes) { for (size_t i = 0; i < axisDrivers[drive].numDrivers; ++i) @@ -2371,7 +2197,7 @@ void Platform::EnableDrive(size_t drive) // Disable the drivers for a drive void Platform::DisableDrive(size_t drive) { - const size_t numAxes = reprap.GetGCodes().GetNumAxes(); + const size_t numAxes = reprap.GetGCodes().GetTotalAxes(); if (drive < numAxes) { for (size_t i = 0; i < axisDrivers[drive].numDrivers; ++i) @@ -2419,7 +2245,7 @@ void Platform::SetDriverCurrent(size_t driver, float currentOrPercent, bool isPe // Set the current for all drivers on an axis or extruder. Current is in mA. void Platform::SetMotorCurrent(size_t drive, float currentOrPercent, bool isPercent) { - const size_t numAxes = reprap.GetGCodes().GetNumAxes(); + const size_t numAxes = reprap.GetGCodes().GetTotalAxes(); if (drive < numAxes) { for (size_t i = 0; i < axisDrivers[drive].numDrivers; ++i) @@ -2515,7 +2341,7 @@ float Platform::GetMotorCurrent(size_t drive, bool isPercent) const { if (drive < DRIVES) { - const size_t numAxes = reprap.GetGCodes().GetNumAxes(); + const size_t numAxes = reprap.GetGCodes().GetTotalAxes(); const uint8_t driver = (drive < numAxes) ? axisDrivers[drive].driverNumbers[0] : extruderDrivers[drive - numAxes]; if (driver < DRIVES) { @@ -2566,7 +2392,7 @@ bool Platform::SetDriverMicrostepping(size_t driver, int microsteps, int mode) // Set the microstepping, returning true if successful. All drivers for the same axis must use the same microstepping. bool Platform::SetMicrostepping(size_t drive, int microsteps, int mode) { - const size_t numAxes = reprap.GetGCodes().GetNumAxes(); + const size_t numAxes = reprap.GetGCodes().GetTotalAxes(); if (drive < numAxes) { bool ok = true; @@ -2603,7 +2429,7 @@ unsigned int Platform::GetDriverMicrostepping(size_t driver, int mode, bool& int // Get the microstepping for an axis or extruder unsigned int Platform::GetMicrostepping(size_t drive, int mode, bool& interpolation) const { - const size_t numAxes = reprap.GetGCodes().GetNumAxes(); + const size_t numAxes = reprap.GetGCodes().GetTotalAxes(); if (drive < numAxes) { return GetDriverMicrostepping(axisDrivers[drive].driverNumbers[0], mode, interpolation); @@ -2634,7 +2460,7 @@ void Platform::SetAxisDriversConfig(size_t drive, const AxisDriversConfig& confi void Platform::SetExtruderDriver(size_t extruder, uint8_t driver) { extruderDrivers[extruder] = driver; - driveDriverBits[extruder + reprap.GetGCodes().GetNumAxes()] = CalcDriverBitmap(driver); + driveDriverBits[extruder + reprap.GetGCodes().GetTotalAxes()] = CalcDriverBitmap(driver); } void Platform::SetDriverStepTiming(size_t driver, float microseconds) @@ -2661,6 +2487,23 @@ float Platform::GetDriverStepTiming(size_t driver) const : 0.0; } +// Set or report the parameters for the specified fan +// If 'mCode' is an M-code used to set parameters for the current kinematics (which should only ever be 106 or 107) +// then search for parameters used to configure the fan. If any are found, perform appropriate actions and return true. +// If errors were discovered while processing parameters, put an appropriate error message in 'reply' and set 'error' to true. +// If no relevant parameters are found, print the existing ones to 'reply' and return false. +bool Platform::ConfigureFan(unsigned int mcode, int fanNum, GCodeBuffer& gb, StringRef& reply, bool& error) +{ + if (fanNum < 0 || fanNum >= (int)NUM_FANS) + { + reply.printf("Fan number %d is invalid, must be between 0 and %u", fanNum, NUM_FANS - 1); + error = true; + return false; + } + + return fans[fanNum].Configure(mcode, fanNum, gb, reply, error); +} + // Get current cooling fan speed on a scale between 0 and 1 float Platform::GetFanValue(size_t fan) const { @@ -2693,7 +2536,7 @@ void Platform::EnableSharedFan(bool enable) // Get current fan RPM -float Platform::GetFanRPM() +float Platform::GetFanRPM() const { // The ISR sets fanInterval to the number of microseconds it took to get fanMaxInterruptCount interrupts. // We get 2 tacho pulses per revolution, hence 2 interrupts per revolution. @@ -2726,7 +2569,7 @@ void Platform::InitFans() { #if defined(DUET_NG) || defined(__RADDS__) || defined(__ALLIGATOR__) // Set fan 1 to be thermostatic by default, monitoring all heaters except the default bed heater - fans[1].SetHeatersMonitored(((1 << HEATERS) - 1) & ~(1 << DefaultBedHeater)); + fans[1].SetHeatersMonitored(((1 << Heaters) - 1) & ~(1 << DefaultBedHeater)); fans[1].SetValue(1.0); // set it full on #else // Fan 1 on the Duet 0.8.5 shares its control pin with heater 6. Set it full on to make sure the heater (if present) is off. @@ -3026,7 +2869,7 @@ void Platform::SetPressureAdvance(size_t extruder, float factor) float Platform::ActualInstantDv(size_t drive) const { const float idv = instantDvs[drive]; - const size_t numAxes = reprap.GetGCodes().GetNumAxes(); + const size_t numAxes = reprap.GetGCodes().GetTotalAxes(); if (drive >= numAxes) { const float eComp = pressureAdvance[drive - numAxes]; @@ -3182,7 +3025,7 @@ bool Platform::GetFirmwarePin(int logicalPin, PinAccess access, Pin& firmwarePin { // Pin number out of range, so nothing to do here } - else if (logicalPin >= Heater0LogicalPin && logicalPin < Heater0LogicalPin + HEATERS) // pins 0-9 correspond to heater channels + else if (logicalPin >= Heater0LogicalPin && logicalPin < Heater0LogicalPin + (int)Heaters) // pins 0-9 correspond to heater channels { // For safety, we don't allow a heater channel to be used for servos until the heater has been disabled if (!reprap.GetHeat().IsHeaterEnabled(logicalPin - Heater0LogicalPin)) @@ -3320,6 +3163,7 @@ void Platform::GetMcuTemperatures(float& minT, float& currT, float& maxT) const #endif #ifdef DUET_NG + // Power in voltage void Platform::GetPowerVoltages(float& minV, float& currV, float& maxV) const { @@ -3327,6 +3171,16 @@ void Platform::GetPowerVoltages(float& minV, float& currV, float& maxV) const currV = AdcReadingToPowerVoltage(currentVin); maxV = AdcReadingToPowerVoltage(highestVin); } + +// TMC driver temperatures +float Platform::GetTmcDriversTemperature(unsigned int board) const +{ + const uint16_t mask = ((1u << 5) - 1) << (5 * board); // there are 5 driver son each board + return ((temperatureShutdownDrivers & mask) != 0) ? 150.0 + : ((temperatureWarningDrivers & mask) != 0) ? 100.0 + : 0.0; +} + #endif // Real-time clock @@ -3479,36 +3333,36 @@ void Platform::Tick() { case 1: case 3: - // We process a thermistor reading on alternate ticks - if (IsThermistorChannel(currentHeater)) { - // Because we are in the tick ISR and no other ISR reads the averaging filter, we can cast away 'volatile' here + // We read a thermistor channel on alternate ticks + // Because we are in the tick ISR and no other ISR reads the averaging filter, we can cast away 'volatile' here. + // The following code assumes number of thermistor channels = number of heater channels ThermistorAveragingFilter& currentFilter = const_cast<ThermistorAveragingFilter&>(thermistorFilters[currentHeater]); - currentFilter.ProcessReading(AnalogInReadChannel(thermistorAdcChannels[heaterTempChannels[currentHeater]])); - } + currentFilter.ProcessReading(AnalogInReadChannel(thermistorAdcChannels[currentHeater])); - // Guard against overly long delays between successive calls of PID::Spin(). - // Do not call Time() here, it isn't safe. We use millis() instead. - if ((configuredHeaters & (1 << currentHeater)) != 0 && (millis() - reprap.GetHeat().GetLastSampleTime(currentHeater)) > maxPidSpinDelay) - { - SetHeater(currentHeater, 0.0); - LogError(ErrorCode::BadTemp); - } + // Guard against overly long delays between successive calls of PID::Spin(). + // Do not call Time() here, it isn't safe. We use millis() instead. + if ((configuredHeaters & (1 << currentHeater)) != 0 && (millis() - reprap.GetHeat().GetLastSampleTime(currentHeater)) > maxPidSpinDelay) + { + SetHeater(currentHeater, 0.0); + LogError(ErrorCode::BadTemp); + } - ++currentHeater; - if (currentHeater == HEATERS) - { - currentHeater = 0; - } + ++currentHeater; + if (currentHeater == Heaters) + { + currentHeater = 0; + } - // If we are not using a simple modulated IR sensor, process the Z probe reading on every tick for a faster response. - // If we are using a simple modulated IR sensor then we need to allow the reading to settle after turning the IR emitter on or off, - // so on alternate ticks we read it and switch the emitter - if (zProbeType != 2) - { - const_cast<ZProbeAveragingFilter&>((tickState == 1) ? zProbeOnFilter : zProbeOffFilter).ProcessReading(GetRawZProbeReading()); + // If we are not using a simple modulated IR sensor, process the Z probe reading on every tick for a faster response. + // If we are using a simple modulated IR sensor then we need to allow the reading to settle after turning the IR emitter on or off, + // so on alternate ticks we read it and switch the emitter + if (zProbeType != 2) + { + const_cast<ZProbeAveragingFilter&>((tickState == 1) ? zProbeOnFilter : zProbeOffFilter).ProcessReading(GetRawZProbeReading()); + } + ++tickState; } - ++tickState; break; case 2: diff --git a/src/Platform.h b/src/Platform.h index 409c2310..5c7a5685 100644 --- a/src/Platform.h +++ b/src/Platform.h @@ -41,8 +41,6 @@ Licence: GPL #include "RepRapFirmware.h" #include "DueFlashStorage.h" #include "Fan.h" -#include "Heating/TemperatureSensor.h" -#include "Heating/Thermistor.h" #include "Heating/TemperatureError.h" #include "OutputMemory.h" #include "Storage/FileStore.h" @@ -88,14 +86,13 @@ const float INSTANT_DVS[DRIVES] = DRIVES_(15.0, 15.0, 0.2, 2.0, 2.0, 2.0, 2.0, 2 // AXES -const float AXIS_MINIMA[MAX_AXES] = AXES_(0.0, 0.0, 0.0, 0.0, 0.0, 0.0); // mm -const float AXIS_MAXIMA[MAX_AXES] = AXES_(230.0, 210.0, 200.0, 0.0, 0.0, 0.0); // mm +const float AXIS_MINIMA[MaxAxes] = AXES_(0.0, 0.0, 0.0, 0.0, 0.0, 0.0); // mm +const float AXIS_MAXIMA[MaxAxes] = AXES_(230.0, 210.0, 200.0, 0.0, 0.0, 0.0); // mm // Z PROBE const float Z_PROBE_STOP_HEIGHT = 0.7; // Millimetres const unsigned int Z_PROBE_AVERAGE_READINGS = 8; // We average this number of readings with IR on, and the same number with IR off -const int ZProbeTypeDelta = 7; // Z probe type for experimental delta probe #ifdef DUET_NG const int Z_PROBE_AD_VALUE = 500; // Default for the Z probe - should be overwritten by experiment @@ -451,10 +448,10 @@ public: void SetPressureAdvance(size_t extruder, float factor); void SetEndStopConfiguration(size_t axis, EndStopType endstopType, bool logicLevel) - pre(axis < MAX_AXES); + pre(axis < MaxAxes); void GetEndStopConfiguration(size_t axis, EndStopType& endstopType, bool& logicLevel) const - pre(axis < MAX_AXES); + pre(axis < MaxAxes); uint32_t GetAllEndstopStates() const; void SetAxisDriversConfig(size_t drive, const AxisDriversConfig& config); @@ -503,59 +500,32 @@ public: void ExtrudeOff(); // Heat and temperature - - 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 + volatile ThermistorAveragingFilter& GetThermistorFilter(size_t channel) + pre(channel < ARRAY_SIZE(thermistorFilters)) + { + return thermistorFilters[channel]; + } + void SetHeater(size_t heater, float power) // power is a fraction in [0,1] - pre(heater < HEATERS); + pre(heater < Heaters); uint32_t HeatSampleInterval() const; void SetHeatSampleTime(float st); float GetHeatSampleTime() const; - - Thermistor& GetThermistor(size_t heater) - pre(heater < HEATERS) - { - return thermistors[heater]; - } - - 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); - - bool IsLinearAdcChannel(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 // Fans - Fan& GetFan(size_t fanNumber) // Get access to the fan control object - pre(fanNumber < NUM_FANS) - { - return fans[fanNumber]; - } + bool ConfigureFan(unsigned int mcode, int fanNumber, GCodeBuffer& gb, StringRef& reply, bool& error); float GetFanValue(size_t fan) const; // Result is returned in percent void SetFanValue(size_t fan, float speed); // Accepts values between 0..1 and 1..255 -#ifndef DUET_NG +#if !defined(DUET_NG) && !defined(__RADDS__) & !defined(__ALLIGATOR__) void EnableSharedFan(bool enable); // enable/disable the fan that shares its PWM pin with the last heater #endif - float GetFanRPM(); + + float GetFanRPM() const; // Flash operations void UpdateFirmware(); @@ -592,6 +562,8 @@ public: #ifdef DUET_NG // Power in voltage void GetPowerVoltages(float& minV, float& currV, float& maxV) const; + float GetTmcDriversTemperature(unsigned int board) const; + void DriverCoolingFansOn(uint32_t driverChannelsMonitored); #endif // User I/O and servo support @@ -709,7 +681,7 @@ private: float pressureAdvance[MaxExtruders]; float motorCurrents[DRIVES]; // the normal motor current for each stepper driver float motorCurrentFraction[DRIVES]; // the percentages of normal motor current that each driver is set to - AxisDriversConfig axisDrivers[MAX_AXES]; // the driver numbers assigned to each axis + AxisDriversConfig axisDrivers[MaxAxes]; // the driver numbers assigned to each axis uint8_t extruderDrivers[MaxExtruders]; // the driver number assigned to each extruder uint32_t driveDriverBits[DRIVES]; // the bitmap of driver port bits for each axis or extruder uint32_t slowDriverStepPulseClocks; // minimum high and low step pulse widths, in processor clocks @@ -738,7 +710,7 @@ private: Pin zProbeModulationPin; volatile ZProbeAveragingFilter zProbeOnFilter; // Z probe readings we took with the IR turned on volatile ZProbeAveragingFilter zProbeOffFilter; // Z probe readings we took with the IR turned off - volatile ThermistorAveragingFilter thermistorFilters[HEATERS]; // bed and extruder thermistor readings + volatile ThermistorAveragingFilter thermistorFilters[Heaters]; // bed and extruder thermistor readings #ifndef __RADDS__ volatile ThermistorAveragingFilter cpuTemperatureFilter; // MCU temperature readings #endif @@ -755,19 +727,17 @@ private: // Axes and endstops - float axisMaxima[MAX_AXES]; - float axisMinima[MAX_AXES]; - EndStopType endStopType[MAX_AXES]; - bool endStopLogicLevel[MAX_AXES]; + float axisMaxima[MaxAxes]; + float axisMinima[MaxAxes]; + EndStopType endStopType[MaxAxes]; + bool endStopLogicLevel[MaxAxes]; // Heaters - bed is assumed to be the first - Pin tempSensePins[HEATERS]; - Pin heatOnPins[HEATERS]; - Thermistor thermistors[HEATERS]; - TemperatureSensor SpiTempSensors[MaxSpiTempSensors]; + Pin tempSensePins[Heaters]; + Pin heatOnPins[Heaters]; Pin spiTempSenseCsPins[MaxSpiTempSensors]; - uint32_t configuredHeaters; // bitmask of all heaters in use + uint32_t configuredHeaters; // bitmask of all real heaters in use uint32_t heatSampleTicks; // Fans @@ -830,8 +800,7 @@ private: // of the M305 command (e.g., SetThermistorNumber() and array lookups assume range // checking has already been performed. - unsigned int heaterTempChannels[HEATERS]; - AnalogChannelNumber thermistorAdcChannels[HEATERS]; + AnalogChannelNumber thermistorAdcChannels[Heaters]; AnalogChannelNumber zProbeAdcChannel; uint8_t tickState; size_t currentHeater; @@ -1144,29 +1113,6 @@ inline void Platform::SetHeatSampleTime(float st) } } -inline bool Platform::IsThermistorChannel(uint8_t heater) const -{ - return heaterTempChannels[heater] < HEATERS; -} - -inline bool Platform::IsThermocoupleChannel(uint8_t heater) const -{ - return heaterTempChannels[heater] >= FirstThermocoupleChannel - && heaterTempChannels[heater] - FirstThermocoupleChannel < MaxSpiTempSensors; -} - -inline bool Platform::IsRtdChannel(uint8_t heater) const -{ - return heaterTempChannels[heater] >= FirstRtdChannel - && heaterTempChannels[heater] - FirstRtdChannel < MaxSpiTempSensors; -} - -inline bool Platform::IsLinearAdcChannel(uint8_t heater) const -{ - return heaterTempChannels[heater] >= FirstLinearAdcChannel - && heaterTempChannels[heater] - FirstLinearAdcChannel < MaxSpiTempSensors; -} - inline const uint8_t* Platform::GetIPAddress() const { return ipAddress; diff --git a/src/PrintMonitor.cpp b/src/PrintMonitor.cpp index 63de1670..0c821d0e 100644 --- a/src/PrintMonitor.cpp +++ b/src/PrintMonitor.cpp @@ -85,7 +85,7 @@ void PrintMonitor::Spin() { // Check if there are any active heaters bool nozzleAtHighTemperature = false; - for(int heater = 0; heater < HEATERS; heater++) + for (int heater = 0; heater < (int)Heaters; heater++) { if (reprap.GetHeat().GetStatus(heater) == Heat::HS_active && reprap.GetHeat().GetActiveTemperature(heater) > TEMPERATURE_LOW_SO_DONT_CARE) { @@ -307,7 +307,7 @@ bool PrintMonitor::GetFileInfo(const char *directory, const char *fileName, GCod parsedFileInfo.layerHeight = 0.0; parsedFileInfo.numFilaments = 0; parsedFileInfo.generatedBy[0] = 0; - for(size_t extr = 0; extr < DRIVES - MIN_AXES; extr++) + for(size_t extr = 0; extr < MaxExtruders; extr++) { parsedFileInfo.filamentNeeded[extr] = 0.0; } @@ -379,7 +379,7 @@ bool PrintMonitor::GetFileInfo(const char *directory, const char *fileName, GCod // Search for filament usage (Cura puts it at the beginning of a G-code file) if (parsedFileInfo.numFilaments == 0) { - parsedFileInfo.numFilaments = FindFilamentUsed(buf, sizeToScan, parsedFileInfo.filamentNeeded, DRIVES - reprap.GetGCodes().GetNumAxes()); + parsedFileInfo.numFilaments = FindFilamentUsed(buf, sizeToScan, parsedFileInfo.filamentNeeded, DRIVES - reprap.GetGCodes().GetTotalAxes()); headerInfoComplete &= (parsedFileInfo.numFilaments != 0); } @@ -519,7 +519,7 @@ bool PrintMonitor::GetFileInfo(const char *directory, const char *fileName, GCod // Search for filament used if (parsedFileInfo.numFilaments == 0) { - parsedFileInfo.numFilaments = FindFilamentUsed(buf, sizeToScan, parsedFileInfo.filamentNeeded, DRIVES - reprap.GetGCodes().GetNumAxes()); + parsedFileInfo.numFilaments = FindFilamentUsed(buf, sizeToScan, parsedFileInfo.filamentNeeded, DRIVES - reprap.GetGCodes().GetTotalAxes()); if (parsedFileInfo.numFilaments == 0) { footerInfoComplete = false; @@ -779,7 +779,7 @@ float PrintMonitor::EstimateTimeLeft(PrintEstimationMethod method) const // Sum up the filament usage and the filament needed float totalFilamentNeeded = 0.0; const float extrRawTotal = gCodes.GetTotalRawExtrusion(); - for (size_t extruder = 0; extruder < DRIVES - reprap.GetGCodes().GetNumAxes(); extruder++) + for (size_t extruder = 0; extruder < DRIVES - reprap.GetGCodes().GetTotalAxes(); extruder++) { totalFilamentNeeded += printingFileInfo.filamentNeeded[extruder]; } diff --git a/src/PrintMonitor.h b/src/PrintMonitor.h index a028c819..71c705da 100644 --- a/src/PrintMonitor.h +++ b/src/PrintMonitor.h @@ -58,7 +58,7 @@ struct GCodeFileInfo time_t lastModifiedTime; float firstLayerHeight; float objectHeight; - float filamentNeeded[DRIVES - MIN_AXES]; + float filamentNeeded[MaxExtruders]; unsigned int numFilaments; float layerHeight; char generatedBy[50]; diff --git a/src/RADDS/Pins_RADDS.h b/src/RADDS/Pins_RADDS.h index 3ba0d735..9f8c023b 100644 --- a/src/RADDS/Pins_RADDS.h +++ b/src/RADDS/Pins_RADDS.h @@ -26,15 +26,14 @@ const size_t DRIVES = 8; // The number of heaters in the machine // 0 is the heated bed even if there isn't one. -const int8_t HEATERS = 4; +const size_t Heaters = 4; // Initialization macro used in statements needing to initialize values in arrays of size HEATERS. E.g., // defaultPidKis[HEATERS] = {HEATERS_(5.0, 0.1, 0.1, 0.1, 0.1, 0.1)}; #define HEATERS_(a,b,c,d,e,f,g,h) { a,b,c,d } -const unsigned int FirstVirtualHeater = 100; -const unsigned int NumVirtualHeaters = 0; // no virtual heaters on RADDS -const size_t MAX_AXES = 6; // The maximum number of movement axes in the machine, usually just X, Y and Z, <= DRIVES +const size_t MinAxes = 3; // The minimum and default number of axes +const size_t MaxAxes = 6; // The maximum number of movement axes in the machine, usually just X, Y and Z, <= DRIVES // Initialization macro used in statements needing to initialize values in arrays of size MAX_AXES #define AXES_(a,b,c,d,e,f) { a,b,c,d,e,f } @@ -77,14 +76,14 @@ const Pin END_STOP_PINS[DRIVES] = { 28, 30, 32, 39, NoPin, NoPin, NoPin, NoPin } const bool HEAT_ON = true; // Analogue pin numbers -const Pin TEMP_SENSE_PINS[HEATERS] = HEATERS_(4, 0, 1, 2, e, f, g, h); +const Pin TEMP_SENSE_PINS[Heaters] = HEATERS_(4, 0, 1, 2, e, f, g, h); // Heater outputs // Bed PMW: D7 has hardware PWM so bed has PWM // h0, h1 PMW: D13 & D12 are on TIOB0 & B8 which are both TC B channels, so they get PWM // h2 bang-bang: D11 is on TIOA8 which is a TC A channel shared with h1, it gets bang-bang control -const Pin HEAT_ON_PINS[HEATERS] = HEATERS_(7, 13, 12, 11, e, f, g, h); // bed, h0, h1, h2 +const Pin HEAT_ON_PINS[Heaters] = HEATERS_(7, 13, 12, 11, e, f, g, h); // bed, h0, h1, h2 // Default thermistor betas const float BED_R25 = 10000.0; diff --git a/src/RepRap.cpp b/src/RepRap.cpp index e727bf55..1dcd27c4 100644 --- a/src/RepRap.cpp +++ b/src/RepRap.cpp @@ -234,7 +234,7 @@ void RepRap::EmergencyStop() } heat->Exit(); - for(size_t heater = 0; heater < HEATERS; heater++) + for(size_t heater = 0; heater < Heaters; heater++) { platform->SetHeater(heater, 0.0); } @@ -479,7 +479,7 @@ void RepRap::Tick() if (ticksInSpinState >= 20000) // if we stall for 20 seconds, save diagnostic data and reset { resetting = true; - for(size_t i = 0; i < HEATERS; i++) + for(size_t i = 0; i < Heaters; i++) { platform->SetHeater(i, 0.0); } @@ -515,7 +515,7 @@ OutputBuffer *RepRap::GetStatusResponse(uint8_t type, ResponseSource source) response->printf("{\"status\":\"%c\",\"coords\":{", ch); // Coordinates - const size_t numAxes = reprap.GetGCodes().GetNumAxes(); + const size_t numAxes = reprap.GetGCodes().GetVisibleAxes(); { float liveCoordinates[DRIVES + 1]; #if SUPPORT_ROLAND @@ -684,49 +684,104 @@ OutputBuffer *RepRap::GetStatusResponse(uint8_t type, ResponseSource source) } /* Heads */ + response->cat("\"heads\":{\"current\":"); + + // Current temperatures + ch = '['; + for (size_t heater = DefaultE0Heater; heater < GetToolHeatersInUse(); heater++) + { + response->catf("%c%.1f", ch, heat->GetTemperature(heater)); + ch = ','; + } + response->cat((ch == '[') ? "[]" : "]"); + + // Active temperatures + response->catf(",\"active\":"); + ch = '['; + for (size_t heater = DefaultE0Heater; heater < GetToolHeatersInUse(); heater++) + { + response->catf("%c%.1f", ch, heat->GetActiveTemperature(heater)); + ch = ','; + } + response->cat((ch == '[') ? "[]" : "]"); + + // Standby temperatures + response->catf(",\"standby\":"); + ch = '['; + for (size_t heater = DefaultE0Heater; heater < GetToolHeatersInUse(); heater++) + { + response->catf("%c%.1f", ch, heat->GetStandbyTemperature(heater)); + ch = ','; + } + response->cat((ch == '[') ? "[]" : "]"); + + // Heater statuses (0=off, 1=standby, 2=active, 3=fault) + response->cat(",\"state\":"); + ch = '['; + for (size_t heater = DefaultE0Heater; heater < GetToolHeatersInUse(); heater++) { - response->cat("\"heads\":{\"current\":"); + response->catf("%c%d", ch, static_cast<int>(heat->GetStatus(heater))); + ch = ','; + } + response->cat((ch == '[') ? "[]" : "]"); - // Current temperatures + /* Tool temperatures */ + response->cat("},\"tools\":{\"active\":["); + for (const Tool *tool = toolList; tool != nullptr; tool = tool->Next()) + { ch = '['; - for (size_t heater = DefaultE0Heater; heater < GetToolHeatersInUse(); heater++) + for (size_t heater = 0; heater < tool->heaterCount; heater++) { - response->catf("%c%.1f", ch, heat->GetTemperature(heater)); + response->catf("%c%.1f", ch, tool->activeTemperatures[heater]); ch = ','; } response->cat((ch == '[') ? "[]" : "]"); - // Active temperatures - response->catf(",\"active\":"); - ch = '['; - for (size_t heater = DefaultE0Heater; heater < GetToolHeatersInUse(); heater++) + if (tool->Next() != nullptr) { - response->catf("%c%.1f", ch, heat->GetActiveTemperature(heater)); - ch = ','; + response->cat(","); } - response->cat((ch == '[') ? "[]" : "]"); + } - // Standby temperatures - response->catf(",\"standby\":"); + response->cat("],\"standby\":["); + for (const Tool *tool = toolList; tool != nullptr; tool = tool->Next()) + { ch = '['; - for (size_t heater = DefaultE0Heater; heater < GetToolHeatersInUse(); heater++) + for (size_t heater = 0; heater < tool->heaterCount; heater++) { - response->catf("%c%.1f", ch, heat->GetStandbyTemperature(heater)); + response->catf("%c%.1f", ch, tool->standbyTemperatures[heater]); ch = ','; } response->cat((ch == '[') ? "[]" : "]"); - // Heater statuses (0=off, 1=standby, 2=active, 3=fault) - response->cat(",\"state\":"); - ch = '['; - for (size_t heater = DefaultE0Heater; heater < GetToolHeatersInUse(); heater++) + if (tool->Next() != nullptr) { - response->catf("%c%d", ch, static_cast<int>(heat->GetStatus(heater))); - ch = ','; + response->cat(","); + } + } + + // Named extra temperature sensors + response->cat("]},\"extra\":["); + bool first = true; + for (size_t heater = FirstVirtualHeater; heater < FirstVirtualHeater + MaxVirtualHeaters; ++heater) + { + const char *nm = heat->GetHeaterName(heater); + if (nm != nullptr) + { + if (!first) + { + response->cat(','); + } + first = false; + response->cat("{\"name\":"); + response->EncodeString(nm, strlen(nm), false, true); + TemperatureError err; + const float t = heat->GetTemperature(heater, err); + response->catf(",\"temp\":%.1f}", t); } - response->cat((ch == '[') ? "[]" : "]"); } - response->cat("}}"); + + response->cat("]}"); } // Time since last reset @@ -825,7 +880,7 @@ OutputBuffer *RepRap::GetStatusResponse(uint8_t type, ResponseSource source) // Axis mapping. Currently we only map the X axis, but we return an array of arrays to allow for mapping other axes in future. response->cat("],\"axisMap\":[["); bool first = true; - for (size_t xi = 0; xi < MAX_AXES; ++xi) + for (size_t xi = 0; xi < MaxAxes; ++xi) { if ((tool->GetXAxisMap() & (1u << xi)) != 0) { @@ -948,7 +1003,7 @@ OutputBuffer *RepRap::GetConfigResponse() return nullptr; } - const size_t numAxes = reprap.GetGCodes().GetNumAxes(); + const size_t numAxes = reprap.GetGCodes().GetVisibleAxes(); // Axis minima response->copy("{\"axisMins\":"); @@ -1131,7 +1186,7 @@ OutputBuffer *RepRap::GetLegacyStatusResponse(uint8_t type, int seq) response->cat((ch == '[') ? "[]" : "]"); // Send XYZ positions - const size_t numAxes = reprap.GetGCodes().GetNumAxes(); + const size_t numAxes = reprap.GetGCodes().GetVisibleAxes(); float liveCoordinates[DRIVES]; reprap.GetMove().LiveCoordinates(liveCoordinates, GetCurrentXAxes()); const Tool* const currentTool = reprap.GetCurrentTool(); diff --git a/src/RepRapFirmware.h b/src/RepRapFirmware.h index 82c679fa..358b96d7 100644 --- a/src/RepRapFirmware.h +++ b/src/RepRapFirmware.h @@ -84,11 +84,38 @@ void SafeStrncat(char *dst, const char *src, size_t length) pre(length != 0); // Macro to assign an array from an initialiser list #define ARRAY_INIT(_dest, _init) static_assert(sizeof(_dest) == sizeof(_init), "Incompatible array types"); memcpy(_dest, _init, sizeof(_init)); +// Classes to facilitate range-based for loops that iterate from 0 up to just below a limit +template<class T> class SimpleRangeIterator +{ +public: + SimpleRangeIterator(T value_) : val(value_) {} + bool operator != (SimpleRangeIterator<T> const& other) const { return val != other.val; } + T const& operator*() const { return val; } + SimpleRangeIterator& operator++() { ++val; return *this; } + +private: + T val; +}; + +template<class T> class SimpleRange +{ +public: + SimpleRange(T limit) : _end(limit) {} + SimpleRangeIterator<T> begin() const { return SimpleRangeIterator<T>(0); } + SimpleRangeIterator<T> end() const { return SimpleRangeIterator<T>(_end); } + +private: + const T _end; +}; + +// Macro to create a SimpleRange from an array +#define ARRAY_INDICES(_arr) (SimpleRange<size_t>(ARRAY_SIZE(_arr))) + // A string buffer used for temporary purposes extern StringRef scratchString; // Common definitions used by more than one module -const size_t CART_AXES = 3; // The number of Cartesian axes +const size_t XYZ_AXES = 3; // The number of Cartesian axes const size_t X_AXIS = 0, Y_AXIS = 1, Z_AXIS = 2, E0_AXIS = 3; // The indices of the Cartesian axes in drive arrays // Common conversion factors diff --git a/src/Tool.cpp b/src/Tool.cpp index dcf1b14e..a46260eb 100644 --- a/src/Tool.cpp +++ b/src/Tool.cpp @@ -58,7 +58,7 @@ Tool * Tool::freelist = nullptr; } for (size_t i = 0; i < hCount; ++i) { - if (h[i] < 0 || h[i] >= HEATERS) + if (h[i] < 0 || h[i] >= (int)Heaters) { reprap.GetPlatform().Message(GENERIC_MESSAGE, "Error: Tool creation: bad heater number"); return nullptr; @@ -88,7 +88,7 @@ Tool * Tool::freelist = nullptr; t->displayColdExtrudeWarning = false; t->virtualExtruderPosition = 0.0; - for (size_t axis = 0; axis < MAX_AXES; axis++) + for (size_t axis = 0; axis < MaxAxes; axis++) { t->offset[axis] = 0.0; } @@ -142,7 +142,7 @@ void Tool::Print(StringRef& reply) reply.cat("; xmap:"); sep = ' '; - for (size_t xi = 0; xi < MAX_AXES; ++xi) + for (size_t xi = 0; xi < MaxAxes; ++xi) { if ((xMapping & (1u << xi)) != 0) { @@ -169,12 +169,11 @@ float Tool::MaxFeedrate() const { if (driveCount <= 0) { - reprap.GetPlatform().Message(GENERIC_MESSAGE, - "Error: Attempt to get maximum feedrate for a tool with no drives.\n"); + reprap.GetPlatform().Message(GENERIC_MESSAGE, "Error: Attempt to get maximum feedrate for a tool with no drives.\n"); return 1.0; } float result = 0.0; - const size_t numAxes = reprap.GetGCodes().GetNumAxes(); + const size_t numAxes = reprap.GetGCodes().GetTotalAxes(); for (size_t d = 0; d < driveCount; d++) { const float mf = reprap.GetPlatform().MaxFeedrate(drives[d] + numAxes); @@ -194,7 +193,7 @@ float Tool::InstantDv() const return 1.0; } float result = FLT_MAX; - const size_t numAxes = reprap.GetGCodes().GetNumAxes(); + const size_t numAxes = reprap.GetGCodes().GetTotalAxes(); for (size_t d = 0; d < driveCount; d++) { const float idv = reprap.GetPlatform().ActualInstantDv(drives[d] + numAxes); @@ -38,7 +38,7 @@ public: static void Delete(Tool *t); const float *GetOffset() const; - void SetOffset(const float offs[MAX_AXES]); + void SetOffset(const float offs[MaxAxes]); size_t DriveCount() const; int Drive(int driveNumber) const; bool ToolCanDrive(bool extrude); @@ -82,11 +82,11 @@ private: int drives[MaxExtruders]; float mix[MaxExtruders]; size_t driveCount; - int heaters[HEATERS]; - float activeTemperatures[HEATERS]; - float standbyTemperatures[HEATERS]; + int heaters[Heaters]; + float activeTemperatures[Heaters]; + float standbyTemperatures[Heaters]; size_t heaterCount; - float offset[MAX_AXES]; + float offset[MaxAxes]; uint32_t xMapping; uint32_t fanMapping; Tool* next; @@ -147,9 +147,9 @@ inline const float *Tool::GetOffset() const return offset; } -inline void Tool::SetOffset(const float offs[MAX_AXES]) +inline void Tool::SetOffset(const float offs[MaxAxes]) { - for(size_t i = 0; i < MAX_AXES; ++i) + for(size_t i = 0; i < MaxAxes; ++i) { offset[i] = offs[i]; } diff --git a/src/Version.h b/src/Version.h index d12c0310..8a642dda 100644 --- a/src/Version.h +++ b/src/Version.h @@ -9,11 +9,11 @@ #define SRC_VERSION_H_ #ifndef VERSION -# define VERSION "1.19beta5" +# define VERSION "1.19beta6" #endif #ifndef DATE -# define DATE "2017-06-04" +# define DATE "2017-06-10" #endif #define AUTHORS "reprappro, dc42, chrishamm, t3p3, dnewman" |