Version 0.78h
Added a few more improvements from RRP's dev branch Corrected M201 output Added a few more minor fixes
This commit is contained in:
parent
30b67ff40a
commit
2a818bcfc0
12 changed files with 583 additions and 329 deletions
|
@ -24,8 +24,8 @@ Licence: GPL
|
|||
#define CONFIGURATION_H
|
||||
|
||||
#define NAME "RepRapFirmware"
|
||||
#define VERSION "0.78g-dc42"
|
||||
#define DATE "2014-07-30"
|
||||
#define VERSION "0.78h-dc42"
|
||||
#define DATE "2014-08-01"
|
||||
#define AUTHORS "reprappro, dc42. zpl"
|
||||
|
||||
// Other firmware that we might switch to be compatible with.
|
||||
|
@ -50,6 +50,8 @@ enum Compatibility
|
|||
|
||||
#define TEMPERATURE_CLOSE_ENOUGH (2.5) // Celsius
|
||||
#define TEMPERATURE_LOW_SO_DONT_CARE (40.0) // Celsius
|
||||
#define HOT_ENOUGH_TO_EXTRUDE (160.0) // Celsius
|
||||
#define TIME_TO_HOT (120.0) // Seconds
|
||||
|
||||
// If temperatures fall outside this range, something nasty has happened.
|
||||
|
||||
|
|
484
GCodes.cpp
484
GCodes.cpp
|
@ -90,12 +90,12 @@ void GCodes::Reset()
|
|||
probeCount = 0;
|
||||
cannedCycleMoveCount = 0;
|
||||
cannedCycleMoveQueued = false;
|
||||
speedFactor = 1.0/60.0; // default is just to convert from mm/minute to mm/second
|
||||
speedFactorChange = 1.0;
|
||||
for (size_t i = 0; i < DRIVES - AXES; ++i)
|
||||
{
|
||||
extrusionFactors[i] = 1.0;
|
||||
}
|
||||
speedFactor = 1.0/60.0; // default is just to convert from mm/minute to mm/second
|
||||
speedFactorChange = 1.0;
|
||||
for (size_t i = 0; i < DRIVES - AXES; ++i)
|
||||
{
|
||||
extrusionFactors[i] = 1.0;
|
||||
}
|
||||
}
|
||||
|
||||
void GCodes::DoFilePrint(GCodeBuffer* gb)
|
||||
|
@ -164,7 +164,7 @@ void GCodes::Spin()
|
|||
int8_t i = 0;
|
||||
do
|
||||
{
|
||||
char b = webserver->ReadGCode();
|
||||
char b = webserver->ReadGCode();
|
||||
if (webGCode->Put(b))
|
||||
{
|
||||
// we have a complete gcode
|
||||
|
@ -245,23 +245,20 @@ void GCodes::Diagnostics()
|
|||
|
||||
bool GCodes::AllMovesAreFinishedAndMoveBufferIsLoaded()
|
||||
{
|
||||
// Last one gone?
|
||||
// Last one gone?
|
||||
if(moveAvailable)
|
||||
return false;
|
||||
|
||||
if(moveAvailable)
|
||||
return false;
|
||||
|
||||
// Wait for all the queued moves to stop so we get the actual last position and feedrate
|
||||
|
||||
if(!reprap.GetMove()->AllMovesAreFinished())
|
||||
return false;
|
||||
reprap.GetMove()->ResumeMoving();
|
||||
|
||||
// Load the last position; If Move can't accept more, return false - should never happen
|
||||
|
||||
if(!reprap.GetMove()->GetCurrentUserPosition(moveBuffer))
|
||||
return false;
|
||||
// Wait for all the queued moves to stop so we get the actual last position and feedrate
|
||||
if(!reprap.GetMove()->AllMovesAreFinished())
|
||||
return false;
|
||||
reprap.GetMove()->ResumeMoving();
|
||||
|
||||
return true;
|
||||
// Load the last position; If Move can't accept more, return false - should never happen
|
||||
if(!reprap.GetMove()->GetCurrentUserPosition(moveBuffer))
|
||||
return false;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
// Save (some of) the state of the machine for recovery in the future.
|
||||
|
@ -269,58 +266,58 @@ bool GCodes::AllMovesAreFinishedAndMoveBufferIsLoaded()
|
|||
|
||||
bool GCodes::Push()
|
||||
{
|
||||
if(stackPointer >= STACK)
|
||||
{
|
||||
platform->Message(BOTH_ERROR_MESSAGE, "Push(): stack overflow!\n");
|
||||
return true;
|
||||
}
|
||||
|
||||
if(!AllMovesAreFinishedAndMoveBufferIsLoaded())
|
||||
return false;
|
||||
|
||||
drivesRelativeStack[stackPointer] = drivesRelative;
|
||||
axesRelativeStack[stackPointer] = axesRelative;
|
||||
feedrateStack[stackPointer] = moveBuffer[DRIVES];
|
||||
fileStack[stackPointer].CopyFrom(fileBeingPrinted);
|
||||
stackPointer++;
|
||||
platform->PushMessageIndent();
|
||||
return true;
|
||||
if(stackPointer >= STACK)
|
||||
{
|
||||
platform->Message(BOTH_ERROR_MESSAGE, "Push(): stack overflow!\n");
|
||||
return true;
|
||||
}
|
||||
|
||||
if(!AllMovesAreFinishedAndMoveBufferIsLoaded())
|
||||
return false;
|
||||
|
||||
drivesRelativeStack[stackPointer] = drivesRelative;
|
||||
axesRelativeStack[stackPointer] = axesRelative;
|
||||
feedrateStack[stackPointer] = moveBuffer[DRIVES];
|
||||
fileStack[stackPointer].CopyFrom(fileBeingPrinted);
|
||||
stackPointer++;
|
||||
platform->PushMessageIndent();
|
||||
return true;
|
||||
}
|
||||
|
||||
// Recover a saved state. Call repeatedly till it returns true.
|
||||
|
||||
bool GCodes::Pop()
|
||||
{
|
||||
if(stackPointer < 1)
|
||||
{
|
||||
platform->Message(BOTH_ERROR_MESSAGE, "Pop(): stack underflow!\n");
|
||||
return true;
|
||||
}
|
||||
|
||||
if(!AllMovesAreFinishedAndMoveBufferIsLoaded())
|
||||
return false;
|
||||
|
||||
stackPointer--;
|
||||
drivesRelative = drivesRelativeStack[stackPointer];
|
||||
axesRelative = axesRelativeStack[stackPointer];
|
||||
fileBeingPrinted.MoveFrom(fileStack[stackPointer]);
|
||||
platform->PopMessageIndent();
|
||||
if(stackPointer < 1)
|
||||
{
|
||||
platform->Message(BOTH_ERROR_MESSAGE, "Pop(): stack underflow!\n");
|
||||
return true;
|
||||
}
|
||||
|
||||
// Remember for next time if we have just been switched to absolute drive moves
|
||||
// DC 2014-07-16: the following code is wrong, it messes up the absolute extruder position (typically it resets it to zero) and does nothing useful as far as I can see.
|
||||
// So I am commenting it out.
|
||||
//for(int8_t i = AXES; i < DRIVES; i++)
|
||||
//{
|
||||
// lastPos[i - AXES] = moveBuffer[i];
|
||||
//}
|
||||
|
||||
// Set the correct feedrate
|
||||
|
||||
moveBuffer[DRIVES] = feedrateStack[stackPointer];
|
||||
|
||||
endStopsToCheck = 0;
|
||||
moveAvailable = true;
|
||||
return true;
|
||||
if(!AllMovesAreFinishedAndMoveBufferIsLoaded())
|
||||
return false;
|
||||
|
||||
stackPointer--;
|
||||
drivesRelative = drivesRelativeStack[stackPointer];
|
||||
axesRelative = axesRelativeStack[stackPointer];
|
||||
fileBeingPrinted.MoveFrom(fileStack[stackPointer]);
|
||||
platform->PopMessageIndent();
|
||||
|
||||
// Remember for next time if we have just been switched to absolute drive moves
|
||||
// DC 2014-07-16: the following code is wrong, it messes up the absolute extruder position (typically it resets it to zero) and does nothing useful as far as I can see.
|
||||
// So I am commenting it out.
|
||||
//for(int8_t i = AXES; i < DRIVES; i++)
|
||||
//{
|
||||
// lastPos[i - AXES] = moveBuffer[i];
|
||||
//}
|
||||
|
||||
// Set the correct feedrate
|
||||
|
||||
moveBuffer[DRIVES] = feedrateStack[stackPointer];
|
||||
|
||||
endStopsToCheck = 0;
|
||||
moveAvailable = true;
|
||||
return true;
|
||||
}
|
||||
|
||||
// Move expects all axis movements to be absolute, and all
|
||||
|
@ -346,8 +343,8 @@ bool GCodes::LoadMoveBufferFromGCode(GCodeBuffer *gb, bool doingG92, bool applyL
|
|||
platform->Message(BOTH_ERROR_MESSAGE, "Attempting to extrude with no tool selected.\n");
|
||||
return false;
|
||||
}
|
||||
float eMovement[DRIVES-AXES];
|
||||
int eMoveCount = tool->DriveCount();
|
||||
float eMovement[DRIVES-AXES];
|
||||
gb->GetFloatArray(eMovement, eMoveCount);
|
||||
if(tool->DriveCount() != eMoveCount)
|
||||
{
|
||||
|
@ -386,7 +383,7 @@ bool GCodes::LoadMoveBufferFromGCode(GCodeBuffer *gb, bool doingG92, bool applyL
|
|||
{
|
||||
if(gb->Seen(axisLetters[axis]))
|
||||
{
|
||||
float moveArg = gb->GetFValue()*distanceScale;
|
||||
float moveArg = gb->GetFValue() * distanceScale;
|
||||
if (axesRelative && !doingG92)
|
||||
{
|
||||
moveArg += moveBuffer[axis];
|
||||
|
@ -550,7 +547,7 @@ bool GCodes::FileCannedCyclesReturn()
|
|||
|
||||
// To execute any move, call this until it returns true.
|
||||
// moveToDo[] entries corresponding with false entries in action[] will
|
||||
// be ignored. Recall that moveToDo[DRIVES] should contain the feed rate
|
||||
// be ignored. Recall that moveToDo[DRIVES] should contain the feedrate
|
||||
// you want (if action[DRIVES] is true).
|
||||
|
||||
bool GCodes::DoCannedCycleMove(EndstopChecks ce)
|
||||
|
@ -1127,11 +1124,11 @@ void GCodes::QueueFileToPrint(const char* fileName)
|
|||
|
||||
void GCodes::DeleteFile(const char* fileName)
|
||||
{
|
||||
if(!platform->GetMassStorage()->Delete(platform->GetGCodeDir(), fileName))
|
||||
{
|
||||
snprintf(scratchString, STRING_LENGTH, "Unsuccessful attempt to delete: %s\n", fileName);
|
||||
platform->Message(BOTH_ERROR_MESSAGE, scratchString);
|
||||
}
|
||||
if(!platform->GetMassStorage()->Delete(platform->GetGCodeDir(), fileName))
|
||||
{
|
||||
snprintf(scratchString, STRING_LENGTH, "Unsuccessful attempt to delete: %s\n", fileName);
|
||||
platform->Message(BOTH_ERROR_MESSAGE, scratchString);
|
||||
}
|
||||
}
|
||||
|
||||
// Send the config file to USB in response to an M503 command.
|
||||
|
@ -1168,7 +1165,7 @@ bool GCodes::SendConfigToLine()
|
|||
|
||||
bool GCodes::DoDwell(GCodeBuffer *gb)
|
||||
{
|
||||
if(!gb->Seen('P'))
|
||||
if(!gb->Seen('P'))
|
||||
return true; // No time given - throw it away
|
||||
|
||||
float dwell = 0.001 * (float) gb->GetLValue(); // P values are in milliseconds; we need seconds
|
||||
|
@ -1208,48 +1205,48 @@ bool GCodes::DoDwellTime(float dwell)
|
|||
|
||||
void GCodes::SetOrReportOffsets(char* reply, GCodeBuffer *gb)
|
||||
{
|
||||
if(gb->Seen('P'))
|
||||
{
|
||||
int8_t toolNumber = gb->GetIValue();
|
||||
toolNumber += gb->GetToolNumberAdjust();
|
||||
Tool* tool = reprap.GetTool(toolNumber);
|
||||
if(tool == NULL)
|
||||
{
|
||||
snprintf(reply, STRING_LENGTH, "Attempt to set/report offsets and temperatures for non-existent tool: %d\n", toolNumber);
|
||||
return;
|
||||
}
|
||||
float standby[HEATERS];
|
||||
float active[HEATERS];
|
||||
tool->GetVariables(standby, active);
|
||||
int hCount = tool->HeaterCount();
|
||||
if(hCount > 0)
|
||||
{
|
||||
bool setting = false;
|
||||
if(gb->Seen('R'))
|
||||
{
|
||||
gb->GetFloatArray(standby, hCount);
|
||||
setting = true;
|
||||
}
|
||||
if(gb->Seen('S'))
|
||||
{
|
||||
gb->GetFloatArray(active, hCount);
|
||||
setting = true;
|
||||
}
|
||||
if(setting)
|
||||
{
|
||||
tool->SetVariables(standby, active);
|
||||
}
|
||||
else
|
||||
{
|
||||
reply[0] = 0;
|
||||
snprintf(reply, STRING_LENGTH, "Tool %d - Active/standby temperature(s): ", toolNumber);
|
||||
for(int8_t heater = 0; heater < hCount; heater++)
|
||||
{
|
||||
sncatf(reply, STRING_LENGTH, "%.1f/%.1f ", active[heater], standby[heater]);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
if(gb->Seen('P'))
|
||||
{
|
||||
int8_t toolNumber = gb->GetIValue();
|
||||
toolNumber += gb->GetToolNumberAdjust();
|
||||
Tool* tool = reprap.GetTool(toolNumber);
|
||||
if(tool == NULL)
|
||||
{
|
||||
snprintf(reply, STRING_LENGTH, "Attempt to set/report offsets and temperatures for non-existent tool: %d\n", toolNumber);
|
||||
return;
|
||||
}
|
||||
float standby[HEATERS];
|
||||
float active[HEATERS];
|
||||
tool->GetVariables(standby, active);
|
||||
int hCount = tool->HeaterCount();
|
||||
if(hCount > 0)
|
||||
{
|
||||
bool setting = false;
|
||||
if(gb->Seen('R'))
|
||||
{
|
||||
gb->GetFloatArray(standby, hCount);
|
||||
setting = true;
|
||||
}
|
||||
if(gb->Seen('S'))
|
||||
{
|
||||
gb->GetFloatArray(active, hCount);
|
||||
setting = true;
|
||||
}
|
||||
if(setting)
|
||||
{
|
||||
tool->SetVariables(standby, active);
|
||||
}
|
||||
else
|
||||
{
|
||||
reply[0] = 0;
|
||||
snprintf(reply, STRING_LENGTH, "Tool %d - Active/standby temperature(s): ", toolNumber);
|
||||
for(int8_t heater = 0; heater < hCount; heater++)
|
||||
{
|
||||
sncatf(reply, STRING_LENGTH, "%.1f/%.1f ", active[heater], standby[heater]);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void GCodes::AddNewTool(GCodeBuffer *gb, char *reply)
|
||||
|
@ -1661,13 +1658,13 @@ void GCodes::SetToolHeaters(Tool *tool, float temperature)
|
|||
bool GCodes::ActOnCode(GCodeBuffer *gb)
|
||||
{
|
||||
// M-code parameters might contain letters T and G, e.g. in filenames.
|
||||
// I assume that G-and T-code parameters never contain the letter M.
|
||||
// dc42 assumes that G-and T-code parameters never contain the letter M.
|
||||
// Therefore we must check for an M-code first.
|
||||
if (gb->Seen('M'))
|
||||
{
|
||||
return HandleMcode(gb);
|
||||
}
|
||||
// I don't think a G-code parameter ever contains letter T, or a T-code ever contains letter G.
|
||||
// dc42 doesn't think a G-code parameter ever contains letter T, or a T-code ever contains letter G.
|
||||
// So it doesn't matter in which order we look for them.
|
||||
if (gb->Seen('G'))
|
||||
{
|
||||
|
@ -1913,7 +1910,7 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
|||
break;
|
||||
|
||||
case 82: // Use absolute extruder positioning
|
||||
if (drivesRelative)
|
||||
if (drivesRelative) // don't reset the absolute extruder position if it was already absolute
|
||||
{
|
||||
for (int8_t extruder = AXES; extruder < DRIVES; extruder++)
|
||||
{
|
||||
|
@ -1941,9 +1938,9 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
|||
case 85: // Set inactive time
|
||||
break;
|
||||
|
||||
case 92: // Set/report steps/mm for some axes
|
||||
{
|
||||
bool seen = false;
|
||||
case 92: // Set/report steps/mm for some axes
|
||||
{
|
||||
bool seen = false;
|
||||
for(int8_t axis = 0; axis < AXES; axis++)
|
||||
{
|
||||
if(gb->Seen(axisLetters[axis]))
|
||||
|
@ -1991,8 +1988,8 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
|||
{
|
||||
reprap.GetMove()->SetStepHypotenuse();
|
||||
}
|
||||
}
|
||||
break;
|
||||
}
|
||||
break;
|
||||
|
||||
case 98:
|
||||
if (gb->Seen('P'))
|
||||
|
@ -2024,17 +2021,17 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
|||
}
|
||||
break;
|
||||
|
||||
case 105: // Deprecated...
|
||||
strncpy(reply, "T:", STRING_LENGTH);
|
||||
for(int8_t heater = 1; heater < HEATERS; heater++)
|
||||
{
|
||||
if(reprap.GetHeat()->GetStatus(heater) != Heat::HS_off)
|
||||
{
|
||||
sncatf(reply, STRING_LENGTH, "%.1f ", reprap.GetHeat()->GetTemperature(heater));
|
||||
}
|
||||
}
|
||||
sncatf(reply, STRING_LENGTH, "B: %.1f ", reprap.GetHeat()->GetTemperature(0));
|
||||
break;
|
||||
case 105: // Deprecated...
|
||||
strncpy(reply, "T:", STRING_LENGTH);
|
||||
for(int8_t heater = 1; heater < HEATERS; heater++)
|
||||
{
|
||||
if(reprap.GetHeat()->GetStatus(heater) != Heat::HS_off)
|
||||
{
|
||||
sncatf(reply, STRING_LENGTH, "%.1f ", reprap.GetHeat()->GetTemperature(heater));
|
||||
}
|
||||
}
|
||||
sncatf(reply, STRING_LENGTH, "B: %.1f ", reprap.GetHeat()->GetTemperature(0));
|
||||
break;
|
||||
|
||||
case 106: // Fan on or off
|
||||
if (gb->Seen('I'))
|
||||
|
@ -2048,7 +2045,8 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
|||
f = max<float>(f, 0.0);
|
||||
if (coolingInverted)
|
||||
{
|
||||
platform->CoolingFan(255.0 - f);
|
||||
// Check if 1.0 or 255.0 may be used as the maximum value
|
||||
platform->CoolingFan((f <= 1.0 ? 1.0 : 255.0) - f);
|
||||
}
|
||||
else
|
||||
{
|
||||
|
@ -2153,7 +2151,6 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
|||
}
|
||||
break;
|
||||
|
||||
//TODO M119
|
||||
case 119:
|
||||
{
|
||||
snprintf(reply, STRING_LENGTH, "Endstops - ");
|
||||
|
@ -2188,7 +2185,7 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
|||
sncatf(reply, STRING_LENGTH, "%c: %s%c ", axisLetters[axis], es, comma);
|
||||
}
|
||||
}
|
||||
break;
|
||||
break;
|
||||
|
||||
case 120:
|
||||
result = Push();
|
||||
|
@ -2231,27 +2228,27 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
|||
}
|
||||
break;
|
||||
|
||||
case 140: // Set bed temperature
|
||||
if(gb->Seen('S'))
|
||||
{
|
||||
if(HOT_BED >= 0)
|
||||
{
|
||||
reprap.GetHeat()->SetActiveTemperature(HOT_BED, gb->GetFValue());
|
||||
reprap.GetHeat()->Activate(HOT_BED);
|
||||
}
|
||||
}
|
||||
if(gb->Seen('R'))
|
||||
{
|
||||
if(HOT_BED >= 0)
|
||||
{
|
||||
reprap.GetHeat()->SetStandbyTemperature(HOT_BED, gb->GetFValue());
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
case 141: // Chamber temperature
|
||||
platform->Message(HOST_MESSAGE, "M141 - heated chamber not yet implemented\n");
|
||||
break;
|
||||
case 140: // Set bed temperature
|
||||
if(gb->Seen('S'))
|
||||
{
|
||||
if(HOT_BED >= 0)
|
||||
{
|
||||
reprap.GetHeat()->SetActiveTemperature(HOT_BED, gb->GetFValue());
|
||||
reprap.GetHeat()->Activate(HOT_BED);
|
||||
}
|
||||
}
|
||||
if(gb->Seen('R'))
|
||||
{
|
||||
if(HOT_BED >= 0)
|
||||
{
|
||||
reprap.GetHeat()->SetStandbyTemperature(HOT_BED, gb->GetFValue());
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
case 141: // Chamber temperature
|
||||
platform->Message(HOST_MESSAGE, "M141 - heated chamber not yet implemented\n");
|
||||
break;
|
||||
|
||||
// case 160: //number of mixing filament drives TODO: With tools defined, is this needed?
|
||||
// if(gb->Seen('S'))
|
||||
|
@ -2261,25 +2258,25 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
|||
// }
|
||||
// break;
|
||||
|
||||
case 190: // Deprecated...
|
||||
if(gb->Seen('S'))
|
||||
{
|
||||
if(HOT_BED >= 0)
|
||||
{
|
||||
reprap.GetHeat()->SetActiveTemperature(HOT_BED, gb->GetFValue());
|
||||
reprap.GetHeat()->Activate(HOT_BED);
|
||||
if (!AllMovesAreFinishedAndMoveBufferIsLoaded()) // tell Move not to wait for more moves
|
||||
{
|
||||
return false;
|
||||
}
|
||||
result = reprap.GetHeat()->HeaterAtSetTemperature(HOT_BED);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case 190: // Deprecated...
|
||||
if(gb->Seen('S'))
|
||||
{
|
||||
if(HOT_BED >= 0)
|
||||
{
|
||||
reprap.GetHeat()->SetActiveTemperature(HOT_BED, gb->GetFValue());
|
||||
reprap.GetHeat()->Activate(HOT_BED);
|
||||
if (!AllMovesAreFinishedAndMoveBufferIsLoaded()) // tell Move not to wait for more moves
|
||||
{
|
||||
return false;
|
||||
}
|
||||
result = reprap.GetHeat()->HeaterAtSetTemperature(HOT_BED);
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
case 201: // Set/print axis accelerations FIXME - should these be in /min not /sec ?
|
||||
{
|
||||
bool seen = false;
|
||||
case 201: // Set/print axis accelerations FIXME - should these be in /min not /sec ?
|
||||
{
|
||||
bool seen = false;
|
||||
for(int8_t axis = 0; axis < AXES; axis++)
|
||||
{
|
||||
if(gb->Seen(axisLetters[axis]))
|
||||
|
@ -2311,16 +2308,16 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
|||
|
||||
if(!seen)
|
||||
{
|
||||
snprintf(reply, STRING_LENGTH, "Axis limits - ");
|
||||
char comma = ',';
|
||||
for(int8_t axis = 0; axis < AXES; axis++)
|
||||
snprintf(reply, STRING_LENGTH, "Accelerations: X: %f, Y: %f, Z: %f, E: ",
|
||||
platform->Acceleration(X_AXIS)/distanceScale, platform->Acceleration(Y_AXIS)/distanceScale,
|
||||
platform->Acceleration(Z_AXIS)/distanceScale);
|
||||
for(int8_t drive = AXES; drive < DRIVES; drive++)
|
||||
{
|
||||
if(axis == AXES - 1)
|
||||
sncatf(reply, STRING_LENGTH, "%f", platform->Acceleration(drive)/distanceScale);
|
||||
if(drive < DRIVES-1)
|
||||
{
|
||||
comma = ' ';
|
||||
sncatf(reply, STRING_LENGTH, ":");
|
||||
}
|
||||
sncatf(reply, STRING_LENGTH, "%c: %.1f min, %.1f max%c ", axisLetters[axis],
|
||||
platform->AxisMinimum(axis), platform->AxisMaximum(axis), comma);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -2383,7 +2380,7 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
|||
result = OffsetAxes(gb);
|
||||
break;
|
||||
|
||||
case 208: // Set/print maximum axis lengths. If there is an S parameter with value 1 then we set the min value, alse we set the max value.
|
||||
case 208: // Set/print maximum axis lengths. If there is an S parameter with value 1 then we set the min value, else we set the max value.
|
||||
{
|
||||
bool setMin = (gb->Seen('S') ? (gb->GetIValue() == 1): false);
|
||||
bool seen = false;
|
||||
|
@ -2406,11 +2403,17 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
|||
|
||||
if (!seen)
|
||||
{
|
||||
snprintf(reply, STRING_LENGTH, "X:%.1f Y:%.1f Z:%.1f",
|
||||
(setMin) ? platform->AxisMinimum(X_AXIS) : platform->AxisMaximum(X_AXIS),
|
||||
(setMin) ? platform->AxisMinimum(Y_AXIS) : platform->AxisMaximum(Y_AXIS),
|
||||
(setMin) ? platform->AxisMinimum(Z_AXIS) : platform->AxisMaximum(Z_AXIS)
|
||||
);
|
||||
snprintf(reply, STRING_LENGTH, "Axis limits - ");
|
||||
char comma = ',';
|
||||
for(int8_t axis = 0; axis < AXES; axis++)
|
||||
{
|
||||
if(axis == AXES - 1)
|
||||
{
|
||||
comma = ' ';
|
||||
}
|
||||
sncatf(reply, STRING_LENGTH, "%c: %.1f min, %.1f max%c ", axisLetters[axis],
|
||||
platform->AxisMinimum(axis), platform->AxisMaximum(axis), comma);
|
||||
}
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
@ -2494,7 +2497,23 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
|||
SetPidParameters(gb, 1, reply);
|
||||
break;
|
||||
|
||||
case 302: // Allow cold extrudes
|
||||
case 302: // Allow, deny or report cold extrudes
|
||||
if (gb->Seen('P'))
|
||||
{
|
||||
if (gb->GetIValue() > 0)
|
||||
{
|
||||
reprap.AllowColdExtrude();
|
||||
}
|
||||
else
|
||||
{
|
||||
reprap.DenyColdExtrude();
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
snprintf(reply, STRING_LENGTH, "Cold extrudes are %s, use M302 P[1/0] to allow or deny them",
|
||||
reprap.ColdExtrude() ? "enabled" : "disabled");
|
||||
}
|
||||
break;
|
||||
|
||||
case 304: // Set/report heated bed PID values
|
||||
|
@ -2661,28 +2680,47 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
|||
}
|
||||
break;
|
||||
|
||||
case 558: // Set Z probe type
|
||||
if(gb->Seen('P'))
|
||||
{
|
||||
platform->SetZProbeType(gb->GetIValue());
|
||||
}
|
||||
else
|
||||
{
|
||||
snprintf(reply, STRING_LENGTH, "Z Probe: %d", platform->GetZProbeType());
|
||||
}
|
||||
case 558: // Set or report Z probe type and for which axes it is used
|
||||
{
|
||||
bool seen = false;
|
||||
if(gb->Seen('P'))
|
||||
{
|
||||
platform->SetZProbeType(gb->GetIValue());
|
||||
seen = true;
|
||||
}
|
||||
|
||||
bool zProbeAxes[AXES];
|
||||
platform->GetZProbeAxes(zProbeAxes);
|
||||
for(int axis=0; axis<AXES; axis++)
|
||||
{
|
||||
if (gb->Seen(axisLetters[axis]))
|
||||
{
|
||||
zProbeAxes[axis] = (gb->GetIValue() > 0);
|
||||
seen = true;
|
||||
}
|
||||
}
|
||||
|
||||
if (seen)
|
||||
{
|
||||
platform->SetZProbeAxes(zProbeAxes);
|
||||
}
|
||||
else
|
||||
{
|
||||
snprintf(reply, STRING_LENGTH, "Z Probe type is %d and it is used for these axes:", platform->GetZProbeType());
|
||||
for(int axis=0; axis<AXES; axis++)
|
||||
{
|
||||
if (zProbeAxes[axis])
|
||||
{
|
||||
sncatf(reply, STRING_LENGTH, " %c", axisLetters[axis]);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
case 559: // Upload config.g or another gcode file to put in the sys directory
|
||||
{
|
||||
const char* str;
|
||||
if (gb->Seen('P'))
|
||||
{
|
||||
str = gb->GetString();
|
||||
}
|
||||
else
|
||||
{
|
||||
str = platform->GetConfigFile();
|
||||
}
|
||||
const char* str = (gb->Seen('P') ? gb->GetString() : platform->GetConfigFile());
|
||||
bool ok = OpenFileToWrite(platform->GetSysDir(), str, gb);
|
||||
if (ok)
|
||||
{
|
||||
|
@ -2698,15 +2736,7 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
|||
|
||||
case 560: // Upload reprap.htm or another web interface file
|
||||
{
|
||||
const char* str;
|
||||
if (gb->Seen('P'))
|
||||
{
|
||||
str = gb->GetString();
|
||||
}
|
||||
else
|
||||
{
|
||||
str = INDEX_PAGE;
|
||||
}
|
||||
const char* str = (gb->Seen('P') ? gb->GetString() : INDEX_PAGE);
|
||||
bool ok = OpenFileToWrite(platform->GetWebDir(), str, gb);
|
||||
if (ok)
|
||||
{
|
||||
|
@ -2899,7 +2929,8 @@ bool GCodes::ChangeTool(int newToolNumber)
|
|||
{
|
||||
toolChangeSequence++;
|
||||
}
|
||||
} else
|
||||
}
|
||||
else
|
||||
{
|
||||
toolChangeSequence++;
|
||||
}
|
||||
|
@ -2921,7 +2952,8 @@ bool GCodes::ChangeTool(int newToolNumber)
|
|||
{
|
||||
toolChangeSequence++;
|
||||
}
|
||||
} else
|
||||
}
|
||||
else
|
||||
{
|
||||
toolChangeSequence++;
|
||||
}
|
||||
|
@ -2940,7 +2972,8 @@ bool GCodes::ChangeTool(int newToolNumber)
|
|||
{
|
||||
toolChangeSequence++;
|
||||
}
|
||||
} else
|
||||
}
|
||||
else
|
||||
{
|
||||
toolChangeSequence++;
|
||||
}
|
||||
|
@ -3057,7 +3090,9 @@ bool GCodeBuffer::Put(char c)
|
|||
// Strip out the line number and checksum
|
||||
|
||||
while (gcodeBuffer[gcodePointer] != ' ' && gcodeBuffer[gcodePointer])
|
||||
{
|
||||
gcodePointer++;
|
||||
}
|
||||
|
||||
// Anything there?
|
||||
|
||||
|
@ -3181,7 +3216,8 @@ const void GCodeBuffer::GetFloatArray(float a[], int& returnedLength)
|
|||
{
|
||||
a[i] = a[0];
|
||||
}
|
||||
} else
|
||||
}
|
||||
else
|
||||
{
|
||||
returnedLength = length;
|
||||
}
|
||||
|
|
41
Heat.cpp
41
Heat.cpp
|
@ -32,7 +32,9 @@ Heat::Heat(Platform* p, GCodes* g)
|
|||
void Heat::Init()
|
||||
{
|
||||
for(int8_t heater=0; heater < HEATERS; heater++)
|
||||
{
|
||||
pids[heater]->Init();
|
||||
}
|
||||
lastTime = platform->Time();
|
||||
longWait = lastTime;
|
||||
active = true;
|
||||
|
@ -41,7 +43,9 @@ void Heat::Init()
|
|||
void Heat::Exit()
|
||||
{
|
||||
for(int8_t heater=0; heater < HEATERS; heater++)
|
||||
{
|
||||
pids[heater]->SwitchOff();
|
||||
}
|
||||
platform->Message(HOST_MESSAGE, "Heat class exited.\n");
|
||||
active = false;
|
||||
}
|
||||
|
@ -116,6 +120,7 @@ void PID::Init()
|
|||
temperatureFault = false;
|
||||
active = false; // Default to standby temperature
|
||||
switchedOff = true;
|
||||
heatingUp = false;
|
||||
}
|
||||
|
||||
void PID::SwitchOn()
|
||||
|
@ -147,7 +152,8 @@ void PID::Spin()
|
|||
return;
|
||||
}
|
||||
|
||||
// We are switched on. Check for faults.
|
||||
// We are switched on. Check for faults. Temperature silly-low or silly-high mean open-circuit
|
||||
// or shorted thermistor respectively.
|
||||
|
||||
if(temperature < BAD_LOW_TEMPERATURE || temperature > BAD_HIGH_TEMPERATURE)
|
||||
{
|
||||
|
@ -157,8 +163,9 @@ void PID::Spin()
|
|||
platform->SetHeater(heater, 0.0);
|
||||
temperatureFault = true;
|
||||
switchedOff = true;
|
||||
snprintf(scratchString, STRING_LENGTH, "Temperature measurement fault on heater %d, T = %.1f\n", heater, temperature);
|
||||
snprintf(scratchString, STRING_LENGTH, "Temperature fault on heater %d, T = %.1f\n", heater, temperature);
|
||||
platform->Message(BOTH_MESSAGE, scratchString);
|
||||
reprap.FlagTemperatureFault(heater);
|
||||
}
|
||||
}
|
||||
else
|
||||
|
@ -166,6 +173,36 @@ void PID::Spin()
|
|||
badTemperatureCount = 0;
|
||||
}
|
||||
|
||||
// Now check how long it takes to warm up. If too long, maybe the thermistor is not in contact with the heater
|
||||
|
||||
if(heatingUp && heater != HOT_BED) // FIXME - also check bed warmup time?
|
||||
{
|
||||
float tmp = standbyTemperature;
|
||||
if(active)
|
||||
{
|
||||
tmp = activeTemperature;
|
||||
}
|
||||
tmp -= TEMPERATURE_CLOSE_ENOUGH;
|
||||
if(temperature < tmp)
|
||||
{
|
||||
float tim = platform->Time() - timeSetHeating;
|
||||
if(tim > TIME_TO_HOT)
|
||||
{
|
||||
platform->SetHeater(heater, 0.0);
|
||||
temperatureFault = true;
|
||||
switchedOff = true;
|
||||
snprintf(scratchString, STRING_LENGTH, "Heating fault on heater %d, T = %.1f C; still not at temperature after %f seconds.\n",
|
||||
heater, temperature, tim);
|
||||
platform->Message(BOTH_MESSAGE, scratchString);
|
||||
reprap.FlagTemperatureFault(heater);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
heatingUp = false;
|
||||
}
|
||||
}
|
||||
|
||||
float targetTemperature = (active) ? activeTemperature : standbyTemperature;
|
||||
float error = targetTemperature - temperature;
|
||||
const PidParameters& pp = platform->GetPidParameters(heater);
|
||||
|
|
13
Heat.h
13
Heat.h
|
@ -60,6 +60,8 @@ class PID
|
|||
int8_t heater; // The index of our heater
|
||||
int8_t badTemperatureCount; // Count of sequential dud readings
|
||||
bool temperatureFault; // Has our heater developed a fault?
|
||||
float timeSetHeating; // When we were switched on
|
||||
bool heatingUp; // Are we heating up?
|
||||
};
|
||||
|
||||
/**
|
||||
|
@ -139,12 +141,22 @@ inline void PID::Activate()
|
|||
{
|
||||
SwitchOn();
|
||||
active = true;
|
||||
if(!heatingUp)
|
||||
{
|
||||
timeSetHeating = platform->Time();
|
||||
}
|
||||
heatingUp = activeTemperature > temperature;
|
||||
}
|
||||
|
||||
inline void PID::Standby()
|
||||
{
|
||||
SwitchOn();
|
||||
active = false;
|
||||
if(!heatingUp)
|
||||
{
|
||||
timeSetHeating = platform->Time();
|
||||
}
|
||||
heatingUp = standbyTemperature > temperature;
|
||||
}
|
||||
|
||||
inline void PID::ResetFault()
|
||||
|
@ -158,6 +170,7 @@ inline void PID::SwitchOff()
|
|||
platform->SetHeater(heater, 0.0);
|
||||
active = false;
|
||||
switchedOff = true;
|
||||
heatingUp = false;
|
||||
}
|
||||
|
||||
|
||||
|
|
106
Platform.cpp
106
Platform.cpp
|
@ -134,6 +134,7 @@ void Platform::Init()
|
|||
nvData.macAddress = MAC_ADDRESS;
|
||||
|
||||
nvData.zProbeType = 0; // Default is to use the switch
|
||||
nvData.zProbeAxes = Z_PROBE_AXES;
|
||||
nvData.switchZProbeParameters.Init(0.0);
|
||||
nvData.irZProbeParameters.Init(Z_PROBE_STOP_HEIGHT);
|
||||
nvData.alternateZProbeParameters.Init(Z_PROBE_STOP_HEIGHT);
|
||||
|
@ -232,21 +233,21 @@ void Platform::Init()
|
|||
{
|
||||
if (stepPins[i] >= 0)
|
||||
{
|
||||
if(i == E0_DRIVE || i == E3_DRIVE) //STEP_PINS {14, 25, 5, X2, 41, 39, X4, 49}
|
||||
if(i == E0_DRIVE || i == E3_DRIVE) // STEP_PINS {14, 25, 5, X2, 41, 39, X4, 49}
|
||||
pinModeNonDue(stepPins[i], OUTPUT);
|
||||
else
|
||||
pinMode(stepPins[i], OUTPUT);
|
||||
}
|
||||
if (directionPins[i] >= 0)
|
||||
{
|
||||
if(i == E0_DRIVE) //DIRECTION_PINS {15, 26, 4, X3, 35, 53, 51, 48}
|
||||
if(i == E0_DRIVE) // DIRECTION_PINS {15, 26, 4, X3, 35, 53, 51, 48}
|
||||
pinModeNonDue(directionPins[i], OUTPUT);
|
||||
else
|
||||
pinMode(directionPins[i], OUTPUT);
|
||||
}
|
||||
if (enablePins[i] >= 0)
|
||||
{
|
||||
if(i == Z_AXIS || i==E0_DRIVE || i==E2_DRIVE) //ENABLE_PINS {29, 27, X1, X0, 37, X8, 50, 47}
|
||||
if(i == Z_AXIS || i == E0_DRIVE || i == E2_DRIVE) // ENABLE_PINS {29, 27, X1, X0, 37, X8, 50, 47}
|
||||
pinModeNonDue(enablePins[i], OUTPUT);
|
||||
else
|
||||
pinMode(enablePins[i], OUTPUT);
|
||||
|
@ -272,14 +273,14 @@ void Platform::Init()
|
|||
{
|
||||
if (heatOnPins[i] >= 0)
|
||||
{
|
||||
if(i == E0_HEATER || i==E1_HEATER) //HEAT_ON_PINS {6, X5, X7, 7, 8, 9}
|
||||
if(i == E0_HEATER || i == E1_HEATER) // HEAT_ON_PINS {6, X5, X7, 7, 8, 9}
|
||||
{
|
||||
digitalWriteNonDue(heatOnPins[i], HIGH); // turn the heater off
|
||||
digitalWriteNonDue(heatOnPins[i], HIGH); // turn the heater off
|
||||
pinModeNonDue(heatOnPins[i], OUTPUT);
|
||||
}
|
||||
else
|
||||
{
|
||||
digitalWrite(heatOnPins[i], HIGH); // turn the heater off
|
||||
digitalWrite(heatOnPins[i], HIGH); // turn the heater off
|
||||
pinMode(heatOnPins[i], OUTPUT);
|
||||
}
|
||||
}
|
||||
|
@ -391,6 +392,23 @@ int Platform::GetZProbeType() const
|
|||
return nvData.zProbeType;
|
||||
}
|
||||
|
||||
void Platform::SetZProbeAxes(const bool axes[AXES])
|
||||
{
|
||||
for(int axis=0; axis<AXES; axis++)
|
||||
{
|
||||
nvData.zProbeAxes[axis] = axes[axis];
|
||||
}
|
||||
WriteNvData();
|
||||
}
|
||||
|
||||
void Platform::GetZProbeAxes(bool (&axes)[AXES])
|
||||
{
|
||||
for(int axis=0; axis<AXES; axis++)
|
||||
{
|
||||
axes[axis] = nvData.zProbeAxes[axis];
|
||||
}
|
||||
}
|
||||
|
||||
float Platform::ZProbeStopHeight() const
|
||||
{
|
||||
switch (nvData.zProbeType)
|
||||
|
@ -793,11 +811,13 @@ void Platform::Diagnostics()
|
|||
AppendMessage(BOTH_MESSAGE, scratchString);
|
||||
reprap.Timing();
|
||||
|
||||
#if LWIP_STATS
|
||||
// Normally we should NOT try to display LWIP stats here, because it uses debugPrintf(), which will hang the system is no USB cable is connected.
|
||||
if (reprap.Debug())
|
||||
{
|
||||
stats_display();
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
void Platform::DiagnosticTest(int d)
|
||||
|
@ -930,21 +950,18 @@ void Platform::SetHeater(size_t heater, const float& power)
|
|||
|
||||
EndStopHit Platform::Stopped(int8_t drive)
|
||||
{
|
||||
if (nvData.zProbeType > 0)
|
||||
{ // Z probe is used for both X and Z.
|
||||
if (drive != Y_AXIS)
|
||||
{
|
||||
int zProbeVal = ZProbe();
|
||||
int zProbeADValue =
|
||||
(nvData.zProbeType == 3) ?
|
||||
nvData.alternateZProbeParameters.adcValue : nvData.irZProbeParameters.adcValue;
|
||||
if (zProbeVal >= zProbeADValue)
|
||||
return lowHit;
|
||||
else if (zProbeVal * 10 >= zProbeADValue * 9) // if we are at/above 90% of the target value
|
||||
return lowNear;
|
||||
else
|
||||
return noStop;
|
||||
}
|
||||
if (nvData.zProbeType > 0 && drive < AXES && nvData.zProbeAxes[drive])
|
||||
{
|
||||
int zProbeVal = ZProbe();
|
||||
int zProbeADValue =
|
||||
(nvData.zProbeType == 3) ?
|
||||
nvData.alternateZProbeParameters.adcValue : nvData.irZProbeParameters.adcValue;
|
||||
if (zProbeVal >= zProbeADValue)
|
||||
return lowHit;
|
||||
else if (zProbeVal * 10 >= zProbeADValue * 9) // if we are at/above 90% of the target value
|
||||
return lowNear;
|
||||
else
|
||||
return noStop;
|
||||
}
|
||||
|
||||
if (lowStopPins[drive] >= 0)
|
||||
|
@ -965,9 +982,13 @@ void Platform::SetDirection(byte drive, bool direction)
|
|||
if(directionPins[drive] < 0)
|
||||
return;
|
||||
if(drive == E0_DRIVE) //DIRECTION_PINS {15, 26, 4, X3, 35, 53, 51, 48}
|
||||
{
|
||||
digitalWriteNonDue(directionPins[drive], direction);
|
||||
}
|
||||
else
|
||||
{
|
||||
digitalWrite(directionPins[drive], direction);
|
||||
}
|
||||
}
|
||||
|
||||
void Platform::Disable(byte drive)
|
||||
|
@ -1041,13 +1062,28 @@ float Platform::MotorCurrent(byte drive)
|
|||
return (float)pot * maxStepperDigipotVoltage / (0.256 * 8.0 * senseResistor);
|
||||
}
|
||||
|
||||
//Changed to be compatible with existing gcode norms
|
||||
// M106 S0 = fully off M106 S255 = fully on
|
||||
// This is a bit of a compromise - old RepRaps used fan speeds in the range
|
||||
// [0, 255], which is very hardware dependent. It makes much more sense
|
||||
// to specify speeds in [0.0, 1.0]. This looks at the value supplied (which
|
||||
// the G Code reader will get right for a float or an int) and attempts to
|
||||
// do the right thing whichever the user has done. This will only not work
|
||||
// for an old-style fan speed of 1/255...
|
||||
|
||||
void Platform::CoolingFan(float speed)
|
||||
{
|
||||
if(coolingFanPin >= 0)
|
||||
{
|
||||
byte p =(byte)speed;
|
||||
byte p;
|
||||
|
||||
if(speed <= 1.0)
|
||||
{
|
||||
p = (byte)(255.0 * max<float>(0.0, speed));
|
||||
}
|
||||
else
|
||||
{
|
||||
p = (byte)speed;
|
||||
}
|
||||
|
||||
// The cooling fan output pin gets inverted if HEAT_ON == 0
|
||||
analogWriteNonDue(coolingFanPin, (HEAT_ON == 0) ? (255 - p) : p);
|
||||
}
|
||||
|
@ -1057,17 +1093,17 @@ void Platform::CoolingFan(float speed)
|
|||
|
||||
void Platform::SetInterrupt(float s) // Seconds
|
||||
{
|
||||
if (s <= 0.0)
|
||||
{
|
||||
//NVIC_DisableIRQ(TC3_IRQn);
|
||||
Message(HOST_MESSAGE, "Negative interrupt!\n");
|
||||
s = STANDBY_INTERRUPT_RATE;
|
||||
}
|
||||
uint32_t rc = (uint32_t)( (((long)(TIME_TO_REPRAP*s))*84l)/128l );
|
||||
TC_SetRA(TC1, 0, rc/2); //50% high, 50% low
|
||||
TC_SetRC(TC1, 0, rc);
|
||||
TC_Start(TC1, 0);
|
||||
NVIC_EnableIRQ(TC3_IRQn);
|
||||
if (s <= 0.0)
|
||||
{
|
||||
//NVIC_DisableIRQ(TC3_IRQn);
|
||||
Message(HOST_MESSAGE, "Negative interrupt!\n");
|
||||
s = STANDBY_INTERRUPT_RATE;
|
||||
}
|
||||
uint32_t rc = (uint32_t)( (((long)(TIME_TO_REPRAP*s))*84l)/128l );
|
||||
TC_SetRA(TC1, 0, rc/2); //50% high, 50% low
|
||||
TC_SetRC(TC1, 0, rc);
|
||||
TC_Start(TC1, 0);
|
||||
NVIC_EnableIRQ(TC3_IRQn);
|
||||
}
|
||||
|
||||
//-----------------------------------------------------------------------------------------------------
|
||||
|
|
74
Platform.h
74
Platform.h
|
@ -99,6 +99,7 @@ Licence: GPL
|
|||
#define Z_PROBE_STOP_HEIGHT (0.7) // mm
|
||||
#define Z_PROBE_PIN (10) // Analogue pin number
|
||||
#define Z_PROBE_MOD_PIN (52) // Digital pin number to turn the IR LED on (high) or off (low)
|
||||
#define Z_PROBE_AXES {true, false, true} // Axes for which the Z-probe is normally used
|
||||
const unsigned int numZProbeReadingsAveraged = 8; // we average this number of readings with IR on, and the same number with IR off
|
||||
|
||||
#define MAX_FEEDRATES {100.0, 100.0, 3.0, 20.0, 20.0, 20.0, 20.0, 20.0} // mm/sec
|
||||
|
@ -107,6 +108,12 @@ const unsigned int numZProbeReadingsAveraged = 8; // we average this number of r
|
|||
#define INSTANT_DVS {15.0, 15.0, 0.2, 2.0, 2.0, 2.0, 2.0, 2.0} // (mm/sec)
|
||||
#define NUM_MIXING_DRIVES 1; //number of mixing drives
|
||||
|
||||
#define E0_DRIVE 3 //the index of the first Extruder drive
|
||||
#define E1_DRIVE 4 //the index of the second Extruder drive
|
||||
#define E2_DRIVE 5 //the index of the third Extruder drive
|
||||
#define E3_DRIVE 6 //the index of the fourth Extruder drive
|
||||
#define E4_DRIVE 7 //the index of the fifth Extruder drive
|
||||
|
||||
// AXES
|
||||
|
||||
#define AXIS_MAXIMA {220, 200, 200} // mm
|
||||
|
@ -118,12 +125,6 @@ const unsigned int numZProbeReadingsAveraged = 8; // we average this number of r
|
|||
#define Y_AXIS 1 // The index of the Y axis
|
||||
#define Z_AXIS 2 // The index of the Z axis
|
||||
|
||||
#define E0_DRIVE 3 //the index of the first Extruder drive
|
||||
#define E1_DRIVE 4 //the index of the second Extruder drive
|
||||
#define E2_DRIVE 5 //the index of the third Extruder drive
|
||||
#define E3_DRIVE 6 //the index of the fourth Extruder drive
|
||||
#define E4_DRIVE 7 //the index of the fifth Extruder drive
|
||||
|
||||
// HEATERS - The bed is assumed to be the at index 0
|
||||
|
||||
#define TEMP_SENSE_PINS {5, 4, 0, 7, 8, 9} // Analogue pin numbers
|
||||
|
@ -168,15 +169,10 @@ const float defaultFullBand[HEATERS] = {5.0, 30.0, 30.0, 30.0, 30.0, 30.0}; //
|
|||
const float defaultPidMin[HEATERS] = {0.0, 0.0, 0.0, 0.0, 0.0, 0.0}; // minimum value of I-term
|
||||
const float defaultPidMax[HEATERS] = {255, 180, 180, 180, 180, 180}; // maximum value of I-term, must be high enough to reach 245C for ABS printing
|
||||
|
||||
#define STANDBY_TEMPERATURES {ABS_ZERO, ABS_ZERO} // We specify one for the bed, though it's not needed
|
||||
#define ACTIVE_TEMPERATURES {ABS_ZERO, ABS_ZERO}
|
||||
#define COOLING_FAN_PIN X6 // pin D34 is PWM capable but not an Arduino PWM pin - use X6 instead
|
||||
#define HEAT_ON 0 // 0 for inverted heater (eg Duet v0.6) 1 for not (e.g. Duet v0.4)
|
||||
|
||||
#define STANDBY_TEMPERATURES {ABS_ZERO, ABS_ZERO, ABS_ZERO, ABS_ZERO, ABS_ZERO, ABS_ZERO} // We specify one for the bed, though it's not needed
|
||||
#define ACTIVE_TEMPERATURES {ABS_ZERO, ABS_ZERO, ABS_ZERO, ABS_ZERO, ABS_ZERO, ABS_ZERO}
|
||||
#define COOLING_FAN_PIN X6 //pin D34 is PWM capable but not an Arduino PWM pin - use X6 instead
|
||||
#define HEAT_ON 0 // 0 for inverted heater (e.g. Duet v0.6) 1 for not (e.g. Duet v0.4)
|
||||
#define COOLING_FAN_PIN X6 //pin D34 is PWM capable but not an Arduino PWM pin - use X6 instead
|
||||
#define HEAT_ON 0 // 0 for inverted heater (e.g. Duet v0.6) 1 for not (e.g. Duet v0.4)
|
||||
|
||||
// For the theory behind ADC oversampling, see http://www.atmel.com/Images/doc8003.pdf
|
||||
const unsigned int adOversampleBits = 1; // number of bits we oversample when reading temperatures
|
||||
|
@ -191,10 +187,10 @@ const unsigned int adDisconnectedVirtual = adDisconnectedReal << adOversampleBit
|
|||
|
||||
#define HOT_BED 0 // The index of the heated bed; set to -1 if there is no heated bed
|
||||
#define E0_HEATER 1 //the index of the first extruder heater
|
||||
#define E1_HEATER 2 //the index of the first extruder heater
|
||||
#define E2_HEATER 3 //the index of the first extruder heater
|
||||
#define E3_HEATER 4 //the index of the first extruder heater
|
||||
#define E4_HEATER 5 //the index of the first extruder heater
|
||||
#define E1_HEATER 2 //the index of the second extruder heater
|
||||
#define E2_HEATER 3 //the index of the third extruder heater
|
||||
#define E3_HEATER 4 //the index of the fourth extruder heater
|
||||
#define E4_HEATER 5 //the index of the fifth extruder heater
|
||||
|
||||
/****************************************************************************************************/
|
||||
|
||||
|
@ -346,17 +342,17 @@ class FileStore //: public InputOutput
|
|||
public:
|
||||
|
||||
int8_t Status(); // Returns OR of IOStatus
|
||||
bool Read(char& b);
|
||||
int Read(char* buf, unsigned int nBytes);
|
||||
bool Write(char b);
|
||||
bool Write(const char *s, unsigned int len);
|
||||
bool Write(const char* s);
|
||||
bool Close();
|
||||
bool Seek(unsigned long pos);
|
||||
bool GoToEnd(); // Position the file at the end (so you can write on the end).
|
||||
unsigned long Length(); // File size in bytes
|
||||
void Duplicate();
|
||||
bool Flush();
|
||||
bool Read(char& b); // Read 1 byte
|
||||
int Read(char* buf, unsigned int nBytes); // Read a block of nBytes length
|
||||
bool Write(char b); // Write 1 byte
|
||||
bool Write(const char *s, unsigned int len); // Write a block of len bytes
|
||||
bool Write(const char* s); // Write a string
|
||||
bool Close(); // Shut the file and tidy up
|
||||
bool Seek(unsigned long pos); // Jump to pos in the file
|
||||
bool GoToEnd(); // Position the file at the end (so you can write on the end).
|
||||
unsigned long Length(); // File size in bytes
|
||||
void Duplicate(); // Create a second reference to this file
|
||||
bool Flush(); // Write remaining buffer data
|
||||
|
||||
friend class Platform;
|
||||
|
||||
|
@ -610,6 +606,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 SetZProbing(bool starting);
|
||||
bool GetZProbeParameters(struct ZProbeParameters& params) const;
|
||||
bool SetZProbeParameters(const struct ZProbeParameters& params);
|
||||
|
@ -617,8 +615,8 @@ public:
|
|||
|
||||
// Mixing support
|
||||
|
||||
void SetMixingDrives(int);
|
||||
int GetMixingDrives();
|
||||
// void SetMixingDrives(int);
|
||||
// int GetMixingDrives();
|
||||
|
||||
int8_t SlowestDrive() const;
|
||||
|
||||
|
@ -655,6 +653,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
|
||||
PidParameters pidParams[HEATERS];
|
||||
byte ipAddress[4];
|
||||
byte netMask[4];
|
||||
|
@ -991,21 +990,6 @@ inline float Platform::AxisTotalLength(int8_t axis) const
|
|||
return axisMaxima[axis] - axisMinima[axis];
|
||||
}
|
||||
|
||||
inline void Platform::SetMixingDrives(int num_drives)
|
||||
{
|
||||
if(num_drives>(DRIVES-AXES))
|
||||
{
|
||||
Message(HOST_MESSAGE, "More mixing extruder drives set with M160 than exist in firmware configuration\n");
|
||||
return;
|
||||
}
|
||||
numMixingDrives = num_drives;
|
||||
}
|
||||
|
||||
inline int Platform::GetMixingDrives()
|
||||
{
|
||||
return numMixingDrives;
|
||||
}
|
||||
|
||||
//********************************************************************************************************
|
||||
|
||||
// Drive the RepRap machine - Heat and temperature
|
||||
|
|
Binary file not shown.
|
@ -189,13 +189,12 @@ void RepRap::Init()
|
|||
currentTool = NULL;
|
||||
const uint32_t wdtTicks = 256; // number of watchdog ticks @ 32768Hz/128 before the watchdog times out (max 4095)
|
||||
WDT_Enable(WDT, (wdtTicks << WDT_MR_WDV_Pos) | (wdtTicks << WDT_MR_WDD_Pos) | WDT_MR_WDRSTEN); // enable watchdog, reset the mcu if it times out
|
||||
active = true; // must do this before we start the network, else the watchdog may time out
|
||||
coldExtrude = true; // DC42 changed default to true for compatibility because for now we are aiming for copatibility with RRP 0.78
|
||||
active = true; // must do this before we start the network, else the watchdog may time out
|
||||
|
||||
snprintf(scratchString, STRING_LENGTH, "%s Version %s dated %s\n", NAME, VERSION, DATE);
|
||||
platform->Message(HOST_MESSAGE, scratchString);
|
||||
|
||||
platform->Message(HOST_MESSAGE, NAME);
|
||||
platform->Message(HOST_MESSAGE, " Version ");
|
||||
platform->Message(HOST_MESSAGE, VERSION);
|
||||
platform->Message(HOST_MESSAGE, ", dated ");
|
||||
platform->Message(HOST_MESSAGE, DATE);
|
||||
platform->Message(HOST_MESSAGE, ".\n\nExecuting ");
|
||||
platform->Message(HOST_MESSAGE, platform->GetConfigFile());
|
||||
platform->Message(HOST_MESSAGE, "...\n\n");
|
||||
|
|
26
Reprap.h
26
Reprap.h
|
@ -41,7 +41,12 @@ class RepRap
|
|||
Tool* GetCurrentTool();
|
||||
Tool* GetTool(int toolNumber);
|
||||
void SetToolVariables(int toolNumber, float* standbyTemperatures, float* activeTemperatures);
|
||||
void AllowColdExtrude();
|
||||
void DenyColdExtrude();
|
||||
bool ColdExtrude() const;
|
||||
void PrintTool(int toolNumber, char* reply) const;
|
||||
void FlagTemperatureFault(int8_t dudHeater);
|
||||
void ClearTemperatureFault(int8_t wasDudHeater);
|
||||
Platform* GetPlatform() const;
|
||||
Move* GetMove() const;
|
||||
Heat* GetHeat() const;
|
||||
|
@ -74,6 +79,7 @@ class RepRap
|
|||
bool resetting;
|
||||
uint16_t activeExtruders;
|
||||
uint16_t activeHeaters;
|
||||
bool coldExtrude;
|
||||
};
|
||||
|
||||
inline Platform* RepRap::GetPlatform() const { return platform; }
|
||||
|
@ -86,6 +92,26 @@ inline bool RepRap::Debug() const { return debug; }
|
|||
inline Tool* RepRap::GetCurrentTool() { return currentTool; }
|
||||
inline uint16_t RepRap::GetExtrudersInUse() const { return activeExtruders; }
|
||||
inline uint16_t RepRap::GetHeatersInUse() const { return activeHeaters; }
|
||||
inline bool RepRap::ColdExtrude() const { return coldExtrude; }
|
||||
inline void RepRap::AllowColdExtrude() { coldExtrude = true; }
|
||||
inline void RepRap::DenyColdExtrude() { coldExtrude = false; }
|
||||
|
||||
inline void RepRap::FlagTemperatureFault(int8_t dudHeater)
|
||||
{
|
||||
if(toolList != NULL)
|
||||
{
|
||||
toolList->FlagTemperatureFault(dudHeater);
|
||||
}
|
||||
}
|
||||
|
||||
inline void RepRap::ClearTemperatureFault(int8_t wasDudHeater)
|
||||
{
|
||||
reprap.GetHeat()->ResetFault(wasDudHeater);
|
||||
if(toolList != NULL)
|
||||
{
|
||||
toolList->ClearTemperatureFault(wasDudHeater);
|
||||
}
|
||||
}
|
||||
|
||||
inline void RepRap::SetDebug(bool d)
|
||||
{
|
||||
|
|
97
Tool.cpp
97
Tool.cpp
|
@ -32,6 +32,8 @@ Tool::Tool(int toolNumber, long d[], int dCount, long h[], int hCount)
|
|||
active = false;
|
||||
driveCount = dCount;
|
||||
heaterCount = hCount;
|
||||
heaterFault = false;
|
||||
mixing = false;
|
||||
|
||||
if(driveCount > 0)
|
||||
{
|
||||
|
@ -43,9 +45,12 @@ Tool::Tool(int toolNumber, long d[], int dCount, long h[], int hCount)
|
|||
return;
|
||||
}
|
||||
drives = new int[driveCount];
|
||||
mix = new float[driveCount];
|
||||
float r = 1.0/(float)driveCount;
|
||||
for(int8_t drive = 0; drive < driveCount; drive++)
|
||||
{
|
||||
drives[drive] = d[drive];
|
||||
mix[drive] = r;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -70,7 +75,7 @@ Tool::Tool(int toolNumber, long d[], int dCount, long h[], int hCount)
|
|||
}
|
||||
}
|
||||
|
||||
void Tool::Print(char* reply) const
|
||||
void Tool::Print(char* reply)
|
||||
{
|
||||
snprintf(reply, STRING_LENGTH, "Tool %d - drives: ", myNumber);
|
||||
char comma = ',';
|
||||
|
@ -97,6 +102,7 @@ void Tool::Print(char* reply) const
|
|||
|
||||
sncatf(reply, STRING_LENGTH, " status: %s", active ? "selected" : "standby");
|
||||
}
|
||||
|
||||
float Tool::MaxFeedrate() const
|
||||
{
|
||||
if(driveCount <= 0)
|
||||
|
@ -138,17 +144,83 @@ float Tool::InstantDv() const
|
|||
// Add a tool to the end of the linked list.
|
||||
// (We must already be in it.)
|
||||
|
||||
void Tool::AddTool(Tool* t)
|
||||
void Tool::AddTool(Tool* tool)
|
||||
{
|
||||
Tool* last = this;
|
||||
Tool* n = next;
|
||||
Tool* t = this;
|
||||
Tool* last;
|
||||
while(t != NULL)
|
||||
{
|
||||
if(t->Number() == tool->Number())
|
||||
{
|
||||
reprap.GetPlatform()->Message(HOST_MESSAGE, "Add tool: tool number already in use.\n");
|
||||
return;
|
||||
}
|
||||
last = t;
|
||||
t = t->Next();
|
||||
}
|
||||
tool->next = NULL; // Defensive...
|
||||
last->next = tool;
|
||||
}
|
||||
|
||||
// There is a temperature fault on a heater.
|
||||
// Disable all tools using that heater.
|
||||
// This function must be called for the first
|
||||
// entry in the linked list.
|
||||
|
||||
void Tool::FlagTemperatureFault(int8_t heater)
|
||||
{
|
||||
Tool* n = this;
|
||||
while(n != NULL)
|
||||
{
|
||||
last = n;
|
||||
n->SetTemperatureFault(heater);
|
||||
n = n->Next();
|
||||
}
|
||||
t->next = NULL; // Defensive...
|
||||
last->next = t;
|
||||
}
|
||||
|
||||
void Tool::ClearTemperatureFault(int8_t heater)
|
||||
{
|
||||
Tool* n = this;
|
||||
while(n != NULL)
|
||||
{
|
||||
n->ResetTemperatureFault(heater);
|
||||
n = n->Next();
|
||||
}
|
||||
}
|
||||
|
||||
void Tool::SetTemperatureFault(int8_t dudHeater)
|
||||
{
|
||||
for(int8_t heater = 0; heater < heaterCount; heater++)
|
||||
{
|
||||
if(dudHeater == heaters[heater])
|
||||
{
|
||||
heaterFault = true;
|
||||
return;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void Tool::ResetTemperatureFault(int8_t wasDudHeater)
|
||||
{
|
||||
for(int8_t heater = 0; heater < heaterCount; heater++)
|
||||
{
|
||||
if(wasDudHeater == heaters[heater])
|
||||
{
|
||||
heaterFault = false;
|
||||
return;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
bool Tool::AllHeatersAtHighTemperature() const
|
||||
{
|
||||
for(int8_t heater = 0; heater < heaterCount; heater++)
|
||||
{
|
||||
if(reprap.GetHeat()->GetTemperature(heaters[heater]) < HOT_ENOUGH_TO_EXTRUDE)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
void Tool::Activate(Tool* currentlyActive)
|
||||
|
@ -200,6 +272,17 @@ void Tool::GetVariables(float* standby, float* active) const
|
|||
}
|
||||
}
|
||||
|
||||
bool Tool::ToolCanDrive() const
|
||||
{
|
||||
if(heaterFault)
|
||||
return false;
|
||||
|
||||
if(reprap.ColdExtrude() || AllHeatersAtHighTemperature())
|
||||
return true;
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
// Update the number of active drives and extruders in use to reflect what this tool uses
|
||||
void Tool::UpdateExtruderAndHeaterCount(uint16_t &numExtruders, uint16_t &numHeaters) const
|
||||
{
|
||||
|
|
53
Tool.h
53
Tool.h
|
@ -34,14 +34,20 @@ public:
|
|||
void GetOffset(float& xx, float& yy, float& zz) const;
|
||||
int DriveCount() const;
|
||||
int Drive(int driveNumber) const;
|
||||
bool ToolCanDrive() const;
|
||||
int HeaterCount() const;
|
||||
int Heater(int heaterNumber) const;
|
||||
int Number() const;
|
||||
void SetVariables(float* standby, float* active);
|
||||
void GetVariables(float* standby, float* active) const;
|
||||
void DefineMix(float* m);
|
||||
float* GetMix() const;
|
||||
void TurnMixingOn();
|
||||
void TurnMixingOff();
|
||||
bool Mixing() const;
|
||||
float MaxFeedrate() const;
|
||||
float InstantDv() const;
|
||||
void Print(char* reply) const;
|
||||
void Print(char* reply);
|
||||
|
||||
friend class RepRap;
|
||||
|
||||
|
@ -50,13 +56,20 @@ protected:
|
|||
Tool* Next() const;
|
||||
void Activate(Tool* currentlyActive);
|
||||
void Standby();
|
||||
void AddTool(Tool* t);
|
||||
void AddTool(Tool* tool);
|
||||
void FlagTemperatureFault(int8_t dudHeater);
|
||||
void ClearTemperatureFault(int8_t wasDudHeater);
|
||||
void UpdateExtruderAndHeaterCount(uint16_t &extruders, uint16_t &heaters) const;
|
||||
|
||||
private:
|
||||
|
||||
void SetTemperatureFault(int8_t dudHeater);
|
||||
void ResetTemperatureFault(int8_t wasDudHeater);
|
||||
bool AllHeatersAtHighTemperature() const;
|
||||
int myNumber;
|
||||
int* drives;
|
||||
float* mix;
|
||||
bool mixing;
|
||||
int driveCount;
|
||||
int* heaters;
|
||||
float* activeTemperatures;
|
||||
|
@ -64,13 +77,9 @@ private:
|
|||
int heaterCount;
|
||||
Tool* next;
|
||||
bool active;
|
||||
bool heaterFault;
|
||||
};
|
||||
|
||||
inline int Tool::DriveCount() const
|
||||
{
|
||||
return driveCount;
|
||||
}
|
||||
|
||||
inline int Tool::Drive(int driveNumber) const
|
||||
{
|
||||
return drives[driveNumber];
|
||||
|
@ -96,7 +105,37 @@ inline int Tool::Number() const
|
|||
return myNumber;
|
||||
}
|
||||
|
||||
inline void Tool::DefineMix(float* m)
|
||||
{
|
||||
for(int8_t drive = 0; drive < driveCount; drive++)
|
||||
{
|
||||
mix[drive] = m[drive];
|
||||
}
|
||||
}
|
||||
|
||||
inline float* Tool::GetMix() const
|
||||
{
|
||||
return mix;
|
||||
}
|
||||
|
||||
inline void Tool::TurnMixingOn()
|
||||
{
|
||||
mixing = true;
|
||||
}
|
||||
|
||||
inline void Tool::TurnMixingOff()
|
||||
{
|
||||
mixing = false;
|
||||
}
|
||||
|
||||
inline bool Tool::Mixing() const
|
||||
{
|
||||
return mixing;
|
||||
}
|
||||
|
||||
inline int Tool::DriveCount() const
|
||||
{
|
||||
return driveCount;
|
||||
}
|
||||
|
||||
#endif /* TOOL_H_ */
|
||||
|
|
|
@ -495,7 +495,6 @@ void Webserver::ConnectionLost(const ConnectionState *cs)
|
|||
if (interpreter->DebugEnabled())
|
||||
{
|
||||
debugPrintf("Webserver: ConnectionLost called with port %d\n", local_port);
|
||||
platform->Message(DEBUG_MESSAGE, scratchString);
|
||||
}
|
||||
|
||||
interpreter->ConnectionLost(local_port);
|
||||
|
|
Reference in a new issue