Version 1.16 beta 1 (more like an alpha)

Support up to 6 axes in many commands
Allow creation of additional axes in M584
Display delta paremners to 3dp instead of 2dp
Removed M126/M127 error messages
Delta calibration now supports bed tilt parameters
On Duet WiFi, delta calibration is now done in double precision maths
Added support for G4 S parameter
Bed compensation or delta calibration is now aborted if the probe was
triggered at the start or was not triggered by the end of the probing
move
Bug fix: JSON file list returned by M20 S2 is now terminated by \n
Bug fix: stupidly high temperatures were returned immediately after
power up in response to status requests
Bug fix: when using an analog Z probe, probing movements were sometimes
aborted  before the full depth had been probed but the firmware thought
that probing had terminated at the full depth
Bug fix: generic messages were sent to PanelDue in plain text format
This commit is contained in:
David Crocker 2016-10-16 22:07:10 +01:00
parent bc8c679e46
commit d89ec70dfc
24 changed files with 833 additions and 687 deletions

View file

@ -26,11 +26,11 @@ Licence: GPL
// Firmware name is now defined in the Pins file
#ifndef VERSION
# define VERSION "1.15e"
# define VERSION "1.16beta1"
#endif
#ifndef DATE
# define DATE "2016-10-02"
# define DATE "2016-10-16"
#endif
#define AUTHORS "reprappro, dc42, zpl, t3p3, dnewman"
@ -193,17 +193,6 @@ const float FILAMENT_WIDTH = 1.75; // Millimetres
#define CONFIG_FILE "config.g"
#define DEFAULT_FILE "default.g"
#define HOME_X_G "homex.g"
#define HOME_Y_G "homey.g"
#define HOME_Z_G "homez.g"
#define HOME_ALL_G "homeall.g"
#define HOME_DELTA_G "homedelta.g"
#define BED_EQUATION_G "bed.g"
#define PAUSE_G "pause.g"
#define RESUME_G "resume.g"
#define CANCEL_G "cancel.g"
#define STOP_G "stop.g"
#define SLEEP_G "sleep.g"
#define EOF_STRING "<!-- **EoF** -->"

View file

@ -29,7 +29,11 @@ const int8_t HEATERS = 8; // The number of heaters in the machine; 0 is the
#define HEATERS_(a,b,c,d,e,f,g,h) { a,b,c,d,e,f,g,h }
const size_t MaxDriversPerAxis = 4; // The maximum number of stepper drivers assigned to one axis
const size_t AXES = 3; // The number of movement axes in the machine, usually just X, Y and Z. <= DRIVES
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 MIN_AXES = 3; // The minimum and default number of axes
const size_t DELTA_AXES = 3; // The number of axis involved in delta movement
const size_t CART_AXES = 3; // The number of Cartesian axes
const size_t NUM_SERIAL_CHANNELS = 2; // The number of serial IO channels (USB and one auxiliary UART)
#define SERIAL_MAIN_DEVICE SerialUSB
#define SERIAL_AUX_DEVICE Serial

View file

@ -13,34 +13,6 @@ static size_t numTmc2660Drivers;
static bool driversPowered = false;
// Connections between Duet 0.6 and TMC2660-EVAL board:
// Driver signal name Eval board pin Our signal name Duet 0.6 expansion connector pin #
// SDI 29 MOSI 11 (TXD1)
// SDO 28 MISO 12 (RXD1)
// SCK 27 SCLK 33 (AD7/PA16)
// /CS 24 /CS 17 (PC5_PWMH1/E1_EN)
// GND 2,3,43,44 GND 2 (GND)
// INT_STEP 17 E1_STEP 15 (PC9_PWMH3)
// INT_DIR 18 E1_DIR 16 (PC3_PWMH0)
// ENN 8 connect to ground 2 (GND)
// CLK 23 connect to ground 2 (GND
// 5V_USB 5 +3.3V 3 (+3.3V)
// Connections between DuetNG 0.6 and TMC2660-EVAL board (now using USART0):
// Driver signal name Eval board pin Our signal name DuetNG 0.6 expansion connector pin #
// SDI 29 SPI1_MOSI 13 (SPI0_MOSI) was 29
// SDO 28 SPI1_MISO 14 (SPI0_MISO) was 30
// SCK 27 SPI1_SCLK 12 (SPI0_SCLK) was 28
// /CS 24 /CS 24 (E2_EN)
// GND 2,3,43,44 GND 2 (GND)
// INT_STEP 19 E2_STEP 19 (E2_STEP)
// INT_DIR 20 E2_DIR 20 (E2_DIR)
// ENN 8 connect to ground 2 (GND)
// CLK 23 connect to ground 2 (GND
// 5V_USB 5 +3.3V 3 (+3.3V)
// Pin assignments for the second prototype, using USART1 SPI
const Pin DriversClockPin = 15; // PB15/TIOA1
const Pin DriversMosiPin = 22; // PA13

File diff suppressed because it is too large Load diff

View file

@ -127,8 +127,13 @@ public:
void Diagnostics(MessageType mtype); // Send helpful information out
bool HaveIncomingData() const; // Is there something that we have to do?
size_t GetStackPointer() const; // Returns the current stack pointer
bool GetAxisIsHomed(uint8_t axis) const { return axisIsHomed[axis]; } // Is the axis at 0?
void SetAxisIsHomed(uint8_t axis) { axisIsHomed[axis] = true; } // Tell us that the axis is now homed
bool GetAxisIsHomed(unsigned int axis) const // Has the axis been homed?
{ return (axesHomed & (1 << axis)) != 0; }
void SetAxisIsHomed(unsigned int axis) // Tell us that the axis is now homed
{ axesHomed |= (1 << axis); }
void SetAxisNotHomed(unsigned int axis) // Tell us that the axis is not homed
{ axesHomed &= ~(1 << axis); }
float GetSpeedFactor() const { return speedFactor * minutesToSeconds; } // Return the current speed factor
float GetExtrusionFactor(size_t extruder) { return extrusionFactors[extruder]; } // Return the current extrusion factors
@ -136,10 +141,7 @@ public:
float GetRawExtruderTotalByDrive(size_t extruder) const; // Get the total extrusion since start of print, for one drive
float GetTotalRawExtrusion() const { return rawExtruderTotal; } // Get the total extrusion since start of print, all drives
bool HaveAux() const { return auxDetected; } // Any device on the AUX line?
bool IsFlashing() const { return isFlashing; } // Is a new firmware binary going to be flashed?
OutputBuffer *GetAuxGCodeReply(); // Returns cached G-Code reply for AUX devices and clears its reference
uint32_t GetAuxSeq() { return auxSeq; }
bool IsPaused() const;
bool IsPausing() const;
@ -151,8 +153,15 @@ public:
void CancelPrint(); // Cancel the current print
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; }
static const char axisLetters[MAX_AXES]; // 'X', 'Y', 'Z'
private:
enum class CannedMoveType : uint8_t { none, relative, absolute };
void FillGCodeBuffers(); // Get new data into the gcode buffers
void StartNextGCode(StringRef& reply); // Fetch a new GCode and process it
void DoFilePrint(GCodeBuffer* gb, StringRef& reply); // Get G Codes from a file and print them
@ -216,6 +225,7 @@ private:
GCodeBuffer* auxGCode; // this one is for the LCD display on the async serial interface
GCodeBuffer* fileMacroGCode; // ...
GCodeBuffer *gbCurrent;
bool active; // Live and running?
bool isPaused; // true if the print has been paused
bool dwellWaiting; // We are in a dwell
@ -232,19 +242,20 @@ private:
bool axesRelative;
GCodeMachineState stack[StackSize]; // State that we save when calling macro files
unsigned int stackPointer; // Push and Pop stack pointer
static const char axisLetters[AXES]; // 'X', 'Y', 'Z'
float axisScaleFactors[AXES]; // Scale XYZ coordinates by this factor (for Delta configurations)
float lastRawExtruderPosition[DRIVES - AXES]; // Extruder position of the last move fed into the Move class
float rawExtruderTotalByDrive[DRIVES - AXES]; // Total extrusion amount fed to Move class since starting print, before applying extrusion factor, per drive
size_t numAxes; // How many axes we have. DEDFAULT
float axisScaleFactors[MAX_AXES]; // Scale XYZ coordinates by this factor (for Delta configurations)
float lastRawExtruderPosition[DRIVES - MIN_AXES]; // Extruder position of the last move fed into the Move class
float rawExtruderTotalByDrive[DRIVES - MIN_AXES]; // Total extrusion amount fed to Move class since starting print, before applying extrusion factor, per drive
float rawExtruderTotal; // Total extrusion amount fed to Move class since starting print, before applying extrusion factor, summed over all drives
float record[DRIVES]; // Temporary store for move positions
float moveToDo[DRIVES+1]; // Where to go set by G1 etc
bool activeDrive[DRIVES]; // Is this drive involved in a move?
float cannedMoveCoords[DRIVES]; // Where to go or how much to move by in a canned cycle move, last is feed rate
float cannedFeedRate; // How fast to do it
CannedMoveType cannedMoveType[DRIVES]; // Is this drive involved in a canned cycle move?
bool offSetSet; // Are any axis offsets non-zero?
float distanceScale; // MM or inches
FileData fileBeingPrinted;
FileData fileToPrint;
FileStore* fileBeingWritten; // A file to write G Codes (or sometimes HTML) in
FileStore* fileBeingWritten; // A file to write G Codes (or sometimes HTML) to
uint16_t toBeHomed; // Bitmap of axes still to be homed
bool doingFileMacro; // Are we executing a macro file?
int oldToolNumber, newToolNumber; // Tools being changed
@ -254,18 +265,18 @@ private:
int probeCount; // Counts multiple probe points
int8_t cannedCycleMoveCount; // Counts through internal (i.e. not macro) canned cycle moves
bool cannedCycleMoveQueued; // True if a canned cycle move has been set
bool zProbesSet; // True if all Z probing is done and we can set the bed equation
float longWait; // Timer for things that happen occasionally (seconds)
bool limitAxes; // Don't think outside the box.
bool axisIsHomed[AXES]; // These record which of the axes have been homed
uint32_t axesHomed; // Bitmap of which axes have been homed
float pausedFanValues[NUM_FANS]; // Fan speeds when the print was paused
float speedFactor; // speed factor, including the conversion from mm/min to mm/sec, normally 1/60
float extrusionFactors[DRIVES - AXES]; // extrusion factors (normally 1.0)
float lastProbedZ; // the last height at which the Z probe stopped
float extrusionFactors[DRIVES - MIN_AXES]; // extrusion factors (normally 1.0)
// Z probe
float lastProbedZ; // the last height at which the Z probe stopped
bool zProbesSet; // True if all Z probing is done and we can set the bed equation
volatile bool zProbeTriggered; // Set by the step ISR when a move is aborted because the Z probe is triggered
bool auxDetected; // Have we processed at least one G-Code from an AUX device?
OutputBuffer *auxGCodeReply; // G-Code reply for AUX devices (special one because it is actually encapsulated before sending)
uint32_t auxSeq; // Sequence number for AUX devices
float simulationTime; // Accumulated simulation time
uint8_t simulationMode; // 0 = not simulating, 1 = simulating, >1 are simulation modes for debugging
FilePosition filePos; // The position we got up to in the file being printed
@ -308,26 +319,9 @@ inline bool GCodes::HaveIncomingData() const
platform->GCodeAvailable(SerialSource::AUX);
}
inline bool GCodes::AllAxesAreHomed() const
{
return axisIsHomed[X_AXIS] && axisIsHomed[Y_AXIS] && axisIsHomed[Z_AXIS];
}
inline void GCodes::SetAllAxesNotHomed()
{
axisIsHomed[X_AXIS] = axisIsHomed[Y_AXIS] = axisIsHomed[Z_AXIS] = false;
}
inline size_t GCodes::GetStackPointer() const
{
return stackPointer;
}
inline OutputBuffer *GCodes::GetAuxGCodeReply()
{
OutputBuffer *temp = auxGCodeReply;
auxGCodeReply = nullptr;
return temp;
}
#endif

View file

@ -43,7 +43,7 @@ void Heat::Init()
pids[heater]->Init(DefaultHotEndHeaterGain, DefaultHotEndHeaterTimeConstant, DefaultHotEndHeaterDeadTime, true);
}
}
lastTime = millis();
lastTime = millis() - platform->HeatSampleInterval(); // flag the PIDS as due for spinning
longWait = platform->Time();
coldExtrude = false;
active = true;
@ -210,12 +210,12 @@ void Heat::ResetFault(int8_t heater)
}
}
float Heat::GetAveragePWM(int8_t heater) const
float Heat::GetAveragePWM(size_t heater) const
{
return pids[heater]->GetAveragePWM();
}
uint32_t Heat::GetLastSampleTime(int8_t heater) const
uint32_t Heat::GetLastSampleTime(size_t heater) const
{
return pids[heater]->GetLastSampleTime();
}

View file

@ -42,11 +42,17 @@ public:
void AllowColdExtrude(); // Allow cold extrusion
void DenyColdExtrude(); // Deny cold extrusion
int8_t GetBedHeater() const; // Get hot bed heater number
void SetBedHeater(int8_t heater); // Set hot bed heater number
int8_t GetBedHeater() const // Get hot bed heater number
post(-1 <= result; result < HEATERS);
int8_t GetChamberHeater() const; // Get chamber heater number
void SetChamberHeater(int8_t heater); // Set chamber heater number
void SetBedHeater(int8_t heater) // Set hot bed heater number
pre(-1 <= heater; heater < HEATERS);
int8_t GetChamberHeater() const // Get chamber heater number
post(-1 <= result; result < HEATERS);
void SetChamberHeater(int8_t heater) // Set chamber heater number
pre(-1 <= heater; heater < HEATERS);
void SetActiveTemperature(int8_t heater, float t);
float GetActiveTemperature(int8_t heater) const;
@ -62,41 +68,40 @@ public:
bool AllHeatersAtSetTemperatures(bool includingBed) const; // Is everything at temperature within tolerance?
bool HeaterAtSetTemperature(int8_t heater) const; // Is a specific heater at temperature within tolerance?
void Diagnostics(MessageType mtype); // Output useful information
float GetAveragePWM(int8_t heater) const; // Return the running average PWM to the heater as a fraction in [0, 1].
float GetAveragePWM(size_t heater) const // Return the running average PWM to the heater as a fraction in [0, 1].
pre(heater < HEATERS);
bool UseSlowPwm(int8_t heater) const; // Queried by the Platform class
uint32_t GetLastSampleTime(int8_t heater) const;
uint32_t GetLastSampleTime(size_t heater) const
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
bool SetHeaterModel(size_t heater, float gain, float tc, float td, float maxPwm, bool usePid) // Set the heater process model
pre(heater < HEATERS);
bool IsModelUsed(size_t heater) const // Is the heater using the PID parameters calculated form the model?
pre(heater < HEATERS);
pre(heater < HEATERS);
void UseModel(size_t heater, bool b) // Use or don't use the model to provide the PID parameters
pre(heater < HEATERS);
pre(heater < HEATERS);
void GetHeaterProtection(size_t heater, float& maxTempExcursion, float& maxFaultTime) const
pre(heater < HEATERS)
{
pids[heater]->GetHeaterProtection(maxTempExcursion, maxFaultTime);
}
pre(heater < HEATERS);
void SetHeaterProtection(size_t heater, float maxTempExcursion, float maxFaultTime)
pre(heater < HEATERS)
{
pids[heater]->SetHeaterProtection(maxTempExcursion, maxFaultTime);
}
pre(heater < HEATERS);
private:
Platform* platform; // The instance of the RepRap hardware class
@ -174,4 +179,14 @@ inline void Heat::UseModel(size_t heater, bool b)
pids[heater]->UseModel(b);
}
inline void Heat::GetHeaterProtection(size_t heater, float& maxTempExcursion, float& maxFaultTime) const
{
pids[heater]->GetHeaterProtection(maxTempExcursion, maxFaultTime);
}
inline void Heat::SetHeaterProtection(size_t heater, float maxTempExcursion, float maxFaultTime)
{
pids[heater]->SetHeaterProtection(maxTempExcursion, maxFaultTime);
}
#endif

View file

@ -50,6 +50,7 @@ void PID::Init(float pGain, float pTc, float pTd, bool usePid)
useModel = true; // by default we use the model in this first release
averagePWM = lastPwm = 0.0;
heatingFaultCount = 0;
temperature = BAD_ERROR_TEMPERATURE;
// Time the sensor was last sampled. During startup, we use the current
// time as the initial value so as to not trigger an immediate warning from the Tick ISR.
@ -59,10 +60,10 @@ void PID::Init(float pGain, float pTc, float pTd, bool usePid)
// Set the process model
bool PID::SetModel(float gain, float tc, float td, float maxPwm, bool usePid)
{
bool rslt = model.SetParameters(gain, tc, td, maxPwm, usePid);
const bool rslt = model.SetParameters(gain, tc, td, maxPwm, usePid);
if (rslt)
{
float safeGain = (heater == reprap.GetHeat()->GetBedHeater() || heater == reprap.GetHeat()->GetChamberHeater())
const float safeGain = (heater == reprap.GetHeat()->GetBedHeater() || heater == reprap.GetHeat()->GetChamberHeater())
? 170.0 : 480.0;
if (gain > safeGain)
{
@ -105,6 +106,7 @@ void PID::SwitchOn()
}
else
{
//debugPrintf("Heater %d on temp %.1f\n", heater, temperature);
const float target = (active) ? activeTemperature : standbyTemperature;
const HeaterMode oldMode = mode;
mode = (temperature + TEMPERATURE_CLOSE_ENOUGH < target) ? HeaterMode::heating

View file

@ -82,16 +82,17 @@ void DDA::DebugPrintVector(const char *name, const float *vec, size_t len) const
void DDA::DebugPrint() const
{
const size_t numAxes = reprap.GetGCodes()->GetNumAxes();
debugPrintf("DDA:");
if (endCoordinatesValid)
{
float startCoordinates[AXES];
for (size_t i = 0; i < AXES; ++i)
float startCoordinates[MAX_AXES];
for (size_t i = 0; i < numAxes; ++i)
{
startCoordinates[i] = endCoordinates[i] - (totalDistance * directionVector[i]);
}
DebugPrintVector(" start", startCoordinates, AXES);
DebugPrintVector(" end", endCoordinates, AXES);
DebugPrintVector(" start", startCoordinates, numAxes);
DebugPrintVector(" end", endCoordinates, numAxes);
}
debugPrintf(" d=%f", totalDistance);
@ -100,14 +101,15 @@ void DDA::DebugPrint() const
"daccel=%f ddecel=%f cks=%u\n",
acceleration, requestedSpeed, topSpeed, startSpeed, endSpeed,
accelDistance, decelDistance, clocksNeeded);
ddm[0].DebugPrint('x', isDeltaMovement);
ddm[1].DebugPrint('y', isDeltaMovement);
ddm[2].DebugPrint('z', isDeltaMovement);
for (size_t i = AXES; i < DRIVES; ++i)
for (size_t axis = 0; axis < numAxes; ++axis)
{
ddm[axis].DebugPrint(reprap.GetGCodes()->axisLetters[axis], isDeltaMovement);
}
for (size_t i = numAxes; i < DRIVES; ++i)
{
if (ddm[i].state != DMState::idle)
{
ddm[i].DebugPrint((char)('0' + (i - AXES)), false);
ddm[i].DebugPrint((char)('0' + (i - numAxes)), false);
}
}
}
@ -148,16 +150,17 @@ bool DDA::Init(const GCodes::RawMove &nextMove, bool doMotorMapping)
const bool isSpecialDeltaMove = (move->IsDeltaMode() && !doMotorMapping);
float accelerations[DRIVES];
const float *normalAccelerations = reprap.GetPlatform()->Accelerations();
const size_t numAxes = reprap.GetGCodes()->GetNumAxes();
for (size_t drive = 0; drive < DRIVES; drive++)
{
accelerations[drive] = normalAccelerations[drive];
if (drive >= AXES || !doMotorMapping)
if (drive >= numAxes || !doMotorMapping)
{
endPoint[drive] = Move::MotorEndPointToMachine(drive, nextMove.coords[drive]);
}
int32_t delta;
if (drive < AXES)
if (drive < numAxes)
{
endCoordinates[drive] = nextMove.coords[drive];
delta = endPoint[drive] - positionNow[drive];
@ -168,7 +171,7 @@ bool DDA::Init(const GCodes::RawMove &nextMove, bool doMotorMapping)
}
DriveMovement& dm = ddm[drive];
if (drive < AXES && !isSpecialDeltaMove)
if (drive < numAxes && !isSpecialDeltaMove)
{
directionVector[drive] = nextMove.coords[drive] - prev->GetEndCoordinate(drive, false);
dm.state = (isDeltaMovement || delta != 0)
@ -187,12 +190,12 @@ bool DDA::Init(const GCodes::RawMove &nextMove, bool doMotorMapping)
dm.direction = (delta >= 0); // for now this is the direction of net movement, but gets adjusted later if it is a delta movement
realMove = true;
if (drive < Z_AXIS)
if (drive < numAxes && drive != Z_AXIS)
{
xyMoving = true;
}
if (drive >= AXES && xyMoving)
if (drive >= numAxes && xyMoving)
{
if (delta > 0)
{
@ -228,20 +231,27 @@ bool DDA::Init(const GCodes::RawMove &nextMove, bool doMotorMapping)
// This means that the user gets the feed rate that he asked for. It also makes the delta calculations simpler.
if (xyMoving || ddm[Z_AXIS].state == DMState::moving)
{
totalDistance = Normalise(directionVector, DRIVES, AXES);
if (isDeltaMovement)
{
// Add on the Z movement needed to compensate for bed tilt
const DeltaParameters& dparams = move->GetDeltaParams();
directionVector[Z_AXIS] += (directionVector[X_AXIS] * dparams.GetXTilt()) + (directionVector[Y_AXIS] * dparams.GetYTilt());
}
totalDistance = Normalise(directionVector, DRIVES, numAxes);
if (isDeltaMovement)
{
// The following are only needed when doing delta movements. We could defer computing them until Prepare(), which would make simulation faster.
a2plusb2 = fsquare(directionVector[X_AXIS]) + fsquare(directionVector[Y_AXIS]);
cKc = (int32_t)(directionVector[Z_AXIS] * DriveMovement::Kc);
const DeltaParameters& dparams = move->GetDeltaParams();
const float initialX = prev->GetEndCoordinate(X_AXIS, false);
const float initialY = prev->GetEndCoordinate(Y_AXIS, false);
const DeltaParameters& dparams = move->GetDeltaParams();
const float diagonalSquared = fsquare(dparams.GetDiagonal());
const float a2b2D2 = a2plusb2 * diagonalSquared;
for (size_t drive = 0; drive < AXES; ++drive)
for (size_t drive = 0; drive < DELTA_AXES; ++drive)
{
const float A = initialX - dparams.GetTowerX(drive);
const float B = initialY - dparams.GetTowerY(drive);
@ -271,11 +281,10 @@ bool DDA::Init(const GCodes::RawMove &nextMove, bool doMotorMapping)
if (drev > 0.0 && drev < totalDistance) // if the reversal point is within range
{
// Calculate how many steps we need to move up before reversing
float hrev = directionVector[Z_AXIS] * drev + sqrt(dSquaredMinusAsquaredMinusBsquared - 2 * drev * aAplusbB - a2plusb2 * fsquare(drev));
const float hrev = directionVector[Z_AXIS] * drev + sqrt(dSquaredMinusAsquaredMinusBsquared - 2 * drev * aAplusbB - a2plusb2 * fsquare(drev));
int32_t numStepsUp = (int32_t)((hrev - h0MinusZ0) * stepsPerMm);
// We may be almost at the peak height already, in which case we don't really have a reversal.
// We must not set reverseStartStep to 1, because then we would set the direction when Prepare() calls CalcStepTime(), before the previous move finishes.
if (numStepsUp < 1 || (dm.direction && (uint32_t)numStepsUp <= dm.totalSteps))
{
dm.mp.delta.reverseStartStep = dm.totalSteps + 1;
@ -326,7 +335,7 @@ bool DDA::Init(const GCodes::RawMove &nextMove, bool doMotorMapping)
// We use the Cartesian motion system to implement these moves, so the feed rate will be interpreted in Cartesian coordinates.
// This is wrong, we want the feed rate to apply to the drive that is moving the farthest.
float maxDistance = 0.0;
for (size_t axis = 0; axis < AXES; ++axis)
for (size_t axis = 0; axis < DELTA_AXES; ++axis)
{
if (normalisedDirectionVector[axis] > maxDistance)
{
@ -616,7 +625,7 @@ 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[AXES])
bool DDA::FetchEndPosition(volatile int32_t ep[DRIVES], volatile float endCoords[MAX_AXES])
{
for (size_t drive = 0; drive < DRIVES; ++drive)
{
@ -624,7 +633,7 @@ bool DDA::FetchEndPosition(volatile int32_t ep[DRIVES], volatile float endCoords
}
if (endCoordinatesValid)
{
for (size_t axis = 0; axis < AXES; ++axis)
for (size_t axis = 0; axis < MAX_AXES; ++axis)
{
endCoords[axis] = endCoordinates[axis];
}
@ -635,7 +644,8 @@ 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);
for (size_t axis = 0; axis < AXES; ++axis)
const size_t numAxes = reprap.GetGCodes()->GetNumAxes();
for (size_t axis = 0; axis < numAxes; ++axis)
{
endCoordinates[axis] = move[axis];
}
@ -652,9 +662,10 @@ pre(disableDeltaMapping || drive < AXES)
}
else
{
if (drive < AXES && !endCoordinatesValid)
const size_t numAxes = reprap.GetGCodes()->GetNumAxes();
if (drive < numAxes && !endCoordinatesValid)
{
reprap.GetMove()->MachineToEndPoint(endPoint, endCoordinates, AXES);
reprap.GetMove()->MachineToEndPoint(endPoint, endCoordinates, numAxes);
endCoordinatesValid = true;
}
return endCoordinates[drive];
@ -733,6 +744,7 @@ void DDA::Prepare()
goingSlow = false;
firstDM = nullptr;
const size_t numAxes = reprap.GetGCodes()->GetNumAxes();
for (size_t drive = 0; drive < DRIVES; ++drive)
{
DriveMovement& dm = ddm[drive];
@ -740,7 +752,7 @@ void DDA::Prepare()
{
dm.drive = drive;
reprap.GetPlatform()->EnableDrive(drive);
if (drive >= AXES)
if (drive >= numAxes)
{
dm.PrepareExtruder(*this, params, usePressureAdvance);
@ -782,7 +794,7 @@ void DDA::Prepare()
dm.nextStepTime = 0;
dm.stepInterval = 999999; // initialise to a large value so that we will calculate the time for just one step
dm.stepsTillRecalc = 0; // so that we don't skip the calculation
bool stepsToDo = (isDeltaMovement && drive < AXES)
bool stepsToDo = (isDeltaMovement && drive < numAxes)
? dm.CalcNextStepTimeDelta(*this, false)
: dm.CalcNextStepTimeCartesian(*this, false);
if (stepsToDo)
@ -834,21 +846,22 @@ pre(state == frozen)
else
{
unsigned int extrusions = 0, retractions = 0; // bitmaps of extruding and retracting drives
const size_t numAxes = reprap.GetGCodes()->GetNumAxes();
for (size_t i = 0; i < DRIVES; ++i)
{
DriveMovement& dm = ddm[i];
if (dm.state == DMState::moving)
{
reprap.GetPlatform()->SetDirection(i, dm.direction);
if (i >= AXES)
if (i >= numAxes)
{
if (dm.direction == FORWARDS)
{
extrusions |= (1 << (i - AXES));
extrusions |= (1 << (i - numAxes));
}
else
{
retractions |= (1 << (i - AXES));
retractions |= (1 << (i - numAxes));
}
}
}
@ -860,8 +873,8 @@ pre(state == frozen)
const unsigned int prohibitedMovements = reprap.GetProhibitedExtruderMovements(extrusions, retractions);
for (DriveMovement **dmpp = &firstDM; *dmpp != nullptr; )
{
bool thisDriveExtruding = (*dmpp)->drive >= AXES;
if (thisDriveExtruding && (prohibitedMovements & (1 << ((*dmpp)->drive - AXES))) != 0)
bool thisDriveExtruding = (*dmpp)->drive >= numAxes;
if (thisDriveExtruding && (prohibitedMovements & (1 << ((*dmpp)->drive - numAxes))) != 0)
{
*dmpp = (*dmpp)->nextDM;
}
@ -932,7 +945,8 @@ bool DDA::Step()
}
}
for (size_t drive = 0; drive < AXES; ++drive)
const size_t numAxes = reprap.GetGCodes()->GetNumAxes();
for (size_t drive = 0; drive < numAxes; ++drive)
{
if ((endStopsToCheck & (1 << drive)) != 0)
{
@ -1019,7 +1033,7 @@ bool DDA::Step()
firstDM = dm; // remove the chain from the list
while (dmToInsert != dm) // note that both of these may be nullptr
{
const bool hasMoreSteps = (isDeltaMovement && dmToInsert->drive < AXES)
const bool hasMoreSteps = (isDeltaMovement && dmToInsert->drive < DELTA_AXES)
? dmToInsert->CalcNextStepTimeDelta(*this, true)
: dmToInsert->CalcNextStepTimeCartesian(*this, true);
DriveMovement * const nextToInsert = dmToInsert->nextDM;
@ -1084,7 +1098,7 @@ void DDA::StopDrive(size_t drive)
endPoint[drive] += stepsLeft; // we were going backwards
}
dm.state = DMState::idle;
if (drive < AXES)
if (drive < reprap.GetGCodes()->GetNumAxes())
{
endCoordinatesValid = false; // the XYZ position is no longer valid
}
@ -1127,6 +1141,14 @@ void DDA::ReduceHomingSpeed()
InsertDM(&dm);
}
}
// We also need to adjust the total clocks needed, to prevent step errors being recorded
const uint32_t clocksSoFar = Platform::GetInterruptClocks() - moveStartTime;
if (clocksSoFar < clocksNeeded)
{
const uint32_t clocksLeft = clocksNeeded - clocksSoFar;
clocksNeeded += (uint32_t)(clocksLeft * (factor - 1.0));
}
}
}

View file

@ -53,7 +53,7 @@ public:
void SetDriveCoordinate(int32_t a, size_t drive); // Force an end point
void SetFeedRate(float rate) { requestedSpeed = rate; }
float GetEndCoordinate(size_t drive, bool disableDeltaMapping);
bool FetchEndPosition(volatile int32_t ep[DRIVES], volatile float endCoords[AXES]);
bool FetchEndPosition(volatile int32_t ep[DRIVES], volatile float endCoords[MAX_AXES]);
void SetPositions(const float move[], size_t numDrives); // Force the endpoints to be these
FilePosition GetFilePosition() const { return filePos; }
float GetRequestedSpeed() const { return requestedSpeed; }
@ -116,7 +116,7 @@ private:
FilePosition filePos; // The position in the SD card file after this move was read, or zero if not read fro SD card
int32_t endPoint[DRIVES]; // Machine coordinates of the endpoint
float endCoordinates[AXES]; // The Cartesian coordinates at the end of the move
float endCoordinates[MAX_AXES]; // The Cartesian coordinates at the end of the move
float directionVector[DRIVES]; // The normalised direction vector - first 3 are XYZ Cartesian coordinates even on a delta
float totalDistance; // How long is the move in hypercuboid space
float acceleration; // The acceleration to use

View file

@ -13,10 +13,11 @@ void DeltaParameters::Init()
diagonal = 0.0;
radius = 0.0;
xCorrection = yCorrection = zCorrection = 0.0;
xTilt = yTilt = 0.0;
printRadius = defaultPrintRadius;
homedHeight = defaultDeltaHomedHeight;
for (size_t axis = 0; axis < AXES; ++axis)
for (size_t axis = 0; axis < DELTA_AXES; ++axis)
{
endstopAdjustments[axis] = 0.0;
towerX[axis] = towerY[axis] = 0.0;
@ -50,7 +51,7 @@ void DeltaParameters::Recalc()
// Calculate the base carriage height when the printer is homed, i.e. the carriages are at the endstops less the corrections
const float tempHeight = diagonal; // any sensible height will do here
float machinePos[AXES];
float machinePos[DELTA_AXES];
InverseTransform(tempHeight, tempHeight, tempHeight, machinePos);
homedCarriageHeight = homedHeight + tempHeight - machinePos[Z_AXIS];
}
@ -67,14 +68,17 @@ void DeltaParameters::NormaliseEndstopAdjustments()
homedCarriageHeight += eav; // no need for a full recalc, this is sufficient
}
// Calculate the motor position for a single tower from a Cartesian coordinate
float DeltaParameters::Transform(const float machinePos[AXES], size_t axis) const
// Calculate the motor position for a single tower from a Cartesian coordinate.
float DeltaParameters::Transform(const float machinePos[DELTA_AXES], size_t axis) const
{
return machinePos[Z_AXIS]
+ sqrt(D2 - fsquare(machinePos[X_AXIS] - towerX[axis]) - fsquare(machinePos[Y_AXIS] - towerY[axis]));
return sqrt(D2 - fsquare(machinePos[X_AXIS] - towerX[axis]) - fsquare(machinePos[Y_AXIS] - towerY[axis]))
+ machinePos[Z_AXIS]
+ (machinePos[X_AXIS] * xTilt)
+ (machinePos[Y_AXIS] * yTilt);
}
void DeltaParameters::InverseTransform(float Ha, float Hb, float Hc, float machinePos[AXES]) const
// Calculate the Cartesian coordinates from the motor coordinates.
void DeltaParameters::InverseTransform(float Ha, float Hb, float Hc, float machinePos[DELTA_AXES]) const
{
const float Fa = coreFa + fsquare(Ha);
const float Fb = coreFb + fsquare(Hb);
@ -103,7 +107,7 @@ void DeltaParameters::InverseTransform(float Ha, float Hb, float Hc, float machi
float z = (minusHalfB - sqrtf(fsquare(minusHalfB) - A * C)) / A;
machinePos[X_AXIS] = (U * z - S) / Q;
machinePos[Y_AXIS] = (P - R * z) / Q;
machinePos[Z_AXIS] = z;
machinePos[Z_AXIS] = z - ((machinePos[X_AXIS] * xTilt) + (machinePos[Y_AXIS] * yTilt));
}
// Compute the derivative of height with respect to a parameter at the specified motor endpoints.
@ -113,7 +117,8 @@ void DeltaParameters::InverseTransform(float Ha, float Hb, float Hc, float machi
// 4 = X tower correction
// 5 = Y tower correction
// 6 = diagonal rod length
float DeltaParameters::ComputeDerivative(unsigned int deriv, float ha, float hb, float hc)
// 7, 8 = X tilt, Y tilt. We scale these by the printable radius to get sensible values in the range -1..1
floatc_t DeltaParameters::ComputeDerivative(unsigned int deriv, float ha, float hb, float hc)
{
const float perturb = 0.2; // perturbation amount in mm or degrees
DeltaParameters hiParams(*this), loParams(*this);
@ -122,50 +127,71 @@ float DeltaParameters::ComputeDerivative(unsigned int deriv, float ha, float hb,
case 0:
case 1:
case 2:
// Endstop corrections
break;
case 3:
hiParams.radius += perturb;
loParams.radius -= perturb;
hiParams.Recalc();
loParams.Recalc();
break;
case 4:
hiParams.xCorrection += perturb;
loParams.xCorrection -= perturb;
hiParams.Recalc();
loParams.Recalc();
break;
case 5:
hiParams.yCorrection += perturb;
loParams.yCorrection -= perturb;
hiParams.Recalc();
loParams.Recalc();
break;
case 6:
hiParams.diagonal += perturb;
loParams.diagonal -= perturb;
hiParams.Recalc();
loParams.Recalc();
break;
case 7:
case 8:
// X and Y tilt
break;
}
hiParams.Recalc();
loParams.Recalc();
float newPos[AXES];
float newPos[DELTA_AXES];
hiParams.InverseTransform((deriv == 0) ? ha + perturb : ha, (deriv == 1) ? hb + perturb : hb, (deriv == 2) ? hc + perturb : hc, newPos);
float zHi = newPos[Z_AXIS];
loParams.InverseTransform((deriv == 0) ? ha - perturb : ha, (deriv == 1) ? hb - perturb : hb, (deriv == 2) ? hc - perturb : hc, newPos);
float zLo = newPos[Z_AXIS];
if (deriv == 7)
{
return -newPos[X_AXIS]/printRadius;
}
if (deriv == 8)
{
return -newPos[Y_AXIS]/printRadius;
}
return (zHi - zLo)/(2 * perturb);
const float zHi = newPos[Z_AXIS];
loParams.InverseTransform((deriv == 0) ? ha - perturb : ha, (deriv == 1) ? hb - perturb : hb, (deriv == 2) ? hc - perturb : hc, newPos);
const float zLo = newPos[Z_AXIS];
return ((floatc_t)zHi - (floatc_t)zLo)/(2 * perturb);
}
// Perform 3, 4, 6 or 7-factor adjustment.
// Perform 3, 4, 6, 7, 8 or 9-factor adjustment.
// The input vector contains the following parameters in this order:
// X, Y and Z endstop adjustments
// If we are doing 4-factor adjustment, the next argument is the delta radius. Otherwise:
// X tower X position adjustment
// Y tower X position adjustment
// Z tower Y position adjustment
// Diagonal rod length adjustment
void DeltaParameters::Adjust(size_t numFactors, const float v[])
// Delta radius
// X tower position adjustment
// Y tower position adjustment
// Diagonal rod length adjustment - omitted if doing 8-factor calibration (remainder are moved down)
// X tilt adjustment
// Y tilt adjustment
void DeltaParameters::Adjust(size_t numFactors, const floatc_t v[])
{
const float oldCarriageHeightA = GetHomedCarriageHeight(A_AXIS); // save for later
@ -184,10 +210,21 @@ void DeltaParameters::Adjust(size_t numFactors, const float v[])
xCorrection += v[4];
yCorrection += v[5];
if (numFactors == 7)
if (numFactors == 7 || numFactors == 9)
{
diagonal += v[6];
}
if (numFactors == 8)
{
xTilt += v[6]/printRadius;
yTilt += v[7]/printRadius;
}
else if (numFactors == 9)
{
xTilt += v[7]/printRadius;
yTilt += v[8]/printRadius;
}
}
Recalc();
@ -198,13 +235,17 @@ void DeltaParameters::Adjust(size_t numFactors, const float v[])
const float heightError = GetHomedCarriageHeight(A_AXIS) - oldCarriageHeightA - v[0];
homedHeight -= heightError;
homedCarriageHeight -= heightError;
// Note: if we adjusted the X and Y tilts, and there are any endstop adjustments, then the homed position won't be exactly in the centre
// and changing the tilt will therefore affect the homed height. We ignore this for now. If it is ever significant, a second sutocalibration
// run will correct it.
}
void DeltaParameters::PrintParameters(StringRef& reply) const
{
reply.printf("Endstops X%.2f Y%.2f Z%.2f, height %.2f, diagonal %.2f, radius %.2f, xcorr %.2f, ycorr %.2f, zcorr %.2f\n",
reply.printf("Stops X%.3f Y%.3f Z%.3f height %.3f diagonal %.3f radius %.3f xcorr %.2f ycorr %.2f zcorr %.2f xtilt %.3f%% ytilt %.3f%%\n",
endstopAdjustments[A_AXIS], endstopAdjustments[B_AXIS], endstopAdjustments[C_AXIS], homedHeight, diagonal, radius,
xCorrection, yCorrection, zCorrection);
xCorrection, yCorrection, zCorrection, xTilt * 100.0, yTilt * 100.0);
}
// End

View file

@ -26,6 +26,8 @@ public:
float GetEndstopAdjustment(size_t axis) const { return endstopAdjustments[axis]; }
float GetHomedCarriageHeight(size_t axis) const { return homedCarriageHeight + endstopAdjustments[axis]; }
float GetPrintRadiusSquared() const { return printRadiusSquared; }
float GetXTilt() const { return xTilt; }
float GetYTilt() const { return yTilt; }
void Init();
void SetDiagonal(float d) { diagonal = d; Recalc(); }
@ -37,12 +39,14 @@ public:
void SetXCorrection(float angle) { xCorrection = angle; Recalc(); }
void SetYCorrection(float angle) { yCorrection = angle; Recalc(); }
void SetZCorrection(float angle) { zCorrection = angle; Recalc(); }
void SetXTilt(float tilt) { xTilt = tilt; }
void SetYTilt(float tilt) { yTilt = tilt; }
float Transform(const float machinePos[AXES], size_t axis) const; // Calculate the motor position for a single tower from a Cartesian coordinate
void InverseTransform(float Ha, float Hb, float Hc, float machinePos[AXES]) const; // Calculate the Cartesian position from the motor positions
float Transform(const float machinePos[DELTA_AXES], size_t axis) const; // Calculate the motor position for a single tower from a Cartesian coordinate
void InverseTransform(float Ha, float Hb, float Hc, float machinePos[DELTA_AXES]) const; // Calculate the Cartesian position from the motor positions
float ComputeDerivative(unsigned int deriv, float ha, float hb, float hc); // Compute the derivative of height with respect to a parameter at a set of motor endpoints
void Adjust(size_t numFactors, const float v[]); // Perform 3-, 4-, 6- or 7-factor adjustment
floatc_t ComputeDerivative(unsigned int deriv, float ha, float hb, float hc); // Compute the derivative of height with respect to a parameter at a set of motor endpoints
void Adjust(size_t numFactors, const floatc_t v[]); // Perform 3-, 4-, 6- or 7-factor adjustment
void PrintParameters(StringRef& reply) const; // Print all the parameters for debugging
private:
@ -56,14 +60,15 @@ private:
float diagonal; // The diagonal rod length, all 3 are assumed to be the same length
float radius; // The nominal delta radius, before any fine tuning of tower positions
float xCorrection, yCorrection, zCorrection; // Tower position corrections
float endstopAdjustments[AXES]; // How much above or below the ideal position each endstop is
float endstopAdjustments[DELTA_AXES]; // How much above or below the ideal position each endstop is
float printRadius;
float homedHeight;
float xTilt, yTilt; // How much we need to raise Z for each unit of movement in the +X and +Y directions
// Derived values
bool deltaMode; // True if this is a delta printer
float towerX[AXES]; // The X coordinate of each tower
float towerY[AXES]; // The Y coordinate of each tower
float towerX[DELTA_AXES]; // The X coordinate of each tower
float towerY[DELTA_AXES]; // The Y coordinate of each tower
float printRadiusSquared;
float homedCarriageHeight;
float Xbc, Xca, Xab, Ybc, Yca, Yab;

View file

@ -82,7 +82,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 - AXES) : 0.0;
const float compensationTime = (doCompensation && dv > 0.0) ? reprap.GetPlatform()->GetPressureAdvance(drive - reprap.GetGCodes()->GetNumAxes()) : 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.

View file

@ -29,7 +29,7 @@ void Move::Init()
// Reset Cartesian mode
deltaParams.Init();
coreXYMode = 0;
for (size_t axis = 0; axis < AXES; ++axis)
for (size_t axis = 0; axis < MAX_AXES; ++axis)
{
axisFactors[axis] = 1.0;
}
@ -375,12 +375,14 @@ FilePosition Move::PausePrint(float positions[DRIVES], float& pausedFeedRate)
if (ddaRingAddPointer != savedDdaRingAddPointer)
{
const size_t numAxes = reprap.GetGCodes()->GetNumAxes();
// We are going to skip some moves. dda points to the last move we are going to print.
for (size_t axis = 0; axis < AXES; ++axis)
for (size_t axis = 0; axis < numAxes; ++axis)
{
positions[axis] = dda->GetEndCoordinate(axis, false);
}
for (size_t drive = AXES; drive < DRIVES; ++drive)
for (size_t drive = numAxes; drive < DRIVES; ++drive)
{
positions[drive] = 0.0; // clear out extruder movement
}
@ -390,7 +392,7 @@ FilePosition Move::PausePrint(float positions[DRIVES], float& pausedFeedRate)
dda = ddaRingAddPointer;
do
{
for (size_t drive = AXES; drive < DRIVES; ++drive)
for (size_t drive = numAxes; drive < DRIVES; ++drive)
{
positions[drive] += dda->GetEndCoordinate(drive, true); // update the amount of extrusion we are going to skip
}
@ -414,6 +416,7 @@ FilePosition Move::PausePrint(float positions[DRIVES], float& pausedFeedRate)
uint32_t maxReps = 0;
#if 0
// For debugging
extern uint32_t sqSum1, sqSum2, sqCount, sqErrors, lastRes1, lastRes2;
extern uint64_t lastNum;
#endif
@ -428,6 +431,7 @@ void Move::Diagnostics(MessageType mtype)
longestGcodeWaitInterval = 0;
#if 0
// For debugging
if (sqCount != 0)
{
reprap.GetPlatform()->AppendMessage(GENERIC_MESSAGE, "Average sqrt times %.2f, %.2f, count %u, errors %u, last %" PRIu64 " %u %u\n",
@ -453,7 +457,8 @@ void Move::SetPositions(const float move[DRIVES])
void Move::EndPointToMachine(const float coords[], int32_t ep[], size_t numDrives) const
{
MotorTransform(coords, ep);
for (size_t drive = AXES; drive < numDrives; ++drive)
const size_t numAxes = reprap.GetGCodes()->GetNumAxes();
for (size_t drive = numAxes; drive < numDrives; ++drive)
{
ep[drive] = MotorEndPointToMachine(drive, coords[drive]);
}
@ -523,18 +528,18 @@ void Move::MachineToEndPoint(const int32_t motorPos[], float machinePos[], size_
}
// Convert the extruders
for (size_t drive = AXES; drive < numDrives; ++drive)
for (size_t drive = reprap.GetGCodes()->GetNumAxes(); drive < numDrives; ++drive)
{
machinePos[drive] = motorPos[drive]/stepsPerUnit[drive];
}
}
// Convert Cartesian coordinates to motor steps
void Move::MotorTransform(const float machinePos[AXES], int32_t motorPos[AXES]) const
void Move::MotorTransform(const float machinePos[MAX_AXES], int32_t motorPos[MAX_AXES]) const
{
if (IsDeltaMode())
{
for (size_t axis = 0; axis < AXES; ++axis)
for (size_t axis = 0; axis < DELTA_AXES; ++axis)
{
motorPos[axis] = MotorEndPointToMachine(axis, deltaParams.Transform(machinePos, axis));
}
@ -546,7 +551,8 @@ void Move::MotorTransform(const float machinePos[AXES], int32_t motorPos[AXES])
}
else
{
for (size_t axis = 0; axis < AXES; ++axis)
const size_t numAxes = reprap.GetGCodes()->GetNumAxes();
for (size_t axis = 0; axis < numAxes; ++axis)
{
motorPos[axis] = MotorEndPointToMachine(axis, MotorFactor(axis, machinePos));
}
@ -602,33 +608,35 @@ float Move::MotorFactor(size_t drive, const float directionVector[]) const
}
// Do the Axis transform BEFORE the bed transform
void Move::AxisTransform(float xyzPoint[AXES]) const
void Move::AxisTransform(float xyzPoint[MAX_AXES]) const
{
//TODO should we transform U axis instead of/as well as X if we are in dual carriage mode?
xyzPoint[X_AXIS] = xyzPoint[X_AXIS] + tanXY*xyzPoint[Y_AXIS] + tanXZ*xyzPoint[Z_AXIS];
xyzPoint[Y_AXIS] = xyzPoint[Y_AXIS] + tanYZ*xyzPoint[Z_AXIS];
}
// Invert the Axis transform AFTER the bed transform
void Move::InverseAxisTransform(float xyzPoint[AXES]) const
void Move::InverseAxisTransform(float xyzPoint[MAX_AXES]) const
{
//TODO should we transform U axis instead of/as well as X if we are in dual carriage mode?
xyzPoint[Y_AXIS] = xyzPoint[Y_AXIS] - tanYZ*xyzPoint[Z_AXIS];
xyzPoint[X_AXIS] = xyzPoint[X_AXIS] - (tanXY*xyzPoint[Y_AXIS] + tanXZ*xyzPoint[Z_AXIS]);
}
void Move::Transform(float xyzPoint[AXES]) const
void Move::Transform(float xyzPoint[MAX_AXES]) const
{
AxisTransform(xyzPoint);
BedTransform(xyzPoint);
}
void Move::InverseTransform(float xyzPoint[AXES]) const
void Move::InverseTransform(float xyzPoint[MAX_AXES]) const
{
InverseBedTransform(xyzPoint);
InverseAxisTransform(xyzPoint);
}
// Do the bed transform AFTER the axis transform
void Move::BedTransform(float xyzPoint[AXES]) const
void Move::BedTransform(float xyzPoint[MAX_AXES]) const
{
switch(numBedCompensationPoints)
{
@ -636,15 +644,15 @@ void Move::BedTransform(float xyzPoint[AXES]) const
break;
case 3:
xyzPoint[Z_AXIS] = xyzPoint[Z_AXIS] + aX*xyzPoint[X_AXIS] + aY*xyzPoint[Y_AXIS] + aC;
xyzPoint[Z_AXIS] += aX*xyzPoint[X_AXIS] + aY*xyzPoint[Y_AXIS] + aC;
break;
case 4:
xyzPoint[Z_AXIS] = xyzPoint[Z_AXIS] + SecondDegreeTransformZ(xyzPoint[X_AXIS], xyzPoint[Y_AXIS]);
xyzPoint[Z_AXIS] += SecondDegreeTransformZ(xyzPoint[X_AXIS], xyzPoint[Y_AXIS]);
break;
case 5:
xyzPoint[Z_AXIS] = xyzPoint[Z_AXIS] + TriangleZ(xyzPoint[X_AXIS], xyzPoint[Y_AXIS]);
xyzPoint[Z_AXIS] += TriangleZ(xyzPoint[X_AXIS], xyzPoint[Y_AXIS]);
break;
default:
@ -653,7 +661,7 @@ void Move::BedTransform(float xyzPoint[AXES]) const
}
// Invert the bed transform BEFORE the axis transform
void Move::InverseBedTransform(float xyzPoint[AXES]) const
void Move::InverseBedTransform(float xyzPoint[MAX_AXES]) const
{
switch(numBedCompensationPoints)
{
@ -661,15 +669,15 @@ void Move::InverseBedTransform(float xyzPoint[AXES]) const
break;
case 3:
xyzPoint[Z_AXIS] = xyzPoint[Z_AXIS] - (aX*xyzPoint[X_AXIS] + aY*xyzPoint[Y_AXIS] + aC);
xyzPoint[Z_AXIS] -= (aX*xyzPoint[X_AXIS] + aY*xyzPoint[Y_AXIS] + aC);
break;
case 4:
xyzPoint[Z_AXIS] = xyzPoint[Z_AXIS] - SecondDegreeTransformZ(xyzPoint[X_AXIS], xyzPoint[Y_AXIS]);
xyzPoint[Z_AXIS] -= SecondDegreeTransformZ(xyzPoint[X_AXIS], xyzPoint[Y_AXIS]);
break;
case 5:
xyzPoint[Z_AXIS] = xyzPoint[Z_AXIS] - TriangleZ(xyzPoint[X_AXIS], xyzPoint[Y_AXIS]);
xyzPoint[Z_AXIS] -= TriangleZ(xyzPoint[X_AXIS], xyzPoint[Y_AXIS]);
break;
default:
@ -765,6 +773,7 @@ float Move::TriangleZ(float x, float y) const
void Move::FinishedBedProbing(int sParam, StringRef& reply)
{
const int numPoints = NumberOfProbePoints();
if (sParam < 0)
{
// A negative sParam just prints the probe heights
@ -773,12 +782,19 @@ void Move::FinishedBedProbing(int sParam, StringRef& reply)
float sumOfSquares = 0.0;
for (size_t i = 0; (int)i < numPoints; ++i)
{
reply.catf(" %.3f", zBedProbePoints[i]);
sum += zBedProbePoints[i];
sumOfSquares += fsquare(zBedProbePoints[i]);
if ((probePointSet[i] & (xSet | ySet | zSet | probeError)) != (xSet | ySet | zSet))
{
reply.cat(" failed");
}
else
{
reply.catf(" %.3f", zBedProbePoints[i]);
sum += zBedProbePoints[i];
sumOfSquares += fsquare(zBedProbePoints[i]);
}
}
const float mean = sum/numPoints;
reply.catf(", mean %.3f, deviation from mean %.3f\n", mean, sqrt(sumOfSquares/numPoints - fsquare(mean)));
reply.catf(", mean %.3f, deviation from mean %.3f", mean, sqrt(sumOfSquares/numPoints - fsquare(mean)));
}
else if (numPoints < sParam)
{
@ -807,7 +823,22 @@ void Move::FinishedBedProbing(int sParam, StringRef& reply)
sParam = numPoints;
}
if (IsDeltaMode())
// Check that all probe points are set and there were no errors
bool hadError = false;
for (size_t i = 0; (int)i < numPoints; ++i)
{
if ((probePointSet[i] & (xSet | ySet | zSet | probeError)) != (xSet | ySet | zSet))
{
hadError = true;
break;
}
}
if (hadError)
{
reply.cat("Compensation or calibration cancelled due to probing errors");
}
else if (IsDeltaMode())
{
DoDeltaCalibration(sParam, reply);
}
@ -815,13 +846,13 @@ void Move::FinishedBedProbing(int sParam, StringRef& reply)
{
SetProbedBedEquation(sParam, reply);
}
}
// Clear out the Z heights so that we don't re-use old points.
// This allows us to use different numbers of probe point on different occasions.
for (size_t i = 0; i < MAX_PROBE_POINTS; ++i)
{
probePointSet[i] &= ~zSet;
}
// Clear out the Z heights so that we don't re-use old points.
// This allows us to use different numbers of probe point on different occasions.
for (size_t i = 0; i < MAX_PROBE_POINTS; ++i)
{
probePointSet[i] &= ~zSet;
}
}
@ -900,11 +931,11 @@ void Move::SetProbedBedEquation(size_t numPoints, StringRef& reply)
}
// Perform 3-, 4-, 6- or 7-factor delta adjustment
void Move::AdjustDeltaParameters(const float v[], size_t numFactors)
void Move::AdjustDeltaParameters(const floatc_t v[], size_t numFactors)
{
// Save the old home carriage heights
float homedCarriageHeights[AXES];
for (size_t drive = 0; drive < AXES; ++drive)
float homedCarriageHeights[DELTA_AXES];
for (size_t drive = 0; drive < DELTA_AXES; ++drive)
{
homedCarriageHeights[drive] = deltaParams.GetHomedCarriageHeight(drive);
}
@ -916,7 +947,7 @@ void Move::AdjustDeltaParameters(const float v[], size_t numFactors)
const int32_t *endCoordinates = lastQueuedMove->DriveCoordinates();
const float *driveStepsPerUnit = reprap.GetPlatform()->GetDriveStepsPerUnit();
for (size_t drive = 0; drive < AXES; ++drive)
for (size_t drive = 0; drive < DELTA_AXES; ++drive)
{
const float heightAdjust = deltaParams.GetHomedCarriageHeight(drive) - homedCarriageHeights[drive];
int32_t ep = endCoordinates[drive] + (int32_t)(heightAdjust * driveStepsPerUnit[drive]);
@ -931,12 +962,12 @@ void Move::AdjustDeltaParameters(const float v[], size_t numFactors)
// or the X positions of the front two towers, the Y position of the rear tower, and the diagonal rod length.
void Move::DoDeltaCalibration(size_t numFactors, StringRef& reply)
{
const size_t NumDeltaFactors = 7; // number of delta machine factors we can adjust
const size_t NumDeltaFactors = 9; // maximum number of delta machine factors we can adjust
const size_t numPoints = NumberOfProbePoints();
if (numFactors != 3 && numFactors != 4 && numFactors != 6 && numFactors != 7)
if (numFactors < 3 || numFactors > NumDeltaFactors || numFactors == 5)
{
reprap.GetPlatform()->MessageF(GENERIC_MESSAGE, "Delta calibration error: %d factors requested but only 3, 4, 6 and 7 supported\n", numFactors);
reprap.GetPlatform()->MessageF(GENERIC_MESSAGE, "Delta calibration error: %d factors requested but only 3, 4, 6, 7, 8 and 9 supported\n", numFactors);
return;
}
@ -950,13 +981,13 @@ void Move::DoDeltaCalibration(size_t numFactors, StringRef& reply)
//uint32_t startTime = reprap.GetPlatform()->GetInterruptClocks();
// Transform the probing points to motor endpoints and store them in a matrix, so that we can do multiple iterations using the same data
FixedMatrix<float, MAX_DELTA_PROBE_POINTS, AXES> probeMotorPositions;
float corrections[MAX_DELTA_PROBE_POINTS];
float initialSumOfSquares = 0.0;
FixedMatrix<floatc_t, MAX_DELTA_PROBE_POINTS, DELTA_AXES> probeMotorPositions;
floatc_t corrections[MAX_DELTA_PROBE_POINTS];
float_t initialSumOfSquares = 0.0;
for (size_t i = 0; i < numPoints; ++i)
{
corrections[i] = 0.0;
float machinePos[AXES];
float machinePos[DELTA_AXES];
float xp = xBedProbePoints[i], yp = yBedProbePoints[i];
if (probePointSet[i] & xyCorrected)
{
@ -981,14 +1012,15 @@ void Move::DoDeltaCalibration(size_t numFactors, StringRef& reply)
float expectedRmsError;
for (;;)
{
// Build a Nx7 matrix of derivatives with respect to xa, xb, yc, za, zb, zc, diagonal.
FixedMatrix<float, MAX_DELTA_PROBE_POINTS, NumDeltaFactors> derivativeMatrix;
// Build a Nx9 matrix of derivatives with respect to xa, xb, yc, za, zb, zc, diagonal.
FixedMatrix<floatc_t, MAX_DELTA_PROBE_POINTS, NumDeltaFactors> derivativeMatrix;
for (size_t i = 0; i < numPoints; ++i)
{
for (size_t j = 0; j < numFactors; ++j)
{
const size_t adjustedJ = (numFactors == 8 && j >= 6) ? j + 1 : j; // skip diagonal rod length if doing 8-factor calibration
derivativeMatrix(i, j) =
deltaParams.ComputeDerivative(j, probeMotorPositions(i, A_AXIS), probeMotorPositions(i, B_AXIS), probeMotorPositions(i, C_AXIS));
deltaParams.ComputeDerivative(adjustedJ, probeMotorPositions(i, A_AXIS), probeMotorPositions(i, B_AXIS), probeMotorPositions(i, C_AXIS));
}
}
@ -998,19 +1030,19 @@ void Move::DoDeltaCalibration(size_t numFactors, StringRef& reply)
}
// Now build the normal equations for least squares fitting
FixedMatrix<float, NumDeltaFactors, NumDeltaFactors + 1> normalMatrix;
FixedMatrix<floatc_t, NumDeltaFactors, NumDeltaFactors + 1> normalMatrix;
for (size_t i = 0; i < numFactors; ++i)
{
for (size_t j = 0; j < numFactors; ++j)
{
float temp = derivativeMatrix(0, i) * derivativeMatrix(0, j);
floatc_t temp = derivativeMatrix(0, i) * derivativeMatrix(0, j);
for (size_t k = 1; k < numPoints; ++k)
{
temp += derivativeMatrix(k, i) * derivativeMatrix(k, j);
}
normalMatrix(i, j) = temp;
}
float temp = derivativeMatrix(0, i) * -(zBedProbePoints[0] + corrections[0]);
floatc_t temp = derivativeMatrix(0, i) * -(zBedProbePoints[0] + corrections[0]);
for (size_t k = 1; k < numPoints; ++k)
{
temp += derivativeMatrix(k, i) * -(zBedProbePoints[k] + corrections[k]);
@ -1023,7 +1055,7 @@ void Move::DoDeltaCalibration(size_t numFactors, StringRef& reply)
PrintMatrix("Normal matrix", normalMatrix, numFactors, numFactors + 1);
}
float solution[NumDeltaFactors];
floatc_t solution[NumDeltaFactors];
normalMatrix.GaussJordan(solution, numFactors);
if (reprap.Debug(moduleMove))
@ -1032,7 +1064,7 @@ void Move::DoDeltaCalibration(size_t numFactors, StringRef& reply)
PrintVector("Solution", solution, numFactors);
// Calculate and display the residuals
float residuals[MAX_DELTA_PROBE_POINTS];
floatc_t residuals[MAX_DELTA_PROBE_POINTS];
for (size_t i = 0; i < numPoints; ++i)
{
residuals[i] = zBedProbePoints[i];
@ -1045,20 +1077,19 @@ void Move::DoDeltaCalibration(size_t numFactors, StringRef& reply)
PrintVector("Residuals", residuals, numPoints);
}
AdjustDeltaParameters(solution, numFactors);
// Calculate the expected probe heights using the new parameters
{
float expectedResiduals[MAX_DELTA_PROBE_POINTS];
float sumOfSquares = 0.0;
floatc_t expectedResiduals[MAX_DELTA_PROBE_POINTS];
floatc_t sumOfSquares = 0.0;
for (size_t i = 0; i < numPoints; ++i)
{
for (size_t axis = 0; axis < AXES; ++axis)
for (size_t axis = 0; axis < DELTA_AXES; ++axis)
{
probeMotorPositions(i, axis) += solution[axis];
}
float newPosition[AXES];
float newPosition[DELTA_AXES];
deltaParams.InverseTransform(probeMotorPositions(i, A_AXIS), probeMotorPositions(i, B_AXIS), probeMotorPositions(i, C_AXIS), newPosition);
corrections[i] = newPosition[Z_AXIS];
expectedResiduals[i] = zBedProbePoints[i] + newPosition[Z_AXIS];
@ -1073,7 +1104,7 @@ void Move::DoDeltaCalibration(size_t numFactors, StringRef& reply)
}
}
// Decide whether to do another iteration Two is slightly better than one, but three doesn't improve things.
// Decide whether to do another iteration. Two is slightly better than one, but three doesn't improve things.
// Alternatively, we could stop when the expected RMS error is only slightly worse than the RMS of the residuals.
++iteration;
if (iteration == 2) break;
@ -1187,7 +1218,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 < AXES && !IsDeltaMode()) // should always be true
if (axis < reprap.GetGCodes()->GetNumAxes() && !IsDeltaMode()) // should always be true
{
float hitPoint;
if (axis == Z_AXIS)
@ -1207,7 +1238,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 < AXES) // should always be true
if (axis < reprap.GetGCodes()->GetNumAxes()) // should always be true
{
float hitPoint = (IsDeltaMode())
? deltaParams.GetHomedCarriageHeight(axis)
@ -1223,13 +1254,13 @@ void Move::JustHomed(size_t axisHomed, float hitPoint, DDA* hitDDA)
{
if (IsCoreXYAxis(axisHomed))
{
float tempCoordinates[AXES];
for (size_t axis = 0; axis < AXES; ++axis)
float tempCoordinates[CART_AXES];
for (size_t axis = 0; axis < CART_AXES; ++axis)
{
tempCoordinates[axis] = hitDDA->GetEndCoordinate(axis, false);
}
tempCoordinates[axisHomed] = hitPoint;
hitDDA->SetPositions(tempCoordinates, AXES);
hitDDA->SetPositions(tempCoordinates, CART_AXES);
}
else
{
@ -1239,20 +1270,21 @@ void Move::JustHomed(size_t axisHomed, float hitPoint, 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'.
// This is called from the step ISR. Any variables it modifies that are also read by code outside the ISR should be declared 'volatile'.
// The move has already been aborted when this is called, so the endpoints in the DDA are the current motor positions.
void Move::ZProbeTriggered(DDA* hitDDA)
{
// Currently, we don't need to do anything here
reprap.GetGCodes()->MoveStoppedByZProbe();
}
// Return the untransformed machine coordinates
void Move::GetCurrentMachinePosition(float m[DRIVES], bool disableMotorMapping) const
{
DDA *lastQueuedMove = ddaRingAddPointer->GetPrevious();
const size_t numAxes = reprap.GetGCodes()->GetNumAxes();
for (size_t i = 0; i < DRIVES; i++)
{
if (i < AXES)
if (i < numAxes)
{
m[i] = lastQueuedMove->GetEndCoordinate(i, disableMotorMapping);
}
@ -1302,17 +1334,18 @@ void Move::LiveCoordinates(float m[DRIVES])
else
{
// Only the extruder coordinates are valid, so we need to convert the motor endpoints to coordinates
memcpy(m + AXES, const_cast<const float *>(liveCoordinates + AXES), sizeof(m[0]) * (DRIVES - AXES));
int32_t tempEndPoints[AXES];
const size_t numAxes = reprap.GetGCodes()->GetNumAxes();
memcpy(m + numAxes, const_cast<const float *>(liveCoordinates + numAxes), sizeof(m[0]) * (DRIVES - numAxes));
int32_t tempEndPoints[MAX_AXES];
memcpy(tempEndPoints, const_cast<const int32_t*>(liveEndPoints), sizeof(tempEndPoints));
cpu_irq_enable();
MachineToEndPoint(tempEndPoints, m, AXES); // this is slow, so do it with interrupts enabled
MachineToEndPoint(tempEndPoints, m, numAxes); // 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]) * AXES);
memcpy(const_cast<float *>(liveCoordinates), m, sizeof(m[0]) * numAxes);
liveCoordinatesValid = true;
}
cpu_irq_enable();
@ -1330,14 +1363,14 @@ void Move::SetLiveCoordinates(const float coords[DRIVES])
liveCoordinates[drive] = coords[drive];
}
liveCoordinatesValid = true;
EndPointToMachine(coords, const_cast<int32_t *>(liveEndPoints), AXES);
EndPointToMachine(coords, const_cast<int32_t *>(liveEndPoints), reprap.GetGCodes()->GetNumAxes());
cpu_irq_enable();
}
void Move::ResetExtruderPositions()
{
cpu_irq_disable();
for(size_t eDrive = AXES; eDrive < DRIVES; eDrive++)
for(size_t eDrive = reprap.GetGCodes()->GetNumAxes(); eDrive < DRIVES; eDrive++)
{
liveCoordinates[eDrive] = 0.0;
}
@ -1531,7 +1564,7 @@ int Move::DoDeltaProbe(float frequency, float amplitude, float rate, float dista
return -1;
}
/*static*/ void Move::PrintMatrix(const char* s, const MathMatrix<float>& m, size_t maxRows, size_t maxCols)
/*static*/ void Move::PrintMatrix(const char* s, const MathMatrix<floatc_t>& m, size_t maxRows, size_t maxCols)
{
debugPrintf("%s\n", s);
if (maxRows == 0)
@ -1552,7 +1585,7 @@ int Move::DoDeltaProbe(float frequency, float amplitude, float rate, float dista
}
}
/*static*/ void Move::PrintVector(const char *s, const float *v, size_t numElems)
/*static*/ void Move::PrintVector(const char *s, const floatc_t *v, size_t numElems)
{
debugPrintf("%s:", s);
for (size_t i = 0; i < numElems; ++i)

View file

@ -10,16 +10,19 @@
#include "DDA.h"
#include "Libraries/Math/Matrix.h"
#include "DeltaParameters.h"
#include "DeltaProbe.h"
#ifdef DUET_NG
const unsigned int DdaRingLength = 40;
typedef double floatc_t; // type of matrix element used for delta calibration
#else
// We are more memory-constrained on the SAM3X
const unsigned int DdaRingLength = 20;
typedef float floatc_t; // type of matrix element used for delta calibration
#endif
#include "DeltaParameters.h"
#include "DeltaProbe.h"
enum PointCoordinateSet
{
unset = 0,
@ -82,12 +85,12 @@ public:
int GetCoreXYMode() const { return coreXYMode; }
void SetCoreXYMode(int mode) { coreXYMode = mode; }
float GetCoreAxisFactor(size_t axis) const { return axisFactors[axis]; }
void setCoreAxisFactor(size_t axis, float f) { axisFactors[axis] = f; }
void SetCoreAxisFactor(size_t axis, float f) { axisFactors[axis] = f; }
bool IsCoreXYAxis(size_t axis) const; // Return true if the specified axis shares its motors with another
void CurrentMoveCompleted(); // Signal that the current move has just been completed
bool TryStartNextMove(uint32_t startTime); // Try to start another move, returning true if Step() needs to be called immediately
void MotorTransform(const float machinePos[AXES], int32_t motorPos[AXES]) const; // Convert Cartesian coordinates to delta motor coordinates
void MotorTransform(const float machinePos[MAX_AXES], int32_t motorPos[MAX_AXES]) const; // Convert Cartesian coordinates to delta motor coordinates
float MotorFactor(size_t drive, const float directionVector[]) const; // Calculate the movement fraction for a single axis motor of a Cartesian or CoreXY printer
void MachineToEndPoint(const int32_t motorPos[], float machinePos[], size_t numDrives) const; // Convert motor coordinates to machine coordinates
void EndPointToMachine(const float coords[], int32_t ep[], size_t numDrives) const;
@ -116,21 +119,21 @@ private:
bool StartNextMove(uint32_t startTime); // start the next move, returning true if Step() needs to be called immediately
void SetProbedBedEquation(size_t numPoints, StringRef& reply); // When we have a full set of probed points, work out the bed's equation
void DoDeltaCalibration(size_t numPoints, StringRef& reply);
void BedTransform(float move[AXES]) const; // Take a position and apply the bed compensations
void GetCurrentMachinePosition(float m[DRIVES], bool disableMotorMapping) const; // Get the current position in untransformed coords
void InverseBedTransform(float move[AXES]) const; // Go from a bed-transformed point back to user coordinates
void AxisTransform(float move[AXES]) const; // Take a position and apply the axis-angle compensations
void InverseAxisTransform(float move[AXES]) const; // Go from an axis transformed point back to user coordinates
void BedTransform(float move[MAX_AXES]) const; // Take a position and apply the bed compensations
void GetCurrentMachinePosition(float m[DRIVES], bool disableMotorMapping) const; // Get the current position in untransformed coords
void InverseBedTransform(float move[MAX_AXES]) 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 BarycentricCoordinates(size_t p0, size_t p1, // Compute the barycentric coordinates of a point in a triangle
size_t p2, float x, float y, float& l1, // (see http://en.wikipedia.org/wiki/Barycentric_coordinate_system).
float& l2, float& l3) const;
float TriangleZ(float x, float y) const; // Interpolate onto a triangular grid
void AdjustDeltaParameters(const float v[], size_t numFactors); // Perform delta adjustment
void AdjustDeltaParameters(const floatc_t v[], size_t numFactors); // Perform delta adjustment
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
static void PrintMatrix(const char* s, const MathMatrix<float>& m, size_t numRows = 0, size_t maxCols = 0); // for debugging
static void PrintVector(const char *s, const float *v, size_t numElems); // for debugging
static void PrintMatrix(const char* s, const MathMatrix<floatc_t>& m, size_t numRows = 0, size_t maxCols = 0); // for debugging
static void PrintVector(const char *s, const floatc_t *v, size_t numElems); // for debugging
bool DDARingAdd(); // Add a processed look-ahead entry to the DDA ring
DDA* DDARingGet(); // Get the next DDA ring entry to be run
@ -177,7 +180,7 @@ private:
uint32_t deltaProbingStartTime;
bool deltaProbing;
int coreXYMode; // 0 = Cartesian, 1 = CoreXY, 2 = CoreXZ, 3 = CoreYZ
float axisFactors[AXES]; // How much further the motors need to move for each axis movement, on a CoreXY/CoreXZ/CoreYZ machine
float axisFactors[MAX_AXES]; // How much further the motors need to move for each axis movement, on a CoreXY/CoreXZ/CoreYZ machine
unsigned int stepErrors; // count of step errors, for diagnostics
};

View file

@ -145,7 +145,7 @@ bool PidParameters::operator==(const PidParameters& other) const
Platform::Platform() :
autoSaveEnabled(false), board(DEFAULT_BOARD_TYPE), active(false), errorCodeBits(0),
fileStructureInitialised(false), tickState(0), debugCode(0)
auxGCodeReply(nullptr), fileStructureInitialised(false), tickState(0), debugCode(0)
{
// Output
auxOutput = new OutputStack();
@ -184,6 +184,9 @@ void Platform::Init()
commsParams[2] = 0;
#endif
auxDetected = false;
auxSeq = 0;
SERIAL_MAIN_DEVICE.begin(baudRates[0]);
SERIAL_AUX_DEVICE.begin(baudRates[1]); // this can't be done in the constructor because the Arduino port initialisation isn't complete at that point
#ifdef SERIAL_AUX2_DEVICE
@ -291,7 +294,7 @@ void Platform::Init()
for (size_t drive = 0; drive < DRIVES; drive++)
{
// Map axes and extruders straight through
if (drive < AXES)
if (drive < MAX_AXES)
{
axisDrivers[drive].numDrivers = 1;
axisDrivers[drive].driverNumbers[0] = (uint8_t)drive;
@ -305,10 +308,11 @@ void Platform::Init()
#endif
endStopLogicLevel[drive] = true; // assume all endstops use active high logic e.g. normally-closed switch to ground
}
else
if (drive >= MIN_AXES)
{
extruderDrivers[drive - AXES] = (uint8_t)drive;
SetPressureAdvance(drive - AXES, 0.0);
extruderDrivers[drive - MIN_AXES] = (uint8_t)drive;
SetPressureAdvance(drive - MIN_AXES, 0.0);
}
driveDriverBits[drive] = CalcDriverBitmap(drive);
@ -570,26 +574,15 @@ int Platform::GetZProbeType() const
return nvData.zProbeType;
}
void Platform::SetZProbeAxes(const bool axes[AXES])
void Platform::SetZProbeAxes(uint32_t axes)
{
for (size_t axis=0; axis<AXES; axis++)
{
nvData.zProbeAxes[axis] = axes[axis];
}
nvData.zProbeAxes = axes;
if (autoSaveEnabled)
{
WriteNvData();
}
}
void Platform::GetZProbeAxes(bool (&axes)[AXES])
{
for (size_t axis=0; axis<AXES; axis++)
{
axes[axis] = nvData.zProbeAxes[axis];
}
}
// Get our best estimate of the Z probe temperature
float Platform::GetZProbeTemperature()
{
@ -737,7 +730,7 @@ bool Platform::SetZProbeParameters(const struct ZProbeParameters& params)
// Return true if we must home X and Y before we home Z (i.e. we are using a bed probe)
bool Platform::MustHomeXYBeforeZ() const
{
return nvData.zProbeType != 0 && nvData.zProbeAxes[Z_AXIS];
return (nvData.zProbeType != 0) && ((nvData.zProbeAxes & (1 << Z_AXIS)) != 0);
}
void Platform::ResetNvData()
@ -754,7 +747,7 @@ void Platform::ResetNvData()
#endif
nvData.zProbeType = 0; // Default is to use no Z probe switch
ARRAY_INIT(nvData.zProbeAxes, Z_PROBE_AXES);
nvData.zProbeAxes = Z_PROBE_AXES;
nvData.switchZProbeParameters.Init(0.0);
nvData.irZProbeParameters.Init(Z_PROBE_STOP_HEIGHT);
nvData.alternateZProbeParameters.Init(Z_PROBE_STOP_HEIGHT);
@ -1044,6 +1037,12 @@ void Platform::Exit()
}
}
// Release the aux output stack (should release the others too!)
while (auxGCodeReply != nullptr)
{
auxGCodeReply = OutputBuffer::Release(auxGCodeReply);
}
// Stop processing data. Don't try to send a message because it will probably never get there.
active = false;
}
@ -1596,7 +1595,7 @@ float Platform::GetTemperature(size_t heater, TemperatureError& err)
return ABS_ZERO + p.GetBeta() / log(resistance / p.GetRInf());
}
// thermistor short circuit, return a high temperature
// Thermistor short circuit, return a high temperature
err = TemperatureError::shortCircuit;
return BAD_ERROR_TEMPERATURE;
}
@ -1714,7 +1713,7 @@ EndStopHit Platform::Stopped(size_t drive) const
if (endStopType[drive] == EndStopType::noEndStop)
{
// No homing switch is configured for this axis, so see if we should use the Z probe
if (nvData.zProbeType > 0 && drive < AXES && nvData.zProbeAxes[drive])
if (nvData.zProbeType > 0 && drive < reprap.GetGCodes()->GetNumAxes() && (nvData.zProbeAxes & (1 << drive)) != 0)
{
return GetZProbeResult(); // using the Z probe as a low homing stop for this axis, so just get its result
}
@ -1760,7 +1759,8 @@ EndStopHit Platform::GetZProbeResult() 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)
{
if (drive < AXES)
const size_t numAxes = reprap.GetGCodes()->GetNumAxes();
if (drive < numAxes)
{
for (size_t i = 0; i < axisDrivers[drive].numDrivers; ++i)
{
@ -1769,7 +1769,7 @@ void Platform::SetDirection(size_t drive, bool direction)
}
else if (drive < DRIVES)
{
SetDriverDirection(extruderDrivers[drive - AXES], direction);
SetDriverDirection(extruderDrivers[drive - numAxes], direction);
}
}
@ -1820,7 +1820,8 @@ 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)
{
if (drive < AXES)
const size_t numAxes = reprap.GetGCodes()->GetNumAxes();
if (drive < numAxes)
{
for (size_t i = 0; i < axisDrivers[drive].numDrivers; ++i)
{
@ -1829,14 +1830,15 @@ void Platform::EnableDrive(size_t drive)
}
else if (drive < DRIVES)
{
EnableDriver(extruderDrivers[drive - AXES]);
EnableDriver(extruderDrivers[drive - numAxes]);
}
}
// Disable the drivers for a drive
void Platform::DisableDrive(size_t drive)
{
if (drive < AXES)
const size_t numAxes = reprap.GetGCodes()->GetNumAxes();
if (drive < numAxes)
{
for (size_t i = 0; i < axisDrivers[drive].numDrivers; ++i)
{
@ -1845,7 +1847,7 @@ void Platform::DisableDrive(size_t drive)
}
else if (drive < DRIVES)
{
DisableDriver(extruderDrivers[drive - AXES]);
DisableDriver(extruderDrivers[drive - numAxes]);
}
}
@ -1883,7 +1885,8 @@ 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)
{
if (drive < AXES)
const size_t numAxes = reprap.GetGCodes()->GetNumAxes();
if (drive < numAxes)
{
for (size_t i = 0; i < axisDrivers[drive].numDrivers; ++i)
{
@ -1893,7 +1896,7 @@ void Platform::SetMotorCurrent(size_t drive, float currentOrPercent, bool isPerc
}
else if (drive < DRIVES)
{
SetDriverCurrent(extruderDrivers[drive - AXES], currentOrPercent, isPercent);
SetDriverCurrent(extruderDrivers[drive - numAxes], currentOrPercent, isPercent);
}
}
@ -1968,7 +1971,8 @@ float Platform::GetMotorCurrent(size_t drive, bool isPercent) const
{
if (drive < DRIVES)
{
uint8_t driver = (drive < AXES) ? axisDrivers[drive].driverNumbers[0] : extruderDrivers[drive - AXES];
const size_t numAxes = reprap.GetGCodes()->GetNumAxes();
const uint8_t driver = (drive < numAxes) ? axisDrivers[drive].driverNumbers[0] : extruderDrivers[drive - numAxes];
if (driver < DRIVES)
{
return (isPercent) ? motorCurrentFraction[driver] * 100.0 : motorCurrents[driver];
@ -2016,7 +2020,8 @@ 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)
{
if (drive < AXES)
const size_t numAxes = reprap.GetGCodes()->GetNumAxes();
if (drive < numAxes)
{
bool ok = true;
for (size_t i = 0; i < axisDrivers[drive].numDrivers; ++i)
@ -2027,7 +2032,7 @@ bool Platform::SetMicrostepping(size_t drive, int microsteps, int mode)
}
else if (drive < DRIVES)
{
return SetDriverMicrostepping(extruderDrivers[drive - AXES], microsteps, mode);
return SetDriverMicrostepping(extruderDrivers[drive - numAxes], microsteps, mode);
}
return false;
}
@ -2049,13 +2054,14 @@ unsigned int Platform::GetDriverMicrostepping(size_t driver, bool& interpolation
// Get the microstepping for an axis or extruder
unsigned int Platform::GetMicrostepping(size_t drive, bool& interpolation) const
{
if (drive < AXES)
const size_t numAxes = reprap.GetGCodes()->GetNumAxes();
if (drive < numAxes)
{
return GetDriverMicrostepping(axisDrivers[drive].driverNumbers[0], interpolation);
}
else if (drive < DRIVES)
{
return GetDriverMicrostepping(extruderDrivers[drive - AXES], interpolation);
return GetDriverMicrostepping(extruderDrivers[drive - numAxes], interpolation);
}
else
{
@ -2079,7 +2085,7 @@ void Platform::SetAxisDriversConfig(size_t drive, const AxisDriversConfig& confi
void Platform::SetExtruderDriver(size_t extruder, uint8_t driver)
{
extruderDrivers[extruder] = driver;
driveDriverBits[extruder + AXES] = CalcDriverBitmap(driver);
driveDriverBits[extruder + reprap.GetGCodes()->GetNumAxes()] = CalcDriverBitmap(driver);
}
void Platform::SetDriverStepTiming(size_t driver, float microseconds)
@ -2277,23 +2283,54 @@ FileStore* Platform::GetFileStore(const char* directory, const char* fileName, b
return NULL;
}
void Platform::AppendAuxReply(const char *msg)
{
// Discard this response if either no aux device is attached or if the response is empty
if (msg[0] != 0 && HaveAux())
{
// Regular text-based responses for AUX are currently stored and processed by M105/M408
if (auxGCodeReply != nullptr || OutputBuffer::Allocate(auxGCodeReply))
{
auxSeq++;
auxGCodeReply->cat(msg);
}
}
}
void Platform::AppendAuxReply(OutputBuffer *reply)
{
// Discard this response if either no aux device is attached or if the response is empty
if (reply == nullptr || reply->Length() == 0 || !HaveAux())
{
OutputBuffer::ReleaseAll(reply);
}
else if ((*reply)[0] == '{')
{
// JSON responses are always sent directly to the AUX device
// For big responses it makes sense to write big chunks of data in portions. Store this data here
auxOutput->Push(reply);
}
else
{
// Other responses are stored for M105/M408
auxSeq++;
if (auxGCodeReply == nullptr)
{
auxGCodeReply = reply;
}
else
{
auxGCodeReply->Append(reply);
}
}
}
void Platform::Message(MessageType type, const char *message)
{
switch (type)
{
case AUX_MESSAGE:
// Message that is to be sent to the first auxiliary device
if (!auxOutput->IsEmpty())
{
// If we're still busy sending a response to the UART device, append this message to the output buffer
auxOutput->GetLastItem()->cat(message);
}
else
{
// Send short strings immediately through the aux channel. There is no flow control on this port, so it can't block for long
SERIAL_AUX_DEVICE.write(message);
SERIAL_AUX_DEVICE.flush();
}
AppendAuxReply(message);
break;
case AUX2_MESSAGE:
@ -2385,15 +2422,7 @@ void Platform::Message(const MessageType type, OutputBuffer *buffer)
switch (type)
{
case AUX_MESSAGE:
// If no AUX device is attached, don't queue this buffer
if (!reprap.GetGCodes()->HaveAux())
{
OutputBuffer::ReleaseAll(buffer);
break;
}
// For big responses it makes sense to write big chunks of data in portions. Store this data here
auxOutput->Push(buffer);
AppendAuxReply(buffer);
break;
case AUX2_MESSAGE:
@ -2491,7 +2520,7 @@ void Platform::SetAtxPower(bool on)
void Platform::SetPressureAdvance(size_t extruder, float factor)
{
if (extruder < DRIVES - AXES)
if (extruder < DRIVES - MIN_AXES)
{
pressureAdvance[extruder] = factor;
}
@ -2500,9 +2529,10 @@ void Platform::SetPressureAdvance(size_t extruder, float factor)
float Platform::ActualInstantDv(size_t drive) const
{
const float idv = instantDvs[drive];
if (drive >= AXES)
const size_t numAxes = reprap.GetGCodes()->GetNumAxes();
if (drive >= numAxes)
{
const float eComp = pressureAdvance[drive - AXES];
const float eComp = pressureAdvance[drive - numAxes];
// If we are using pressure advance then we need to limit the extruder instantDv to avoid velocity mismatches.
// Assume that we want the extruder motor position to be accurate to within 0.01mm of extrusion.
// TODO remove this limit and add/remove steps to the previous and/or next move instead

View file

@ -80,18 +80,6 @@ const float MillisToSeconds = 0.001;
/**************************************************************************************************/
#ifdef DUET_NG
const int Z_PROBE_AD_VALUE = 500; // Default for the Z probe - should be overwritten by experiment
const bool Z_PROBE_AXES[AXES] = { false, false, true }; // Axes for which the Z-probe is normally used
#else
const int Z_PROBE_AD_VALUE = 400; // Default for the Z probe - should be overwritten by experiment
const bool Z_PROBE_AXES[AXES] = { true, false, true }; // Axes for which the Z-probe is normally used
#endif
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 = 6; // Z probe type for experimental delta probe
#if SUPPORT_INKJET
// Inkjet (if any - no inkjet is flagged by INKJET_BITS negative)
@ -112,12 +100,26 @@ const float INSTANT_DVS[DRIVES] = DRIVES_(15.0, 15.0, 0.2, 2.0, 2.0, 2.0, 2.0, 2
const size_t X_AXIS = 0, Y_AXIS = 1, Z_AXIS = 2, E0_AXIS = 3; // The indices of the Cartesian axes in drive arrays
const size_t A_AXIS = 0, B_AXIS = 1, C_AXIS = 2; // The indices of the 3 tower motors of a delta printer in drive arrays
const float AXIS_MINIMA[AXES] = { 0.0, 0.0, 0.0 }; // mm
const float AXIS_MAXIMA[AXES] = { 230.0, 210.0, 200.0 }; // mm
const float AXIS_MINIMA[MAX_AXES] = { 0.0, 0.0, 0.0 }; // mm
const float AXIS_MAXIMA[MAX_AXES] = { 230.0, 210.0, 200.0 }; // mm
const float defaultPrintRadius = 50; // mm
const float defaultDeltaHomedHeight = 200; // 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 = 6; // 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
const uint32_t Z_PROBE_AXES = (1 << Z_AXIS); // Axes for which the Z-probe is normally used
#else
const int Z_PROBE_AD_VALUE = 400; // Default for the Z probe - should be overwritten by experiment
const uint32_t Z_PROBE_AXES = (1 << X_AXIS) | (1 << Z_AXIS); // Axes for which the Z-probe is normally used
#endif
// HEATERS - The bed is assumed to be the at index 0
// Bed thermistor: http://uk.farnell.com/epcos/b57863s103f040/sensor-miniature-ntc-10k/dp/1299930?Ntt=129-9930
@ -464,6 +466,12 @@ public:
bool GCodeAvailable(const SerialSource source) const;
char ReadFromSource(const SerialSource source);
OutputBuffer *GetAuxGCodeReply(); // Returns cached G-Code reply for AUX devices and clears its reference
void AppendAuxReply(OutputBuffer *buf);
void AppendAuxReply(const char *msg);
uint32_t GetAuxSeq() { return auxSeq; }
bool HaveAux() const { return auxDetected; } // Any device on the AUX line?
void SetAuxDetected() { auxDetected = true; }
void SetIPAddress(uint8_t ip[]);
const uint8_t* IPAddress() const;
@ -576,8 +584,8 @@ public:
int GetZProbeSecondaryValues(int& v1, int& v2);
void SetZProbeType(int iZ);
int GetZProbeType() const;
void SetZProbeAxes(const bool axes[AXES]);
void GetZProbeAxes(bool (&axes)[AXES]);
void SetZProbeAxes(uint32_t axes);
uint32_t GetZProbeAxes() const { return nvData.zProbeAxes; }
const ZProbeParameters& GetZProbeParameters() const;
bool SetZProbeParameters(const struct ZProbeParameters& params);
bool MustHomeXYBeforeZ() const;
@ -691,7 +699,7 @@ private:
struct FlashData
{
static const uint16_t magicValue = 0xE6C4; // value we use to recognise that the flash data has been written
static const uint16_t versionValue = 2; // increment this whenever this struct changes
static const uint16_t versionValue = 3; // increment this whenever this struct changes
static const uint32_t nvAddress = (SoftwareResetData::nvAddress + sizeof(SoftwareResetData) + 3) & (~3);
uint16_t magic;
@ -703,7 +711,7 @@ private:
ZProbeParameters irZProbeParameters; // Z probe values for the IR sensor
ZProbeParameters alternateZProbeParameters; // Z probe values for the alternate sensor
int zProbeType; // the type of Z probe we are currently using
bool zProbeAxes[AXES]; // Z probe is used for these axes
uint32_t zProbeAxes; // Z probe is used for these axes (bitmap)
PidParameters pidParams[HEATERS];
byte ipAddress[4];
byte netMask[4];
@ -743,11 +751,11 @@ private:
float accelerations[DRIVES];
float driveStepsPerUnit[DRIVES];
float instantDvs[DRIVES];
float pressureAdvance[DRIVES - AXES];
float pressureAdvance[DRIVES - MIN_AXES];
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[AXES]; // the driver numbers assigned to each axis
uint8_t extruderDrivers[DRIVES - AXES]; // the driver number assigned to each extruder
AxisDriversConfig axisDrivers[MAX_AXES]; // the driver numbers assigned to each axis
uint8_t extruderDrivers[DRIVES - MIN_AXES]; // 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
uint32_t slowDrivers; // bitmap of driver port bits that need extended step pulse timing
@ -783,10 +791,10 @@ private:
// Axes and endstops
float axisMaxima[AXES];
float axisMinima[AXES];
EndStopType endStopType[AXES+1];
bool endStopLogicLevel[AXES+1];
float axisMaxima[MAX_AXES];
float axisMinima[MAX_AXES];
EndStopType endStopType[MAX_AXES+1];
bool endStopLogicLevel[MAX_AXES+1];
// Heaters - bed is assumed to be the first
@ -812,6 +820,9 @@ private:
OutputStack *auxOutput;
OutputStack *aux2Output;
OutputStack *usbOutput;
bool auxDetected; // Have we processed at least one G-Code from an AUX device?
OutputBuffer *auxGCodeReply; // G-Code reply for AUX devices (special one because it is actually encapsulated before sending)
uint32_t auxSeq; // Sequence number for AUX devices
// Files
@ -1228,7 +1239,7 @@ inline const uint8_t* Platform::MACAddress() const
inline float Platform::GetPressureAdvance(size_t extruder) const
{
return (extruder < DRIVES - AXES) ? pressureAdvance[extruder] : 0.0;
return (extruder < DRIVES - MIN_AXES) ? pressureAdvance[extruder] : 0.0;
}
inline void Platform::SetEndStopConfiguration(size_t axis, EndStopType esType, bool logicLevel)
@ -1259,7 +1270,7 @@ inline uint16_t Platform::GetRawZProbeReading() const
case 4:
{
bool b = digitalRead(endStopPins[E0_AXIS]);
if (!endStopLogicLevel[AXES])
if (!endStopLogicLevel[MAX_AXES])
{
b = !b;
}
@ -1299,6 +1310,13 @@ inline MassStorage* Platform::GetMassStorage() const
return massStorage;
}
inline OutputBuffer *Platform::GetAuxGCodeReply()
{
OutputBuffer *temp = auxGCodeReply;
auxGCodeReply = nullptr;
return temp;
}
/*static*/ inline void Platform::EnableWatchdog()
{
watchdogEnable(1000);

View file

@ -302,7 +302,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 - AXES; extr++)
for(size_t extr = 0; extr < DRIVES - MIN_AXES; extr++)
{
parsedFileInfo.filamentNeeded[extr] = 0.0;
}
@ -374,7 +374,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 - AXES);
parsedFileInfo.numFilaments = FindFilamentUsed(buf, sizeToScan, parsedFileInfo.filamentNeeded, DRIVES - reprap.GetGCodes()->GetNumAxes());
headerInfoComplete &= (parsedFileInfo.numFilaments != 0);
}
@ -529,7 +529,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 - AXES);
parsedFileInfo.numFilaments = FindFilamentUsed(buf, sizeToScan, parsedFileInfo.filamentNeeded, DRIVES - reprap.GetGCodes()->GetNumAxes());
if (parsedFileInfo.numFilaments == 0)
{
footerInfoComplete = false;
@ -778,7 +778,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 - AXES; extruder++)
for(size_t extruder = 0; extruder < DRIVES - reprap.GetGCodes()->GetNumAxes(); extruder++)
{
totalFilamentNeeded += printingFileInfo.filamentNeeded[extruder];
}

View file

@ -55,7 +55,7 @@ struct GCodeFileInfo
FilePosition fileSize;
float firstLayerHeight;
float objectHeight;
float filamentNeeded[DRIVES - AXES];
float filamentNeeded[DRIVES - MIN_AXES];
unsigned int numFilaments;
float layerHeight;
char generatedBy[50];

View file

@ -182,7 +182,7 @@ const char *moduleName[] =
// Utilities and storage not part of any class
static char scratchStringBuffer[120]; // this is now used only for short messages; needs to be long enough to print delta parameters
static char scratchStringBuffer[140]; // this is now used only for short messages; needs to be long enough to print delta parameters
StringRef scratchString(scratchStringBuffer, ARRAY_SIZE(scratchStringBuffer));
// For debug use

BIN
src/RepRapFirmware.pdp Normal file

Binary file not shown.

View file

@ -62,7 +62,7 @@ void RepRap::Init()
{
while (gCodes->DoingFileMacro())
{
// GCodes::Spin will read the macro and ensure DoFileMacro returns true when it's done
// GCodes::Spin will read the macro and ensure DoingFileMacro returns false when it's done
Spin();
}
platform->Message(HOST_MESSAGE, "Done!\n");
@ -496,6 +496,7 @@ OutputBuffer *RepRap::GetStatusResponse(uint8_t type, ResponseSource source)
// Coordinates
{
const size_t numAxes = reprap.GetGCodes()->GetNumAxes();
float liveCoordinates[DRIVES + 1];
#if SUPPORT_ROLAND
if (roland->Active())
@ -511,24 +512,27 @@ OutputBuffer *RepRap::GetStatusResponse(uint8_t type, ResponseSource source)
if (currentTool != nullptr)
{
const float *offset = currentTool->GetOffset();
for (size_t i = 0; i < AXES; ++i)
for (size_t i = 0; i < numAxes; ++i)
{
liveCoordinates[i] += offset[i];
}
}
// Homed axes
response->catf("\"axesHomed\":[%d,%d,%d]",
(gCodes->GetAxisIsHomed(0)) ? 1 : 0,
(gCodes->GetAxisIsHomed(1)) ? 1 : 0,
(gCodes->GetAxisIsHomed(2)) ? 1 : 0);
response->cat("\"axesHomed\":");
ch = '[';
for (size_t axis = 0; axis < numAxes; ++axis)
{
response->catf("%c%d", ch, (gCodes->GetAxisIsHomed(axis)) ? 1 : 0);
ch = ',';
}
// Actual and theoretical extruder positions since power up, last G92 or last M23
response->catf(",\"extr\":"); // announce actual extruder positions
response->catf("],\"extr\":"); // announce actual extruder positions
ch = '[';
for (size_t extruder = 0; extruder < GetExtrudersInUse(); extruder++)
{
response->catf("%c%.1f", ch, liveCoordinates[AXES + extruder]);
response->catf("%c%.1f", ch, liveCoordinates[numAxes + extruder]);
ch = ',';
}
if (ch == '[')
@ -547,7 +551,7 @@ OutputBuffer *RepRap::GetStatusResponse(uint8_t type, ResponseSource source)
{
// On Cartesian printers, the live coordinates are (usually) valid
ch = '[';
for (size_t axis = 0; axis < AXES; axis++)
for (size_t axis = 0; axis < numAxes; axis++)
{
response->catf("%c%.2f", ch, liveCoordinates[axis]);
ch = ',';
@ -868,11 +872,11 @@ OutputBuffer *RepRap::GetStatusResponse(uint8_t type, ResponseSource source)
if (source == ResponseSource::AUX)
{
OutputBuffer *response = gCodes->GetAuxGCodeReply();
OutputBuffer *response = platform->GetAuxGCodeReply();
if (response != nullptr)
{
// Send the response to the last command. Do this last
response->catf(",\"seq\":%u,\"resp\":", gCodes->GetAuxSeq()); // send the response sequence number
response->catf(",\"seq\":%u,\"resp\":", platform->GetAuxSeq()); // send the response sequence number
// Send the JSON response
response->EncodeReply(response, true); // also releases the OutputBuffer chain
@ -892,10 +896,12 @@ OutputBuffer *RepRap::GetConfigResponse()
return nullptr;
}
const size_t numAxes = reprap.GetGCodes()->GetNumAxes();
// Axis minima
response->copy("{\"axisMins\":");
char ch = '[';
for (size_t axis = 0; axis < AXES; axis++)
for (size_t axis = 0; axis < numAxes; axis++)
{
response->catf("%c%.2f", ch, platform->AxisMinimum(axis));
ch = ',';
@ -904,7 +910,7 @@ OutputBuffer *RepRap::GetConfigResponse()
// Axis maxima
response->cat("],\"axisMaxes\":");
ch = '[';
for (size_t axis = 0; axis < AXES; axis++)
for (size_t axis = 0; axis < numAxes; axis++)
{
response->catf("%c%.2f", ch, platform->AxisMaximum(axis));
ch = ',';
@ -1066,20 +1072,21 @@ OutputBuffer *RepRap::GetLegacyStatusResponse(uint8_t type, int seq)
response->cat((ch == '[') ? "[]" : "]");
// Send XYZ positions
const size_t numAxes = reprap.GetGCodes()->GetNumAxes();
float liveCoordinates[DRIVES];
reprap.GetMove()->LiveCoordinates(liveCoordinates);
const Tool* currentTool = reprap.GetCurrentTool();
if (currentTool != nullptr)
{
const float *offset = currentTool->GetOffset();
for (size_t i = 0; i < AXES; ++i)
for (size_t i = 0; i < numAxes; ++i)
{
liveCoordinates[i] += offset[i];
}
}
response->catf(",\"pos\":"); // announce the XYZ position
ch = '[';
for (size_t drive = 0; drive < AXES; drive++)
for (size_t drive = 0; drive < numAxes; drive++)
{
response->catf("%c%.2f", ch, liveCoordinates[drive]);
ch = ',';
@ -1138,10 +1145,14 @@ OutputBuffer *RepRap::GetLegacyStatusResponse(uint8_t type, int seq)
response->catf("],\"fanRPM\":%u", static_cast<unsigned int>(platform->GetFanRPM()));
// Send the home state. To keep the messages short, we send 1 for homed and 0 for not homed, instead of true and false.
response->catf(",\"homed\":[%d,%d,%d]",
(gCodes->GetAxisIsHomed(0)) ? 1 : 0,
(gCodes->GetAxisIsHomed(1)) ? 1 : 0,
(gCodes->GetAxisIsHomed(2)) ? 1 : 0);
response->cat(",\"homed\":");
ch = '[';
for (size_t axis = 0; axis < numAxes; ++axis)
{
response->catf("%c%d", ch, (gCodes->GetAxisIsHomed(axis)) ? 1 : 0);
ch = ',';
}
response->cat(']');
if (printMonitor->IsPrinting())
{
@ -1170,7 +1181,7 @@ OutputBuffer *RepRap::GetLegacyStatusResponse(uint8_t type, int seq)
response->EncodeString(myName, ARRAY_SIZE(myName), false);
}
int auxSeq = (int)gCodes->GetAuxSeq();
int auxSeq = (int)platform->GetAuxSeq();
if (type < 2 || (seq != -1 && (int)auxSeq != seq))
{
@ -1178,7 +1189,7 @@ OutputBuffer *RepRap::GetLegacyStatusResponse(uint8_t type, int seq)
response->catf(",\"seq\":%u,\"resp\":", auxSeq); // send the response sequence number
// Send the JSON response
response->EncodeReply(gCodes->GetAuxGCodeReply(), true); // also releases the OutputBuffer chain
response->EncodeReply(platform->GetAuxGCodeReply(), true); // also releases the OutputBuffer chain
}
response->cat("}");
@ -1328,7 +1339,7 @@ void RepRap::Beep(int freq, int ms)
beepFrequency = freq;
beepDuration = ms;
if (gCodes->HaveAux())
if (platform->HaveAux())
{
// If there is an LCD device present, make it beep
platform->Beep(freq, ms);
@ -1341,7 +1352,7 @@ void RepRap::SetMessage(const char *msg)
strncpy(message, msg, MESSAGE_LENGTH);
message[MESSAGE_LENGTH] = 0;
if (gCodes->HaveAux())
if (platform->HaveAux())
{
platform->SendMessage(msg);
}

View file

@ -29,7 +29,8 @@ Tool * Tool::freelist = nullptr;
/*static*/Tool * Tool::Create(int toolNumber, long d[], size_t dCount, long h[], size_t hCount)
{
if (dCount > DRIVES - AXES)
const size_t numAxes = reprap.GetGCodes()->GetNumAxes();
if (dCount > DRIVES - numAxes)
{
reprap.GetPlatform()->Message(GENERIC_MESSAGE,
"Error: Tool creation: attempt to use more drives than there are in the RepRap");
@ -63,7 +64,7 @@ Tool * Tool::freelist = nullptr;
t->mixing = false;
t->displayColdExtrudeWarning = false;
for (size_t axis = 0; axis < AXES; axis++)
for (size_t axis = 0; axis < MAX_AXES; axis++)
{
t->offset[axis] = 0.0;
}
@ -137,9 +138,10 @@ float Tool::MaxFeedrate() const
return 1.0;
}
float result = 0.0;
const size_t numAxes = reprap.GetGCodes()->GetNumAxes();
for (size_t d = 0; d < driveCount; d++)
{
float mf = reprap.GetPlatform()->MaxFeedrate(drives[d] + AXES);
float mf = reprap.GetPlatform()->MaxFeedrate(drives[d] + numAxes);
if (mf > result)
{
result = mf;
@ -156,9 +158,10 @@ float Tool::InstantDv() const
return 1.0;
}
float result = FLT_MAX;
const size_t numAxes = reprap.GetGCodes()->GetNumAxes();
for (size_t d = 0; d < driveCount; d++)
{
float idv = reprap.GetPlatform()->ActualInstantDv(drives[d] + AXES);
float idv = reprap.GetPlatform()->ActualInstantDv(drives[d] + numAxes);
if (idv < result)
{
result = idv;

View file

@ -34,7 +34,7 @@ public:
static void Delete(Tool *t);
const float *GetOffset() const;
void SetOffset(const float offs[AXES]);
void SetOffset(const float offs[MAX_AXES]);
size_t DriveCount() const;
int Drive(int driveNumber) const;
bool ToolCanDrive(bool extrude);
@ -70,8 +70,8 @@ private:
void ResetTemperatureFault(int8_t wasDudHeater);
bool AllHeatersAtHighTemperature(bool forExtrusion) const;
int myNumber;
int drives[DRIVES - AXES];
float mix[DRIVES - AXES];
int drives[DRIVES - MIN_AXES];
float mix[DRIVES - MIN_AXES];
bool mixing;
size_t driveCount;
int heaters[HEATERS];
@ -81,7 +81,7 @@ private:
Tool* next;
bool active;
bool heaterFault;
float offset[AXES];
float offset[MAX_AXES];
volatile bool displayColdExtrudeWarning;
};
@ -144,9 +144,9 @@ inline const float *Tool::GetOffset() const
return offset;
}
inline void Tool::SetOffset(const float offs[AXES])
inline void Tool::SetOffset(const float offs[MAX_AXES])
{
for(size_t i = 0; i < AXES; ++i)
for(size_t i = 0; i < MAX_AXES; ++i)
{
offset[i] = offs[i];
}