Merged RepRapRro's 0.65e version in
Merged changes (mostly to handle multiple tools i.e. extruders) from RRP's 0.65e version.
This commit is contained in:
parent
08f7d2e9b1
commit
73724a4b9a
16 changed files with 1190 additions and 469 deletions
|
@ -24,9 +24,9 @@ Licence: GPL
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
|
|
||||||
#define NAME "RepRapFirmware"
|
#define NAME "RepRapFirmware"
|
||||||
#define VERSION "0.59e-dc42"
|
#define VERSION "0.65e-dc42"
|
||||||
#define DATE "2014-06-01"
|
#define DATE "2014-06-04"
|
||||||
#define LAST_AUTHOR "dc42"
|
#define LAST_AUTHOR "reprappro & dc42"
|
||||||
|
|
||||||
// Other firmware that we might switch to be compatible with.
|
// Other firmware that we might switch to be compatible with.
|
||||||
|
|
||||||
|
@ -48,19 +48,19 @@ enum Compatibility
|
||||||
|
|
||||||
#define HEAT_SAMPLE_TIME (0.5) // Seconds
|
#define HEAT_SAMPLE_TIME (0.5) // Seconds
|
||||||
|
|
||||||
#define TEMPERATURE_CLOSE_ENOUGH (2.5) // Celsius
|
#define TEMPERATURE_CLOSE_ENOUGH (2.0) // Celsius
|
||||||
#define TEMPERATURE_LOW_SO_DONT_CARE (40.0) // Celsius
|
#define TEMPERATURE_LOW_SO_DONT_CARE (40.0) // Celsius
|
||||||
|
|
||||||
// If temperatures fall outside this range, something nasty has happened.
|
// If temperatures fall outside this range, something nasty has happened.
|
||||||
|
|
||||||
#define BAD_LOW_TEMPERATURE -30.0
|
|
||||||
#define BAD_HIGH_TEMPERATURE 300.0
|
|
||||||
#define MAX_BAD_TEMPERATURE_COUNT 6
|
#define MAX_BAD_TEMPERATURE_COUNT 6
|
||||||
|
#define BAD_LOW_TEMPERATURE -10.0
|
||||||
|
#define BAD_HIGH_TEMPERATURE 300.0
|
||||||
|
|
||||||
#define STANDBY_INTERRUPT_RATE 2.0e-4 // Seconds
|
#define STANDBY_INTERRUPT_RATE 2.0e-4 // Seconds
|
||||||
|
|
||||||
#define NUMBER_OF_PROBE_POINTS 4
|
#define NUMBER_OF_PROBE_POINTS 4
|
||||||
#define Z_DIVE 5.0 // Height from which to probe the bed (mm)
|
#define Z_DIVE 8.0 // Height from which to probe the bed (mm)
|
||||||
|
|
||||||
#define SILLY_Z_VALUE -9999.0
|
#define SILLY_Z_VALUE -9999.0
|
||||||
|
|
||||||
|
@ -77,6 +77,12 @@ enum Compatibility
|
||||||
#define HOME_Z_G "homez.g"
|
#define HOME_Z_G "homez.g"
|
||||||
#define HOME_ALL_G "homeall.g"
|
#define HOME_ALL_G "homeall.g"
|
||||||
|
|
||||||
|
#define LIST_SEPARATOR ':' // Lists in G Codes
|
||||||
|
#define FILE_LIST_SEPARATOR ',' // Put this between file names when listing them
|
||||||
|
#define FILE_LIST_BRACKET '"' // Put these round file names when listing them
|
||||||
|
|
||||||
|
#define GCODE_LETTERS { 'X', 'Y', 'Z', 'E', 'F' } // The drives and feedrate in a GCode
|
||||||
|
|
||||||
#define LONG_TIME 300.0 // Seconds
|
#define LONG_TIME 300.0 // Seconds
|
||||||
|
|
||||||
#define EOF_STRING "<!-- **EoF** -->"
|
#define EOF_STRING "<!-- **EoF** -->"
|
||||||
|
|
412
GCodes.cpp
412
GCodes.cpp
|
@ -78,10 +78,6 @@ void GCodes::Reset()
|
||||||
fileGCode->Init();
|
fileGCode->Init();
|
||||||
serialGCode->Init();
|
serialGCode->Init();
|
||||||
cannedCycleGCode->Init();
|
cannedCycleGCode->Init();
|
||||||
webGCode->SetFinished(true);
|
|
||||||
fileGCode->SetFinished(true);
|
|
||||||
serialGCode->SetFinished(true);
|
|
||||||
cannedCycleGCode->SetFinished(true);
|
|
||||||
moveAvailable = false;
|
moveAvailable = false;
|
||||||
fileBeingPrinted.Close();
|
fileBeingPrinted.Close();
|
||||||
fileToPrint.Close();
|
fileToPrint.Close();
|
||||||
|
@ -99,7 +95,7 @@ void GCodes::Reset()
|
||||||
extrusionFactor = 1.0;
|
extrusionFactor = 1.0;
|
||||||
}
|
}
|
||||||
|
|
||||||
void GCodes::doFilePrint(GCodeBuffer* gb)
|
void GCodes::DoFilePrint(GCodeBuffer* gb)
|
||||||
{
|
{
|
||||||
char b;
|
char b;
|
||||||
|
|
||||||
|
@ -240,7 +236,7 @@ void GCodes::Spin()
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
doFilePrint(fileGCode);
|
DoFilePrint(fileGCode);
|
||||||
|
|
||||||
platform->ClassReport("GCodes", longWait);
|
platform->ClassReport("GCodes", longWait);
|
||||||
}
|
}
|
||||||
|
@ -336,6 +332,8 @@ bool GCodes::Pop()
|
||||||
// Move expects all axis movements to be absolute, and all
|
// Move expects all axis movements to be absolute, and all
|
||||||
// extruder drive moves to be relative. This function serves that.
|
// extruder drive moves to be relative. This function serves that.
|
||||||
// If applyLimits is true and we have homed the relevant axes, then we don't allow movement beyond the bed.
|
// If applyLimits is true and we have homed the relevant axes, then we don't allow movement beyond the bed.
|
||||||
|
// Note that if no tool is active (i.e. a Tn command hasn't previously been sent) then no E values will
|
||||||
|
// be acted upon as there is nothing to apply them to.
|
||||||
|
|
||||||
void GCodes::LoadMoveBufferFromGCode(GCodeBuffer *gb, bool doingG92, bool applyLimits)
|
void GCodes::LoadMoveBufferFromGCode(GCodeBuffer *gb, bool doingG92, bool applyLimits)
|
||||||
{
|
{
|
||||||
|
@ -371,24 +369,86 @@ void GCodes::LoadMoveBufferFromGCode(GCodeBuffer *gb, bool doingG92, bool applyL
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
if (gb->Seen(gCodeLetters[i]))
|
/*Fixed to work with multiple concurrent extruder drives:
|
||||||
|
* Default or M160 S1 (set use only one extruder drive)
|
||||||
|
* "G1 En.n" adds the float n.n to the move buffer for the selected head
|
||||||
|
* There is no change in behaviour for one extruder drive setups, or multiple extruder
|
||||||
|
* setups where only one drive is used at any one time.
|
||||||
|
*
|
||||||
|
* M160 Sn (set to use "n" extruder drives) eg
|
||||||
|
* "M160 S3"
|
||||||
|
* "G1 En.n:m.m:o.o" adds the floats to the move buffer in the following way:
|
||||||
|
* moveBuffer[AXES+selectedHead) = n.n
|
||||||
|
* moveBuffer[AXES+selectedHead+1) = m.m
|
||||||
|
* moveBuffer[AXES+selectedHead+2) = o.o
|
||||||
|
* so if selectedHead=1 move buffer ends up looking like this for a 5 extruder drive setup:
|
||||||
|
* {x.x, y.y, z.z, n.n, m.m, o.o, 0.0,0.0, f.f}
|
||||||
|
* where x,y,z are the axes and f is the feedrate.
|
||||||
|
* If selected head > 0 then there is the possibility that more drives can be set than
|
||||||
|
* exist, in that case the last values are discarded e.g:
|
||||||
|
* "T3"
|
||||||
|
* "M160 S3"
|
||||||
|
* "G1 En.n:m.m:o.o"
|
||||||
|
* would leave the move buffer on a 4 extruder drive setup looking like this:
|
||||||
|
* {x.x, y.y, z.z, 0.0, 0.0, 0.0, n.n,m.m, f.f}
|
||||||
|
*/
|
||||||
|
if(gb->Seen('E')&& ((i-AXES) == selectedHead-1))
|
||||||
{
|
{
|
||||||
// Doing an extruder. We need to store the relative distance for this move in moveBuffer and the resulting new position in lastPos.
|
//the number of mixing drives set (by M160)
|
||||||
float moveArg = gb->GetFValue() * distanceScale * extrusionFactor;
|
int numDrives = platform->GetMixingDrives();
|
||||||
if (doingG92)
|
const char* extruderString = gb->GetString();
|
||||||
|
float eArg[numDrives];
|
||||||
|
uint8_t sp = 0; //string pointer
|
||||||
|
uint8_t fp = 0; //float pointer for the start of each floating point number in turn
|
||||||
|
uint8_t hp = 0; //index of the head currently referred to for eArg
|
||||||
|
while(extruderString[sp])
|
||||||
{
|
{
|
||||||
moveBuffer[i] = 0.0; // no move required
|
//first check to confirm we have not got to the feedrate setting part of the string
|
||||||
lastPos[i - AXES] = moveArg; // set new absolute position
|
if(extruderString[sp] == 'F')
|
||||||
|
{
|
||||||
|
break;
|
||||||
}
|
}
|
||||||
else if (drivesRelative)
|
if(extruderString[sp] == ':')
|
||||||
{
|
{
|
||||||
moveBuffer[i] = moveArg;
|
eArg[hp] = (atoff(&extruderString[fp]))*distanceScale;
|
||||||
lastPos[i - AXES] += moveArg;
|
hp++;
|
||||||
|
if(hp >= numDrives)
|
||||||
|
{
|
||||||
|
platform->Message(HOST_MESSAGE, "More mixing extruder drives required in G1 string than set with M160: ");
|
||||||
|
platform->Message(HOST_MESSAGE, gb->Buffer());
|
||||||
|
platform->Message(HOST_MESSAGE, "\n");
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
sp++;
|
||||||
|
fp = sp;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
moveBuffer[i] = moveArg - lastPos[i - AXES];
|
sp++;
|
||||||
lastPos[i - AXES] = moveArg;
|
}
|
||||||
|
}
|
||||||
|
//capture the last drive step amount in the string (or the only one in the case of only one extruder)
|
||||||
|
eArg[hp] = (atoff(&extruderString[fp]))*distanceScale;
|
||||||
|
|
||||||
|
//set the move buffer for each extruder drive
|
||||||
|
for(int j=0;j<numDrives;j++)
|
||||||
|
{
|
||||||
|
float moveArg = eArg[j];
|
||||||
|
if(doingG92)
|
||||||
|
{
|
||||||
|
moveBuffer[i+j] = 0.0; // no move required
|
||||||
|
lastPos[i+j - AXES] = moveArg; // set absolute position
|
||||||
|
}
|
||||||
|
else if (drivesRelative)
|
||||||
|
{
|
||||||
|
moveBuffer[i+j] = moveArg;
|
||||||
|
lastPos[i+j - AXES] += moveArg;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
moveBuffer[i+j] = moveArg - lastPos[i+j - AXES];
|
||||||
|
lastPos[i+j - AXES] = moveArg;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -396,7 +456,7 @@ void GCodes::LoadMoveBufferFromGCode(GCodeBuffer *gb, bool doingG92, bool applyL
|
||||||
|
|
||||||
// Deal with feed rate
|
// Deal with feed rate
|
||||||
|
|
||||||
if (gb->Seen(gCodeLetters[DRIVES]))
|
if(gb->Seen(FEEDRATE_LETTER))
|
||||||
{
|
{
|
||||||
gFeedRate = gb->GetFValue() * distanceScale * speedFactor;
|
gFeedRate = gb->GetFValue() * distanceScale * speedFactor;
|
||||||
}
|
}
|
||||||
|
@ -415,10 +475,11 @@ int GCodes::SetUpMove(GCodeBuffer *gb)
|
||||||
if (moveAvailable)
|
if (moveAvailable)
|
||||||
return 0;
|
return 0;
|
||||||
|
|
||||||
// Load the last position; if Move can't accept more, return 0
|
// Load the last position into moveBuffer; If Move can't accept more, return false
|
||||||
if (!reprap.GetMove()->GetCurrentState(moveBuffer))
|
if (!reprap.GetMove()->GetCurrentState(moveBuffer))
|
||||||
return 0;
|
return 0;
|
||||||
|
|
||||||
|
//check to see if the move is a 'homing' move that endstops are checked on.
|
||||||
checkEndStops = false;
|
checkEndStops = false;
|
||||||
if (gb->Seen('S'))
|
if (gb->Seen('S'))
|
||||||
{
|
{
|
||||||
|
@ -427,8 +488,10 @@ int GCodes::SetUpMove(GCodeBuffer *gb)
|
||||||
checkEndStops = true;
|
checkEndStops = true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
//loads the movebuffer with either the absolute movement required or the
|
||||||
|
//relative movement required
|
||||||
LoadMoveBufferFromGCode(gb, false, !checkEndStops && limitAxes);
|
LoadMoveBufferFromGCode(gb, false, !checkEndStops && limitAxes);
|
||||||
|
//There is a new move in the move buffer
|
||||||
moveAvailable = true;
|
moveAvailable = true;
|
||||||
return (checkEndStops) ? 2 : 1;
|
return (checkEndStops) ? 2 : 1;
|
||||||
}
|
}
|
||||||
|
@ -499,7 +562,7 @@ bool GCodes::DoFileCannedCycles(const char* fileName)
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
doFilePrint(cannedCycleGCode);
|
DoFilePrint(cannedCycleGCode);
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -601,7 +664,7 @@ bool GCodes::OffsetAxes(GCodeBuffer* gb)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if (gb->Seen(gCodeLetters[DRIVES])) // Has the user specified a feedrate?
|
if(gb->Seen(FEEDRATE_LETTER)) // Has the user specified a feedrate?
|
||||||
{
|
{
|
||||||
moveToDo[DRIVES] = gb->GetFValue();
|
moveToDo[DRIVES] = gb->GetFValue();
|
||||||
activeDrive[DRIVES] = true;
|
activeDrive[DRIVES] = true;
|
||||||
|
@ -628,7 +691,7 @@ bool GCodes::OffsetAxes(GCodeBuffer* gb)
|
||||||
// booleans homeX, homeY and homeZ.
|
// booleans homeX, homeY and homeZ.
|
||||||
// Returns true if completed, false if needs to be called again.
|
// Returns true if completed, false if needs to be called again.
|
||||||
// 'reply' is only written if there is an error.
|
// 'reply' is only written if there is an error.
|
||||||
// 'error' is false on entry, gets changed to true iff there is an error.
|
// 'error' is false on entry, gets changed to true if there is an error.
|
||||||
bool GCodes::DoHome(char* reply, bool& error)
|
bool GCodes::DoHome(char* reply, bool& error)
|
||||||
//pre(reply.upb == STRING_LENGTH)
|
//pre(reply.upb == STRING_LENGTH)
|
||||||
{
|
{
|
||||||
|
@ -961,15 +1024,18 @@ bool GCodes::SetPrintZProbe(GCodeBuffer* gb, char* reply)
|
||||||
// are updated at the end of each movement, so this won't tell you
|
// are updated at the end of each movement, so this won't tell you
|
||||||
// where you are mid-movement.
|
// where you are mid-movement.
|
||||||
|
|
||||||
// FIXME - needs to deal with multiple extruders
|
//Fixed to deal with multiple extruders
|
||||||
|
|
||||||
char* GCodes::GetCurrentCoordinates()
|
char* GCodes::GetCurrentCoordinates()
|
||||||
{
|
{
|
||||||
float liveCoordinates[DRIVES + 1];
|
float liveCoordinates[DRIVES + 1];
|
||||||
reprap.GetMove()->LiveCoordinates(liveCoordinates);
|
reprap.GetMove()->LiveCoordinates(liveCoordinates);
|
||||||
|
|
||||||
snprintf(scratchString, STRING_LENGTH, "X:%f Y:%f Z:%f E:%f", liveCoordinates[X_AXIS], liveCoordinates[Y_AXIS],
|
snprintf(scratchString, STRING_LENGTH, "X:%f Y:%f Z:%f ", liveCoordinates[X_AXIS], liveCoordinates[Y_AXIS], liveCoordinates[Z_AXIS]);
|
||||||
liveCoordinates[Z_AXIS], liveCoordinates[AXES]);
|
for(int i = AXES; i< DRIVES; i++)
|
||||||
|
{
|
||||||
|
sncatf(scratchString, STRING_LENGTH, "E%d:%f ",i-AXES,liveCoordinates[i]);
|
||||||
|
}
|
||||||
return scratchString;
|
return scratchString;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -979,6 +1045,7 @@ bool GCodes::OpenFileToWrite(const char* directory, const char* fileName, GCodeB
|
||||||
eofStringCounter = 0;
|
eofStringCounter = 0;
|
||||||
if (fileBeingWritten == NULL)
|
if (fileBeingWritten == NULL)
|
||||||
{
|
{
|
||||||
|
platform->Message(HOST_MESSAGE, "Can't open GCode file for writing.\n");
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
|
@ -1173,7 +1240,7 @@ bool GCodes::SetOffsets(GCodeBuffer *gb)
|
||||||
int8_t head;
|
int8_t head;
|
||||||
if (gb->Seen('P'))
|
if (gb->Seen('P'))
|
||||||
{
|
{
|
||||||
head = gb->GetIValue() + 1; // 0 is the Bed
|
head = gb->GetIValue(); // 0 is the Bed
|
||||||
if (gb->Seen('R'))
|
if (gb->Seen('R'))
|
||||||
reprap.GetHeat()->SetStandbyTemperature(head, gb->GetFValue());
|
reprap.GetHeat()->SetStandbyTemperature(head, gb->GetFValue());
|
||||||
|
|
||||||
|
@ -1203,7 +1270,7 @@ bool GCodes::StandbyHeaters()
|
||||||
return false;
|
return false;
|
||||||
for (int8_t heater = 0; heater < HEATERS; heater++)
|
for (int8_t heater = 0; heater < HEATERS; heater++)
|
||||||
reprap.GetHeat()->Standby(heater);
|
reprap.GetHeat()->Standby(heater);
|
||||||
selectedHead = -1;
|
selectedHead = -1; //FIXME check this does not mess up setters (eg M906) when they are used after this command is called
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1260,6 +1327,44 @@ void GCodes::SetEthernetAddress(GCodeBuffer *gb, int mCode)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
void GCodes::SetMACAddress(GCodeBuffer *gb)
|
||||||
|
{
|
||||||
|
uint8_t mac[6];
|
||||||
|
const char* ipString = gb->GetString();
|
||||||
|
uint8_t sp = 0;
|
||||||
|
uint8_t spp = 0;
|
||||||
|
uint8_t ipp = 0;
|
||||||
|
while(ipString[sp])
|
||||||
|
{
|
||||||
|
if(ipString[sp] == ':')
|
||||||
|
{
|
||||||
|
mac[ipp] = strtol(&ipString[spp], NULL, 0);
|
||||||
|
ipp++;
|
||||||
|
if(ipp > 5)
|
||||||
|
{
|
||||||
|
platform->Message(HOST_MESSAGE, "Dud MAC address: ");
|
||||||
|
platform->Message(HOST_MESSAGE, gb->Buffer());
|
||||||
|
platform->Message(HOST_MESSAGE, "\n");
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
sp++;
|
||||||
|
spp = sp;
|
||||||
|
}else
|
||||||
|
sp++;
|
||||||
|
}
|
||||||
|
mac[ipp] = strtol(&ipString[spp], NULL, 0);
|
||||||
|
if(ipp == 5)
|
||||||
|
{
|
||||||
|
platform->SetMACAddress(mac);
|
||||||
|
} else
|
||||||
|
{
|
||||||
|
platform->Message(HOST_MESSAGE, "Dud MAC address: ");
|
||||||
|
platform->Message(HOST_MESSAGE, gb->Buffer());
|
||||||
|
platform->Message(HOST_MESSAGE, "\n");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
void GCodes::HandleReply(bool error, bool fromLine, const char* reply, char gMOrT, int code, bool resend)
|
void GCodes::HandleReply(bool error, bool fromLine, const char* reply, char gMOrT, int code, bool resend)
|
||||||
{
|
{
|
||||||
if (gMOrT != 'M' || code != 111) // web server reply for M111 is handled before we get here
|
if (gMOrT != 'M' || code != 111) // web server reply for M111 is handled before we get here
|
||||||
|
@ -1418,7 +1523,6 @@ void GCodes::SetHeaterParameters(GCodeBuffer *gb, char reply[STRING_LENGTH])
|
||||||
{
|
{
|
||||||
r25 = pp.GetThermistorR25();
|
r25 = pp.GetThermistorR25();
|
||||||
}
|
}
|
||||||
|
|
||||||
if (gb->Seen('B'))
|
if (gb->Seen('B'))
|
||||||
{
|
{
|
||||||
beta = gb->GetFValue();
|
beta = gb->GetFValue();
|
||||||
|
@ -1727,18 +1831,38 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
||||||
bool seen = false;
|
bool seen = false;
|
||||||
for (int8_t drive = 0; drive < DRIVES; drive++)
|
for (int8_t drive = 0; drive < DRIVES; drive++)
|
||||||
{
|
{
|
||||||
if (gb->Seen(gCodeLetters[drive]))
|
//Do AXES first
|
||||||
|
if(gb->Seen(gCodeLetters[drive])&& drive<AXES)
|
||||||
{
|
{
|
||||||
platform->SetDriveStepsPerUnit(drive, gb->GetFValue());
|
platform->SetDriveStepsPerUnit(drive, gb->GetFValue());
|
||||||
seen = true;
|
seen = true;
|
||||||
}
|
}
|
||||||
|
else if(selectedHead < 0)
|
||||||
|
{
|
||||||
|
// If no head selected, set the first extruder steps - best we can do
|
||||||
|
if(gb->Seen('E'))
|
||||||
|
{
|
||||||
|
platform->SetDriveStepsPerUnit(AXES, gb->GetFValue());
|
||||||
|
seen=true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else if(gb->Seen('E')&& ((drive-AXES) == selectedHead - 1))//then do active extruder
|
||||||
|
{
|
||||||
|
platform->SetDriveStepsPerUnit(AXES+selectedHead - 1, gb->GetFValue());
|
||||||
|
seen=true;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
reprap.GetMove()->SetStepHypotenuse();
|
reprap.GetMove()->SetStepHypotenuse();
|
||||||
if (!seen)
|
if (!seen)
|
||||||
{
|
{
|
||||||
snprintf(reply, STRING_LENGTH, "Steps/mm: X:%f, Y:%f, Z:%f, E:%f",
|
snprintf(reply, STRING_LENGTH, "Steps/mm: X: %f, Y: %f, Z: %f, E: ",
|
||||||
platform->DriveStepsPerUnit(X_AXIS), platform->DriveStepsPerUnit(Y_AXIS),
|
platform->DriveStepsPerUnit(X_AXIS), platform->DriveStepsPerUnit(Y_AXIS),
|
||||||
platform->DriveStepsPerUnit(Z_AXIS), platform->DriveStepsPerUnit(AXES)); // FIXME - needs to do multiple extruders
|
platform->DriveStepsPerUnit(Z_AXIS));
|
||||||
|
// Fixed to do multiple extruders.
|
||||||
|
for(int8_t drive = AXES; drive < DRIVES; drive++)
|
||||||
|
{
|
||||||
|
sncatf(reply, STRING_LENGTH, "%.2f:", platform->DriveStepsPerUnit(drive));
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
@ -1755,16 +1879,18 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 104: // Deprecated
|
case 104: // Deprecated
|
||||||
if (gb->Seen('S'))
|
if(gb->Seen('S') && selectedHead >= 0)
|
||||||
{
|
{
|
||||||
reprap.GetHeat()->SetActiveTemperature(1, gb->GetFValue()); // 0 is the bed
|
//only sets the selected head (As set by T#)
|
||||||
reprap.GetHeat()->Activate(1);
|
reprap.GetHeat()->SetActiveTemperature(selectedHead, gb->GetFValue()); // 0 is the bed
|
||||||
|
reprap.GetHeat()->Activate(selectedHead);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 105: // Deprecated...
|
case 105: // Deprecated...
|
||||||
strncpy(reply, "T:", STRING_LENGTH);
|
strncpy(reply, "T:", STRING_LENGTH);
|
||||||
for (int8_t heater = HEATERS - 1; heater > 0; heater--)
|
//FIXME - why did this decrement rather than increment through the heaters (odd behaviour)
|
||||||
|
for(int8_t heater = 1; heater < HEATERS; heater++)
|
||||||
{
|
{
|
||||||
sncatf(reply, STRING_LENGTH, "%.1f ", reprap.GetHeat()->GetTemperature(heater));
|
sncatf(reply, STRING_LENGTH, "%.1f ", reprap.GetHeat()->GetTemperature(heater));
|
||||||
}
|
}
|
||||||
|
@ -1797,20 +1923,13 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 109: // Set extruder temperature and wait - deprecated
|
case 109: // Set extruder temperature and wait - deprecated
|
||||||
case 190: // Set bed temperature and wait - deprecated
|
if(gb->Seen('S') && selectedHead >= 0)
|
||||||
{
|
{
|
||||||
int8_t heater = (code == 190) ? 0 : 1;
|
reprap.GetHeat()->SetActiveTemperature(selectedHead, gb->GetFValue()); // 0 is the bed
|
||||||
if (gb->Seen('S'))
|
reprap.GetHeat()->Activate(selectedHead);
|
||||||
{
|
|
||||||
reprap.GetHeat()->SetActiveTemperature(heater, gb->GetFValue());
|
|
||||||
reprap.GetHeat()->Activate(heater);
|
|
||||||
}
|
|
||||||
if (!AllMovesAreFinishedAndMoveBufferIsLoaded())
|
|
||||||
{
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
result = reprap.GetHeat()->HeaterAtSetTemperature(heater);
|
|
||||||
}
|
}
|
||||||
|
//check here rather than falling through to M116, we want to just wait for the extruder we specified (otherwise use M116 not M109)
|
||||||
|
result = reprap.GetHeat()->HeaterAtSetTemperature(selectedHead);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 110: // Set line numbers - line numbers are dealt with in the GCodeBuffer class
|
case 110: // Set line numbers - line numbers are dealt with in the GCodeBuffer class
|
||||||
|
@ -1818,7 +1937,9 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
||||||
|
|
||||||
case 111: // Debug level
|
case 111: // Debug level
|
||||||
if (gb->Seen('S'))
|
if (gb->Seen('S'))
|
||||||
|
{
|
||||||
reprap.SetDebug(gb->GetIValue());
|
reprap.SetDebug(gb->GetIValue());
|
||||||
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 112: // Emergency stop - acted upon in Webserver, but also here in case it comes from USB etc.
|
case 112: // Emergency stop - acted upon in Webserver, but also here in case it comes from USB etc.
|
||||||
|
@ -1852,7 +1973,10 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
||||||
result = reprap.GetHeat()->AllHeatersAtSetTemperatures();
|
result = reprap.GetHeat()->AllHeatersAtSetTemperatures();
|
||||||
break;
|
break;
|
||||||
|
|
||||||
// case 117 is handled later because it falls through to the default case
|
//TODO M119
|
||||||
|
case 119:
|
||||||
|
platform->Message(HOST_MESSAGE, "M119 - endstop status not yet implemented\n");
|
||||||
|
break;
|
||||||
|
|
||||||
case 120:
|
case 120:
|
||||||
result = Push();
|
result = Push();
|
||||||
|
@ -1889,15 +2013,47 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
||||||
platform->Message(HOST_MESSAGE, "M141 - heated chamber not yet implemented\n");
|
platform->Message(HOST_MESSAGE, "M141 - heated chamber not yet implemented\n");
|
||||||
break;
|
break;
|
||||||
|
|
||||||
// case 190 is with case 109 because it used the same code
|
case 160: //number of mixing filament drives
|
||||||
|
if(gb->Seen('S'))
|
||||||
|
{
|
||||||
|
int iValue=gb->GetIValue();
|
||||||
|
platform->SetMixingDrives(iValue);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
|
case 190: // Deprecated...
|
||||||
|
if(gb->Seen('S'))
|
||||||
|
{
|
||||||
|
float value=gb->GetFValue();
|
||||||
|
reprap.GetHeat()->SetActiveTemperature(0, value);
|
||||||
|
reprap.GetHeat()->SetStandbyTemperature(0, value); // FIXME have to set both?not sure as the bed should always be selected
|
||||||
|
reprap.GetHeat()->Activate(0);
|
||||||
|
}
|
||||||
|
result = reprap.GetHeat()->HeaterAtSetTemperature(0);
|
||||||
|
break;
|
||||||
|
|
||||||
case 201: // Set axis accelerations
|
case 201: // Set axis accelerations
|
||||||
for (int8_t drive = 0; drive < DRIVES; drive++)
|
for (int8_t drive = 0; drive < DRIVES; drive++)
|
||||||
{
|
{
|
||||||
if (gb->Seen(gCodeLetters[drive]))
|
//Do AXES first
|
||||||
|
if(gb->Seen(gCodeLetters[drive]) && drive<AXES)
|
||||||
{
|
{
|
||||||
float value = gb->GetFValue();
|
platform->SetAcceleration(drive, gb->GetFValue());
|
||||||
platform->SetAcceleration(drive, value);
|
}
|
||||||
|
else if(selectedHead < 0)
|
||||||
|
{
|
||||||
|
if(gb->Seen('E')) // Do first one - best we can do
|
||||||
|
{
|
||||||
|
platform->SetAcceleration(AXES, gb->GetFValue());
|
||||||
|
}
|
||||||
|
}//then do active extruder
|
||||||
|
else if(gb->Seen('E') && ((drive-AXES) == selectedHead-1))
|
||||||
|
{
|
||||||
|
platform->SetAcceleration(AXES+selectedHead-1, gb->GetFValue()); //Set the E acceleration for the currently selected tool
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
platform->SetAcceleration(drive, -1);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
@ -1905,11 +2061,25 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
||||||
case 203: // Set maximum feed rates
|
case 203: // Set maximum feed rates
|
||||||
for (int8_t drive = 0; drive < DRIVES; drive++)
|
for (int8_t drive = 0; drive < DRIVES; drive++)
|
||||||
{
|
{
|
||||||
if (gb->Seen(gCodeLetters[drive]))
|
//Do AXES first
|
||||||
|
if(gb->Seen(gCodeLetters[drive]) && drive<AXES)
|
||||||
{
|
{
|
||||||
float value = gb->GetFValue() * distanceScale * 0.016666667; // G Code feedrates are in mm/minute; we need mm/sec;
|
float value = gb->GetFValue() * distanceScale * 0.016666667; // G Code feedrates are in mm/minute; we need mm/sec;
|
||||||
platform->SetMaxFeedrate(drive, value);
|
platform->SetMaxFeedrate(drive, value);
|
||||||
}
|
}
|
||||||
|
else if(selectedHead < 0)
|
||||||
|
{
|
||||||
|
if(gb->Seen('E'))
|
||||||
|
{
|
||||||
|
float value = gb->GetFValue()*distanceScale*0.016666667; // G Code feedrates are in mm/minute; we need mm/sec;
|
||||||
|
platform->SetMaxFeedrate(AXES, value); //Set the E Steps for the first E - best we can do
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else if(gb->Seen('E') && ((drive-AXES) == selectedHead-1))//then do active extruder
|
||||||
|
{
|
||||||
|
float value = gb->GetFValue()*distanceScale*0.016666667; // G Code feedrates are in mm/minute; we need mm/sec;
|
||||||
|
platform->SetMaxFeedrate(AXES+selectedHead-1, value); //Set the E Steps for the currently selected tool
|
||||||
|
}
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
@ -2005,6 +2175,13 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
||||||
result = SendConfigToLine();
|
result = SendConfigToLine();
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case 540:
|
||||||
|
if(gb->Seen('P'))
|
||||||
|
{
|
||||||
|
SetMACAddress(gb);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
case 550: // Set machine name
|
case 550: // Set machine name
|
||||||
if (gb->Seen('P'))
|
if (gb->Seen('P'))
|
||||||
reprap.GetWebserver()->SetName(gb->GetString());
|
reprap.GetWebserver()->SetName(gb->GetString());
|
||||||
|
@ -2012,12 +2189,16 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
||||||
|
|
||||||
case 551: // Set password
|
case 551: // Set password
|
||||||
if (gb->Seen('P'))
|
if (gb->Seen('P'))
|
||||||
|
{
|
||||||
reprap.GetWebserver()->SetPassword(gb->GetString());
|
reprap.GetWebserver()->SetPassword(gb->GetString());
|
||||||
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 552: // Set/Get IP address
|
case 552: // Set/Get IP address
|
||||||
if (gb->Seen('P'))
|
if (gb->Seen('P'))
|
||||||
|
{
|
||||||
SetEthernetAddress(gb, code);
|
SetEthernetAddress(gb, code);
|
||||||
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
const byte *ip = platform->IPAddress();
|
const byte *ip = platform->IPAddress();
|
||||||
|
@ -2027,7 +2208,9 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
||||||
|
|
||||||
case 553: // Set/Get netmask
|
case 553: // Set/Get netmask
|
||||||
if (gb->Seen('P'))
|
if (gb->Seen('P'))
|
||||||
|
{
|
||||||
SetEthernetAddress(gb, code);
|
SetEthernetAddress(gb, code);
|
||||||
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
const byte *nm = platform->NetMask();
|
const byte *nm = platform->NetMask();
|
||||||
|
@ -2037,7 +2220,9 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
||||||
|
|
||||||
case 554: // Set/Get gateway
|
case 554: // Set/Get gateway
|
||||||
if (gb->Seen('P'))
|
if (gb->Seen('P'))
|
||||||
|
{
|
||||||
SetEthernetAddress(gb, code);
|
SetEthernetAddress(gb, code);
|
||||||
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
const byte *gw = platform->GateWay();
|
const byte *gw = platform->GateWay();
|
||||||
|
@ -2047,7 +2232,9 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
||||||
|
|
||||||
case 555: // Set firmware type to emulate
|
case 555: // Set firmware type to emulate
|
||||||
if (gb->Seen('P'))
|
if (gb->Seen('P'))
|
||||||
|
{
|
||||||
platform->SetEmulating((Compatibility) gb->GetIValue());
|
platform->SetEmulating((Compatibility) gb->GetIValue());
|
||||||
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 556: // Axis compensation
|
case 556: // Axis compensation
|
||||||
|
@ -2055,9 +2242,13 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
||||||
{
|
{
|
||||||
float value = gb->GetFValue();
|
float value = gb->GetFValue();
|
||||||
for (int8_t axis = 0; axis < AXES; axis++)
|
for (int8_t axis = 0; axis < AXES; axis++)
|
||||||
|
{
|
||||||
if (gb->Seen(gCodeLetters[axis]))
|
if (gb->Seen(gCodeLetters[axis]))
|
||||||
|
{
|
||||||
reprap.GetMove()->SetAxisCompensation(axis, gb->GetFValue() / value);
|
reprap.GetMove()->SetAxisCompensation(axis, gb->GetFValue() / value);
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 557: // Set Z probe point coordinates
|
case 557: // Set Z probe point coordinates
|
||||||
|
@ -2142,6 +2333,10 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case 563: // Define tool
|
||||||
|
|
||||||
|
break;
|
||||||
|
|
||||||
case 564: // Think outside the box?
|
case 564: // Think outside the box?
|
||||||
if(gb->Seen('S'))
|
if(gb->Seen('S'))
|
||||||
{
|
{
|
||||||
|
@ -2152,11 +2347,28 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
||||||
case 906: // Set Motor currents
|
case 906: // Set Motor currents
|
||||||
for (uint8_t i = 0; i < DRIVES; i++)
|
for (uint8_t i = 0; i < DRIVES; i++)
|
||||||
{
|
{
|
||||||
if (gb->Seen(gCodeLetters[i]))
|
//Do AXES first
|
||||||
|
if(gb->Seen(gCodeLetters[i])&& i<AXES)
|
||||||
{
|
{
|
||||||
float value = gb->GetFValue(); // mA
|
float value = gb->GetFValue(); // mA
|
||||||
platform->SetMotorCurrent(i, value);
|
platform->SetMotorCurrent(i, value);
|
||||||
}
|
}
|
||||||
|
else if(selectedHead < 0)
|
||||||
|
{
|
||||||
|
if(gb->Seen('E'))
|
||||||
|
{
|
||||||
|
float value = gb->GetFValue(); // mA
|
||||||
|
platform->SetMotorCurrent(AXES, value); // Set first one - best we can do
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else //do for selected extruder
|
||||||
|
{
|
||||||
|
if(gb->Seen(gCodeLetters[i]))
|
||||||
|
{
|
||||||
|
float value = gb->GetFValue(); // mA
|
||||||
|
platform->SetMotorCurrent(AXES+selectedHead-1, value);
|
||||||
|
}
|
||||||
|
}
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
@ -2195,41 +2407,43 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
||||||
|
|
||||||
bool GCodes::HandleTcode(GCodeBuffer* gb)
|
bool GCodes::HandleTcode(GCodeBuffer* gb)
|
||||||
{
|
{
|
||||||
bool error = false;
|
|
||||||
char reply[STRING_LENGTH];
|
char reply[STRING_LENGTH];
|
||||||
reply[0] = 0;
|
reply[0] = 0;
|
||||||
|
|
||||||
int code = gb->GetIValue();
|
int code = gb->GetIValue();
|
||||||
if (code == selectedHead)
|
if (code == selectedHead)
|
||||||
{
|
{
|
||||||
HandleReply(error, gb == serialGCode, reply, 'T', code, false);
|
HandleReply(false, gb == serialGCode, reply, 'T', code, false);
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
error = true;
|
|
||||||
for (int8_t i = AXES; i < DRIVES; i++)
|
for (int8_t i = AXES; i < DRIVES; i++)
|
||||||
{
|
{
|
||||||
if (selectedHead == i - AXES)
|
if(selectedHead == i - AXES + 1)
|
||||||
{
|
{
|
||||||
reprap.GetHeat()->Standby(selectedHead + 1); // + 1 because 0 is the Bed
|
reprap.GetHeat()->Standby(selectedHead);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool toolNotFound = true;
|
||||||
for (int8_t i = AXES; i < DRIVES; i++)
|
for (int8_t i = AXES; i < DRIVES; i++)
|
||||||
{
|
{
|
||||||
if (code == i - AXES)
|
if(code == i - AXES + 1)
|
||||||
{
|
{
|
||||||
selectedHead = code;
|
selectedHead = code;
|
||||||
reprap.GetHeat()->Activate(selectedHead + 1); // 0 is the Bed
|
reprap.GetHeat()->Activate(selectedHead);
|
||||||
error = false;
|
toolNotFound = false;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if (error)
|
if(toolNotFound)
|
||||||
{
|
{
|
||||||
snprintf(reply, STRING_LENGTH, "Invalid T Code: %s", gb->Buffer());
|
selectedHead = -1;
|
||||||
}
|
}
|
||||||
|
|
||||||
HandleReply(error, gb == serialGCode, reply, 'T', code, false);
|
// snprintf(reply, STRING_LENGTH, "Invalid T Code: %s", gb->Buffer());
|
||||||
|
|
||||||
|
HandleReply(false, gb == serialGCode, reply, 'T', code, false);
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -2387,6 +2601,7 @@ float GCodeBuffer::GetFValue()
|
||||||
if (readPointer < 0)
|
if (readPointer < 0)
|
||||||
{
|
{
|
||||||
platform->Message(HOST_MESSAGE, "GCodes: Attempt to read a GCode float before a search.\n");
|
platform->Message(HOST_MESSAGE, "GCodes: Attempt to read a GCode float before a search.\n");
|
||||||
|
readPointer = -1;
|
||||||
return 0.0;
|
return 0.0;
|
||||||
}
|
}
|
||||||
float result = (float) strtod(&gcodeBuffer[readPointer + 1], 0);
|
float result = (float) strtod(&gcodeBuffer[readPointer + 1], 0);
|
||||||
|
@ -2394,6 +2609,66 @@ float GCodeBuffer::GetFValue()
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Get a :-separated list of floats after a key letter
|
||||||
|
|
||||||
|
const void GCodeBuffer::GetFloatArray(float a[], int& length)
|
||||||
|
{
|
||||||
|
length = 0;
|
||||||
|
if(readPointer < 0)
|
||||||
|
{
|
||||||
|
platform->Message(HOST_MESSAGE, "GCodes: Attempt to read a GCode float array before a search.\n");
|
||||||
|
readPointer = -1;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool inList = true;
|
||||||
|
while(inList)
|
||||||
|
{
|
||||||
|
a[length] = (float)strtod(&gcodeBuffer[readPointer + 1], 0);
|
||||||
|
length++;
|
||||||
|
readPointer++;
|
||||||
|
while(gcodeBuffer[readPointer] && (gcodeBuffer[readPointer] != ' ') && (gcodeBuffer[readPointer] != LIST_SEPARATOR))
|
||||||
|
{
|
||||||
|
readPointer++;
|
||||||
|
}
|
||||||
|
if(gcodeBuffer[readPointer] != LIST_SEPARATOR)
|
||||||
|
{
|
||||||
|
inList = false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
readPointer = -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Get a :-separated list of longs after a key letter
|
||||||
|
|
||||||
|
const void GCodeBuffer::GetLongArray(long l[], int& length)
|
||||||
|
{
|
||||||
|
length = 0;
|
||||||
|
if(readPointer < 0)
|
||||||
|
{
|
||||||
|
platform->Message(HOST_MESSAGE, "GCodes: Attempt to read a GCode long array before a search.\n");
|
||||||
|
readPointer = -1;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool inList = true;
|
||||||
|
while(inList)
|
||||||
|
{
|
||||||
|
l[length] = strtol(&gcodeBuffer[readPointer + 1], 0, 0);
|
||||||
|
length++;
|
||||||
|
readPointer++;
|
||||||
|
while(gcodeBuffer[readPointer] && (gcodeBuffer[readPointer] != ' ') && (gcodeBuffer[readPointer] != LIST_SEPARATOR))
|
||||||
|
{
|
||||||
|
readPointer++;
|
||||||
|
}
|
||||||
|
if(gcodeBuffer[readPointer] != LIST_SEPARATOR)
|
||||||
|
{
|
||||||
|
inList = false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
readPointer = -1;
|
||||||
|
}
|
||||||
|
|
||||||
// Get a string after a G Code letter found by a call to Seen().
|
// Get a string after a G Code letter found by a call to Seen().
|
||||||
// It will be the whole of the rest of the GCode string, so strings
|
// It will be the whole of the rest of the GCode string, so strings
|
||||||
// should always be the last parameter.
|
// should always be the last parameter.
|
||||||
|
@ -2403,6 +2678,7 @@ const char* GCodeBuffer::GetString()
|
||||||
if (readPointer < 0)
|
if (readPointer < 0)
|
||||||
{
|
{
|
||||||
platform->Message(HOST_MESSAGE, "GCodes: Attempt to read a GCode string before a search.\n");
|
platform->Message(HOST_MESSAGE, "GCodes: Attempt to read a GCode string before a search.\n");
|
||||||
|
readPointer = -1;
|
||||||
return "";
|
return "";
|
||||||
}
|
}
|
||||||
const char* result = &gcodeBuffer[readPointer + 1];
|
const char* result = &gcodeBuffer[readPointer + 1];
|
||||||
|
@ -2425,11 +2701,14 @@ const char* GCodeBuffer::GetUnprecedentedString()
|
||||||
{
|
{
|
||||||
readPointer = 0;
|
readPointer = 0;
|
||||||
while (gcodeBuffer[readPointer] && gcodeBuffer[readPointer] != ' ')
|
while (gcodeBuffer[readPointer] && gcodeBuffer[readPointer] != ' ')
|
||||||
|
{
|
||||||
readPointer++;
|
readPointer++;
|
||||||
|
}
|
||||||
|
|
||||||
if (!gcodeBuffer[readPointer])
|
if (!gcodeBuffer[readPointer])
|
||||||
{
|
{
|
||||||
platform->Message(HOST_MESSAGE, "GCodes: String expected but not seen.\n");
|
platform->Message(HOST_MESSAGE, "GCodes: String expected but not seen.\n");
|
||||||
|
readPointer = -1;
|
||||||
return gcodeBuffer; // Good idea?
|
return gcodeBuffer; // Good idea?
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -2445,6 +2724,7 @@ long GCodeBuffer::GetLValue()
|
||||||
if (readPointer < 0)
|
if (readPointer < 0)
|
||||||
{
|
{
|
||||||
platform->Message(HOST_MESSAGE, "GCodes: Attempt to read a GCode int before a search.\n");
|
platform->Message(HOST_MESSAGE, "GCodes: Attempt to read a GCode int before a search.\n");
|
||||||
|
readPointer = -1;
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
long result = strtol(&gcodeBuffer[readPointer + 1], 0, 0);
|
long result = strtol(&gcodeBuffer[readPointer + 1], 0, 0);
|
||||||
|
|
223
GCodes.h
223
GCodes.h
|
@ -25,7 +25,8 @@ Licence: GPL
|
||||||
#define STACK 5
|
#define STACK 5
|
||||||
#define GCODE_LENGTH 100 // Maximum length of internally-generated G Code string
|
#define GCODE_LENGTH 100 // Maximum length of internally-generated G Code string
|
||||||
|
|
||||||
#define GCODE_LETTERS { 'X', 'Y', 'Z', 'E', 'F' } // The drives and feedrate in a GCode
|
#define GCODE_LETTERS { 'X', 'Y', 'Z', 'E', 'F' } // The drives and feedrate in a GCode //FIXME when working with multiple extruders GCODE_LETTERS[DRIVES] is out of scope
|
||||||
|
#define FEEDRATE_LETTER 'F'//FIX to work with multiple extruders without having to re-define GCODE_LETTERS array
|
||||||
|
|
||||||
// Small class to hold an individual GCode and provide functions to allow it to be parsed
|
// Small class to hold an individual GCode and provide functions to allow it to be parsed
|
||||||
|
|
||||||
|
@ -33,34 +34,36 @@ class GCodeBuffer
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
GCodeBuffer(Platform* p, const char* id);
|
GCodeBuffer(Platform* p, const char* id);
|
||||||
void Init();
|
void Init(); // Set it up
|
||||||
bool Put(char c);
|
bool Put(char c); // Add a character to the end
|
||||||
bool Seen(char c);
|
bool Seen(char c); // Is a character present?
|
||||||
float GetFValue();
|
float GetFValue(); // Get a float after a key letter
|
||||||
int GetIValue();
|
int GetIValue(); // Get an integer after a key letter
|
||||||
long GetLValue();
|
long GetLValue(); // Get a long integer after a key letter
|
||||||
const char* GetUnprecedentedString();
|
const char* GetUnprecedentedString(); // Get a string with no preceding key letter
|
||||||
const char* GetString();
|
const char* GetString(); // Get a string after a key letter
|
||||||
|
const void GetFloatArray(float a[], int& length); // Get a :-separated list of floats after a key letter
|
||||||
|
const void GetLongArray(long l[], int& length); // Get a :-separated list of longs after a key letter
|
||||||
const char* Buffer();
|
const char* Buffer();
|
||||||
bool Active() const;
|
bool Active() const;
|
||||||
void SetFinished(bool f);
|
void SetFinished(bool f); // Set the G Code executed (or not)
|
||||||
void Pause();
|
void Pause();
|
||||||
void CancelPause();
|
void CancelPause();
|
||||||
const char* WritingFileDirectory() const;
|
const char* WritingFileDirectory() const; // If we are writing the G Code to a file, where that file is
|
||||||
void SetWritingFileDirectory(const char* wfd);
|
void SetWritingFileDirectory(const char* wfd); // Set the directory for the file to write the GCode in
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
enum State { idle, executing, paused };
|
enum State { idle, executing, paused };
|
||||||
int CheckSum();
|
int CheckSum(); // Compute the checksum (if any) at the end of the G Code
|
||||||
Platform* platform;
|
Platform* platform; // Pointer to the RepRap's controlling class
|
||||||
char gcodeBuffer[GCODE_LENGTH];
|
char gcodeBuffer[GCODE_LENGTH]; // The G Code
|
||||||
const char* identity;
|
const char* identity; // Where we are from (web, file, serial line etc)
|
||||||
int gcodePointer;
|
int gcodePointer; // Index in the buffer
|
||||||
int readPointer;
|
int readPointer; // Where in the buffer to read next
|
||||||
bool inComment;
|
bool inComment; // Are we after a ';' character?
|
||||||
State state;
|
State state; // Idle, executing or paused
|
||||||
const char* writingFileDirectory;
|
const char* writingFileDirectory; // If the G Code is going into a file, where that is
|
||||||
};
|
};
|
||||||
|
|
||||||
//****************************************************************************************************
|
//****************************************************************************************************
|
||||||
|
@ -72,109 +75,114 @@ class GCodes
|
||||||
public:
|
public:
|
||||||
|
|
||||||
GCodes(Platform* p, Webserver* w);
|
GCodes(Platform* p, Webserver* w);
|
||||||
void Spin();
|
void Spin(); // Called in a tight loop to make this class work
|
||||||
void Init();
|
void Init(); // Set it up
|
||||||
void Exit();
|
void Exit(); // Shut it down
|
||||||
void Reset();
|
void Reset();
|
||||||
bool RunConfigurationGCodes();
|
bool RunConfigurationGCodes(); // Run the configuration G Code file on reboot
|
||||||
bool ReadMove(float* m, bool& ce);
|
bool ReadMove(float* m, bool& ce); // Called by the Move class to get a movement set by the last G Code
|
||||||
void QueueFileToPrint(const char* fileName);
|
void QueueFileToPrint(const char* fileName); // Open a file of G Codes to run
|
||||||
void DeleteFile(const char* fileName);
|
void DeleteFile(const char* fileName); // Does what it says
|
||||||
bool GetProbeCoordinates(int count, float& x, float& y, float& z);
|
bool GetProbeCoordinates(int count, float& x, float& y, float& z); // Get pre-recorded probe coordinates
|
||||||
char* GetCurrentCoordinates();
|
char* GetCurrentCoordinates(); // Get where we are as a string
|
||||||
bool PrintingAFile() const;
|
bool PrintingAFile() const; // Are we in the middle of printing a file?
|
||||||
void Diagnostics();
|
void Diagnostics(); // Send helpful information out
|
||||||
bool HaveIncomingData() const;
|
int8_t GetSelectedHead() const; // return which tool is selected
|
||||||
bool GetAxisIsHomed(uint8_t axis) const { return axisIsHomed[axis]; }
|
bool HaveIncomingData() const; // Is there something that we have to do?
|
||||||
|
bool GetAxisIsHomed(uint8_t axis) const { return axisIsHomed[axis]; } // Is the axis at 0?
|
||||||
void SetAxisIsHomed(uint8_t axis) { axisIsHomed[axis] = true; }
|
void SetAxisIsHomed(uint8_t axis) { axisIsHomed[axis] = true; }
|
||||||
float GetExtruderPosition(uint8_t extruder) const;
|
float GetExtruderPosition(uint8_t extruder) const;
|
||||||
void PauseSDPrint();
|
void PauseSDPrint();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
void doFilePrint(GCodeBuffer* gb);
|
void DoFilePrint(GCodeBuffer* gb); // Get G Codes from a file and print them
|
||||||
bool AllMovesAreFinishedAndMoveBufferIsLoaded();
|
bool AllMovesAreFinishedAndMoveBufferIsLoaded(); // Wait for move queue to exhaust and the current position is loaded
|
||||||
bool DoCannedCycleMove(bool ce);
|
bool DoCannedCycleMove(bool ce); // Do a move from an internally programmed canned cycle
|
||||||
bool DoFileCannedCycles(const char* fileName);
|
bool DoFileCannedCycles(const char* fileName); // Run a GCode macro in a file
|
||||||
bool FileCannedCyclesReturn();
|
bool FileCannedCyclesReturn(); // End a macro
|
||||||
bool ActOnGcode(GCodeBuffer* gb);
|
bool ActOnGcode(GCodeBuffer* gb); // Do the G Code
|
||||||
bool HandleGcode(GCodeBuffer* gb);
|
bool HandleGcode(GCodeBuffer* gb);
|
||||||
bool HandleMcode(GCodeBuffer* gb);
|
bool HandleMcode(GCodeBuffer* gb);
|
||||||
bool HandleTcode(GCodeBuffer* gb);
|
bool HandleTcode(GCodeBuffer* gb);
|
||||||
int SetUpMove(GCodeBuffer* gb);
|
int SetUpMove(GCodeBuffer* gb);
|
||||||
bool DoDwell(GCodeBuffer *gb);
|
bool DoDwell(GCodeBuffer *gb); // Wait for a bit
|
||||||
bool DoDwellTime(float dwell);
|
bool DoDwellTime(float dwell);
|
||||||
bool DoHome(char *reply, bool& error);
|
bool DoHome(char *reply, bool& error); // Home some axes
|
||||||
bool DoSingleZProbeAtPoint();
|
bool DoSingleZProbeAtPoint(); // Probe at a given point
|
||||||
bool DoSingleZProbe();
|
bool DoSingleZProbe(); // Probe where we are
|
||||||
bool SetSingleZProbeAtAPosition(GCodeBuffer *gb);
|
bool SetSingleZProbeAtAPosition(GCodeBuffer *gb); // Probes at a given position - see the comment at the head of the function itself
|
||||||
bool DoMultipleZProbe();
|
bool DoMultipleZProbe(); // Probes a series of points and sets the bed equation
|
||||||
bool SetPrintZProbe(GCodeBuffer *gb, char *reply);
|
bool SetPrintZProbe(GCodeBuffer *gb, char *reply); // Either return the probe value, or set its threshold
|
||||||
bool SetOffsets(GCodeBuffer *gb);
|
bool SetOffsets(GCodeBuffer *gb); // Deal with a G10
|
||||||
bool SetPositions(GCodeBuffer *gb);
|
bool SetPositions(GCodeBuffer *gb); // Deal with a G92
|
||||||
void LoadMoveBufferFromGCode(GCodeBuffer *gb, bool doingG92, bool applyLimits);
|
void LoadMoveBufferFromGCode(GCodeBuffer *gb, // Set up a move for the Move class
|
||||||
bool NoHome() const;
|
bool doingG92, bool applyLimits);
|
||||||
bool Push();
|
bool NoHome() const; // Are we homing and not finished?
|
||||||
bool Pop();
|
bool Push(); // Push feedrate etc on the stack
|
||||||
bool DisableDrives();
|
bool Pop(); // Pop feedrate etc
|
||||||
bool StandbyHeaters();
|
bool DisableDrives(); // Turn the motors off
|
||||||
void SetEthernetAddress(GCodeBuffer *gb, int mCode);
|
bool StandbyHeaters(); // Set all heaters to standby temperatures
|
||||||
void HandleReply(bool error, bool fromLine, const char* reply, char gMOrT, int code, bool resend);
|
void SetEthernetAddress(GCodeBuffer *gb, int mCode); // Does what it says
|
||||||
bool OpenFileToWrite(const char* directory, const char* fileName, GCodeBuffer *gb);
|
void SetMACAddress(GCodeBuffer *gb); // Deals with an M540
|
||||||
void WriteGCodeToFile(GCodeBuffer *gb);
|
void HandleReply(bool error, bool fromLine, const char* reply, // If the GCode is from the serial interface, reply to it
|
||||||
bool SendConfigToLine();
|
char gMOrT, int code, bool resend);
|
||||||
void WriteHTMLToFile(char b, GCodeBuffer *gb);
|
bool OpenFileToWrite(const char* directory, // Start saving GCodes in a file
|
||||||
bool OffsetAxes(GCodeBuffer *gb);
|
const char* fileName, GCodeBuffer *gb);
|
||||||
|
void WriteGCodeToFile(GCodeBuffer *gb); // Write this GCode into a file
|
||||||
|
bool SendConfigToLine(); // Deal with M503
|
||||||
|
void WriteHTMLToFile(char b, GCodeBuffer *gb); // Save an HTML file (usually to upload a new web interface)
|
||||||
|
bool OffsetAxes(GCodeBuffer *gb); // Set offsets - deprecated, use G10
|
||||||
void SetPidParameters(GCodeBuffer *gb, int heater, char reply[STRING_LENGTH]);
|
void SetPidParameters(GCodeBuffer *gb, int heater, char reply[STRING_LENGTH]);
|
||||||
void SetHeaterParameters(GCodeBuffer *gb, char reply[STRING_LENGTH]);
|
void SetHeaterParameters(GCodeBuffer *gb, char reply[STRING_LENGTH]);
|
||||||
int8_t Heater(int8_t head) const;
|
int8_t Heater(int8_t head) const;
|
||||||
|
Platform* platform; // The RepRap machine
|
||||||
Platform* platform;
|
bool active; // Live and running?
|
||||||
bool active;
|
Webserver* webserver; // The webserver class
|
||||||
Webserver* webserver;
|
float dwellTime; // How long a pause for a dwell (seconds)?
|
||||||
float dwellTime;
|
bool dwellWaiting; // We are in a dwell
|
||||||
bool dwellWaiting;
|
GCodeBuffer* webGCode; // The sources...
|
||||||
GCodeBuffer* webGCode;
|
GCodeBuffer* fileGCode; // ...
|
||||||
GCodeBuffer* fileGCode;
|
GCodeBuffer* serialGCode; // ...
|
||||||
GCodeBuffer* serialGCode;
|
GCodeBuffer* cannedCycleGCode; // ... of G Codes
|
||||||
GCodeBuffer* cannedCycleGCode;
|
bool moveAvailable; // Have we seen a move G Code and set it up?
|
||||||
bool moveAvailable;
|
float moveBuffer[DRIVES+1]; // Move coordinates; last is feed rate
|
||||||
float moveBuffer[DRIVES+1]; // Last is feed rate
|
bool checkEndStops; // Should we check them on the next move?
|
||||||
bool checkEndStops;
|
bool drivesRelative; // Are movements relative - all except X, Y and Z
|
||||||
bool drivesRelative; // All except X, Y and Z
|
bool axesRelative; // Are movements relative - X, Y and Z
|
||||||
bool axesRelative; // X, Y and Z
|
bool drivesRelativeStack[STACK]; // For dealing with Push and Pop
|
||||||
bool drivesRelativeStack[STACK];
|
bool axesRelativeStack[STACK]; // For dealing with Push and Pop
|
||||||
bool axesRelativeStack[STACK];
|
float feedrateStack[STACK]; // For dealing with Push and Pop
|
||||||
float feedrateStack[STACK];
|
|
||||||
FileData fileStack[STACK];
|
FileData fileStack[STACK];
|
||||||
int8_t stackPointer;
|
int8_t stackPointer; // Push and Pop stack pointer
|
||||||
char gCodeLetters[DRIVES + 1]; // Extra is for F
|
char gCodeLetters[DRIVES + 1]; // 'X', 'Y' etc. Extra is for F
|
||||||
float lastPos[DRIVES - AXES]; // Just needed for relative moves.
|
float lastPos[DRIVES - AXES]; // Just needed for relative moves; i.e. not X, Y and Z
|
||||||
float record[DRIVES+1];
|
float record[DRIVES+1]; // Temporary store for move positions
|
||||||
float moveToDo[DRIVES+1];
|
float moveToDo[DRIVES+1]; // Where to go set by G1 etc
|
||||||
bool activeDrive[DRIVES+1];
|
bool activeDrive[DRIVES+1]; // Is this drive involved in a move?
|
||||||
bool offSetSet;
|
bool offSetSet; // Are any axis offsets non-zero?
|
||||||
float distanceScale;
|
float distanceScale; // MM or inches
|
||||||
FileData fileBeingPrinted;
|
FileData fileBeingPrinted;
|
||||||
FileData fileToPrint;
|
FileData fileToPrint;
|
||||||
FileStore* fileBeingWritten;
|
FileStore* fileBeingWritten; // A file to write G Codes (or sometimes HTML) in
|
||||||
FileStore* configFile;
|
FileStore* configFile; // A file containing a macro
|
||||||
bool doingCannedCycleFile;
|
bool doingCannedCycleFile; // Are we executing a macro file?
|
||||||
char* eofString;
|
char* eofString; // What's at the end of an HTML file?
|
||||||
uint8_t eofStringCounter;
|
uint8_t eofStringCounter; // Check the...
|
||||||
uint8_t eofStringLength;
|
uint8_t eofStringLength; // ... EoF string as we read.
|
||||||
int8_t selectedHead;
|
int8_t selectedHead; // Which extruder is in use
|
||||||
bool homeX;
|
bool homeX; // True to home the X axis this move
|
||||||
bool homeY;
|
bool homeY; // True to home the Y axis this move
|
||||||
bool homeZ;
|
bool homeZ; // True to home the Z axis this move
|
||||||
float gFeedRate;
|
int8_t homeAxisMoveCount; // Counts homing moves
|
||||||
int probeCount;
|
float gFeedRate; // Store for the current feedrate
|
||||||
int8_t cannedCycleMoveCount;
|
int probeCount; // Counts multiple probe points
|
||||||
bool cannedCycleMoveQueued;
|
int8_t cannedCycleMoveCount; // Counts through internal (i.e. not macro) canned cycle moves
|
||||||
bool zProbesSet;
|
bool cannedCycleMoveQueued; // True if a canned cycle move has been set
|
||||||
float longWait;
|
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 limitAxes; // Don't think outside the box.
|
||||||
bool axisIsHomed[3]; // these record which of the axes have been homed
|
bool axisIsHomed[3]; // These record which of the axes have been homed
|
||||||
bool waitingForMoveToComplete;
|
bool waitingForMoveToComplete;
|
||||||
bool coolingInverted;
|
bool coolingInverted;
|
||||||
float speedFactor; // speed factor, including the conversion from mm/min to mm/sec, normally 1/60
|
float speedFactor; // speed factor, including the conversion from mm/min to mm/sec, normally 1/60
|
||||||
|
@ -262,4 +270,9 @@ inline bool GCodes::RunConfigurationGCodes()
|
||||||
return !DoFileCannedCycles(platform->GetConfigFile());
|
return !DoFileCannedCycles(platform->GetConfigFile());
|
||||||
}
|
}
|
||||||
|
|
||||||
|
inline int8_t GCodes::GetSelectedHead() const
|
||||||
|
{
|
||||||
|
return selectedHead;
|
||||||
|
}
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
71
Heat.h
71
Heat.h
|
@ -21,66 +21,76 @@ Licence: GPL
|
||||||
#ifndef HEAT_H
|
#ifndef HEAT_H
|
||||||
#define HEAT_H
|
#define HEAT_H
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This class implements a PID controller for the heaters
|
||||||
|
*/
|
||||||
|
|
||||||
class PID
|
class PID
|
||||||
{
|
{
|
||||||
public:
|
friend class Heat;
|
||||||
|
private:
|
||||||
|
//public:
|
||||||
|
|
||||||
PID(Platform* p, int8_t h);
|
PID(Platform* p, int8_t h);
|
||||||
void Init();
|
void Init(); // (Re)Set everything to start
|
||||||
void Spin();
|
void Spin(); // Called in a tight loop to keep things running
|
||||||
void SetActiveTemperature(float t);
|
void SetActiveTemperature(float t);
|
||||||
float GetActiveTemperature() const;
|
float GetActiveTemperature() const;
|
||||||
void SetStandbyTemperature(float t);
|
void SetStandbyTemperature(float t);
|
||||||
float GetStandbyTemperature() const;
|
float GetStandbyTemperature() const;
|
||||||
void Activate();
|
void Activate(); // Switch from idle to active
|
||||||
void Standby();
|
void Standby(); // Switch from active to idle
|
||||||
bool Active() const;
|
bool Active() const;
|
||||||
void ResetFault();
|
void ResetFault(); // Reset a fault condition - only call this if you know what you are doing
|
||||||
float GetTemperature() const;
|
float GetTemperature() const;
|
||||||
|
|
||||||
private:
|
// private:
|
||||||
|
|
||||||
Platform* platform;
|
Platform* platform; // The instance of the class that is the RepRap hardware
|
||||||
float activeTemperature;
|
float activeTemperature; // The required active temperature
|
||||||
float standbyTemperature;
|
float standbyTemperature; // The required standby temperature
|
||||||
float temperature;
|
float temperature; // The current temperature
|
||||||
float lastTemperature;
|
float lastTemperature; // The previous current temperature
|
||||||
float temp_iState;
|
float temp_iState; // The integral PID component
|
||||||
bool active;
|
bool active; // Are we active or standby?
|
||||||
int8_t heater;
|
int8_t heater; // The index of our heater
|
||||||
int8_t badTemperatureCount;
|
int8_t badTemperatureCount; // Count of sequential dud readings
|
||||||
bool temperatureFault;
|
bool temperatureFault; // Has our heater developed a fault?
|
||||||
};
|
};
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The master class that controls all the heaters in the RepRap machine
|
||||||
|
*/
|
||||||
|
|
||||||
class Heat
|
class Heat
|
||||||
{
|
{
|
||||||
|
|
||||||
public:
|
public:
|
||||||
|
|
||||||
Heat(Platform* p, GCodes* g);
|
Heat(Platform* p, GCodes* g);
|
||||||
void Spin();
|
void Spin(); // Called in a tight loop to keep everything going
|
||||||
void Init();
|
void Init(); // Set everything up
|
||||||
void Exit();
|
void Exit(); // Shut everything down
|
||||||
void SetActiveTemperature(int8_t heater, float t);
|
void SetActiveTemperature(int8_t heater, float t);
|
||||||
float GetActiveTemperature(int8_t heater) const;
|
float GetActiveTemperature(int8_t heater) const;
|
||||||
void SetStandbyTemperature(int8_t heater, float t);
|
void SetStandbyTemperature(int8_t heater, float t);
|
||||||
float GetStandbyTemperature(int8_t heater) const;
|
float GetStandbyTemperature(int8_t heater) const;
|
||||||
void Activate(int8_t heater);
|
void Activate(int8_t heater); // Turn on a heater
|
||||||
void Standby(int8_t heater);
|
void Standby(int8_t heater); // Set a heater idle
|
||||||
float GetTemperature(int8_t heater) const;
|
float GetTemperature(int8_t heater) const;
|
||||||
void ResetFault(int8_t heater);
|
void ResetFault(int8_t heater); // Reset a heater fault - oly call this if you know what you are doing
|
||||||
bool AllHeatersAtSetTemperatures() const;
|
bool AllHeatersAtSetTemperatures() const;
|
||||||
bool HeaterAtSetTemperature(int8_t heater) const; // Is a specific heater at temperature within tolerance?
|
bool HeaterAtSetTemperature(int8_t heater) const; // Is a specific heater at temperature within tolerance?
|
||||||
void Diagnostics();
|
void Diagnostics(); // Output useful information
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
Platform* platform;
|
Platform* platform; // The instance of the RepRap hardware class
|
||||||
GCodes* gCodes;
|
GCodes* gCodes; // The instance of the G Code interpreter class
|
||||||
bool active;
|
bool active; // Are we active?
|
||||||
PID* pids[HEATERS];
|
PID* pids[HEATERS]; // A PID controller for each heater
|
||||||
float lastTime;
|
float lastTime; // The last time our Spin() was called
|
||||||
float longWait;
|
float longWait; // Long time for things that happen occasionally
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
@ -189,5 +199,4 @@ inline void Heat::ResetFault(int8_t heater)
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -513,6 +513,9 @@ err_t ethernetif_init(struct netif *netif)
|
||||||
netif->output = etharp_output;
|
netif->output = etharp_output;
|
||||||
netif->linkoutput = low_level_output;
|
netif->linkoutput = low_level_output;
|
||||||
|
|
||||||
|
#if 1
|
||||||
|
// We now require the user to configure the MAC address if the default one is unsuitable, instead of selecting it automatically
|
||||||
|
#else
|
||||||
// Patch the last 4 bytes of the MAC address to be the IP address, so that we can support multiple Duets on the same subnet
|
// Patch the last 4 bytes of the MAC address to be the IP address, so that we can support multiple Duets on the same subnet
|
||||||
{
|
{
|
||||||
size_t i;
|
size_t i;
|
||||||
|
@ -521,9 +524,19 @@ err_t ethernetif_init(struct netif *netif)
|
||||||
gs_uc_mac_address[i + 2] = ((uint8_t*)&(netif->ip_addr))[i];
|
gs_uc_mac_address[i + 2] = ((uint8_t*)&(netif->ip_addr))[i];
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
/* Initialize the hardware */
|
/* Initialize the hardware */
|
||||||
low_level_init(netif);
|
low_level_init(netif);
|
||||||
|
|
||||||
return ERR_OK;
|
return ERR_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void RepRapNetworkSetMACAddress(const u8_t macAddress[])
|
||||||
|
{
|
||||||
|
size_t i;
|
||||||
|
for (i = 0; i < 8; ++i)
|
||||||
|
{
|
||||||
|
gs_uc_mac_address[i] = macAddress[i];
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
20
Move.cpp
20
Move.cpp
|
@ -271,7 +271,8 @@ bool Move::GetCurrentState(float m[])
|
||||||
if(i < AXES)
|
if(i < AXES)
|
||||||
m[i] = lastMove->MachineToEndPoint(i);
|
m[i] = lastMove->MachineToEndPoint(i);
|
||||||
else
|
else
|
||||||
m[i] = 0.0;
|
m[i] = 0.0; //FIXME This resets extruders to 0.0, even the inactive ones (is this behaviour desired?)
|
||||||
|
//m[i] = lastMove->MachineToEndPoint(i); //FIXME TEST alternative that does not reset extruders to 0
|
||||||
}
|
}
|
||||||
if(currentFeedrate >= 0.0)
|
if(currentFeedrate >= 0.0)
|
||||||
m[DRIVES] = currentFeedrate;
|
m[DRIVES] = currentFeedrate;
|
||||||
|
@ -364,7 +365,7 @@ void Move::SetStepHypotenuse()
|
||||||
// We don't want 0. If no axes/extruders are moving these should never be used.
|
// We don't want 0. If no axes/extruders are moving these should never be used.
|
||||||
// But try to be safe.
|
// But try to be safe.
|
||||||
|
|
||||||
stepDistances[0] = 1.0/platform->DriveStepsPerUnit(AXES);
|
stepDistances[0] = 1.0/platform->DriveStepsPerUnit(AXES); //FIXME this is not multi extruder safe (but we should never get here)
|
||||||
extruderStepDistances[0] = stepDistances[0];
|
extruderStepDistances[0] = stepDistances[0];
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -520,7 +521,7 @@ void Move::DoLookAhead()
|
||||||
else if (mt & zMove)
|
else if (mt & zMove)
|
||||||
c = platform->InstantDv(Z_AXIS);
|
c = platform->InstantDv(Z_AXIS);
|
||||||
else
|
else
|
||||||
c = platform->InstantDv(AXES); // value for first extruder FIXME??
|
c = platform->InstantDv((AXES+gCodes->GetSelectedHead())); // value for current extruder
|
||||||
}
|
}
|
||||||
n1->SetV(c);
|
n1->SetV(c);
|
||||||
n1->SetProcessed(vCosineSet);
|
n1->SetProcessed(vCosineSet);
|
||||||
|
@ -571,7 +572,7 @@ void Move::Interrupt()
|
||||||
dda = NULL;
|
dda = NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// creates a new lookahead object adds it to the lookahead ring, returns false if its full
|
||||||
bool Move::LookAheadRingAdd(const long ep[], float feedRate, float vv, bool ce, int8_t mt)
|
bool Move::LookAheadRingAdd(const long ep[], float feedRate, float vv, bool ce, int8_t mt)
|
||||||
{
|
{
|
||||||
if(LookAheadRingFull())
|
if(LookAheadRingFull())
|
||||||
|
@ -614,7 +615,7 @@ void Move::SetIdentityTransform()
|
||||||
secondDegreeCompensation = false;
|
secondDegreeCompensation = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
void Move::Transform(float xyzPoint[])
|
void Move::Transform(float xyzPoint[]) const
|
||||||
{
|
{
|
||||||
xyzPoint[X_AXIS] = xyzPoint[X_AXIS] + tanXY*xyzPoint[Y_AXIS] + tanXZ*xyzPoint[Z_AXIS];
|
xyzPoint[X_AXIS] = xyzPoint[X_AXIS] + tanXY*xyzPoint[Y_AXIS] + tanXZ*xyzPoint[Z_AXIS];
|
||||||
xyzPoint[Y_AXIS] = xyzPoint[Y_AXIS] + tanYZ*xyzPoint[Z_AXIS];
|
xyzPoint[Y_AXIS] = xyzPoint[Y_AXIS] + tanYZ*xyzPoint[Z_AXIS];
|
||||||
|
@ -624,7 +625,7 @@ void Move::Transform(float xyzPoint[])
|
||||||
xyzPoint[Z_AXIS] = xyzPoint[Z_AXIS] + aX*xyzPoint[X_AXIS] + aY*xyzPoint[Y_AXIS] + aC;
|
xyzPoint[Z_AXIS] = xyzPoint[Z_AXIS] + aX*xyzPoint[X_AXIS] + aY*xyzPoint[Y_AXIS] + aC;
|
||||||
}
|
}
|
||||||
|
|
||||||
void Move::InverseTransform(float xyzPoint[])
|
void Move::InverseTransform(float xyzPoint[]) const
|
||||||
{
|
{
|
||||||
if(secondDegreeCompensation)
|
if(secondDegreeCompensation)
|
||||||
xyzPoint[Z_AXIS] = xyzPoint[Z_AXIS] - SecondDegreeTransformZ(xyzPoint[X_AXIS], xyzPoint[Y_AXIS]);
|
xyzPoint[Z_AXIS] = xyzPoint[Z_AXIS] - SecondDegreeTransformZ(xyzPoint[X_AXIS], xyzPoint[Y_AXIS]);
|
||||||
|
@ -973,6 +974,10 @@ MovementProfile DDA::Init(LookAhead* lookAhead, float& u, float& v)
|
||||||
// by a velocity later.
|
// by a velocity later.
|
||||||
|
|
||||||
int8_t mt = myLookAheadEntry->GetMovementType();
|
int8_t mt = myLookAheadEntry->GetMovementType();
|
||||||
|
// acceleration calculation. Usually this is OK. But check that we are not asking
|
||||||
|
// the extruder to accelerate, decelerate, or move too fast. The common place
|
||||||
|
// for this to happen is when it is moving back from a previous retraction during
|
||||||
|
// an XY move.
|
||||||
|
|
||||||
if(mt & xyMove) // X or Y involved?
|
if(mt & xyMove) // X or Y involved?
|
||||||
{
|
{
|
||||||
|
@ -981,7 +986,6 @@ MovementProfile DDA::Init(LookAhead* lookAhead, float& u, float& v)
|
||||||
// the extruder to accelerate, decelerate, or move too fast. The common place
|
// the extruder to accelerate, decelerate, or move too fast. The common place
|
||||||
// for this to happen is when it is moving back from a previous retraction during
|
// for this to happen is when it is moving back from a previous retraction during
|
||||||
// an XY move.
|
// an XY move.
|
||||||
|
|
||||||
if((mt & eMove) && eDistance > distance)
|
if((mt & eMove) && eDistance > distance)
|
||||||
{
|
{
|
||||||
SetEAcceleration(eDistance);
|
SetEAcceleration(eDistance);
|
||||||
|
@ -1240,11 +1244,13 @@ float LookAhead::Cosine()
|
||||||
return cosine;
|
return cosine;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
//Returns units (mm) from steps for a particular drive
|
||||||
float LookAhead::MachineToEndPoint(int8_t drive, long coord)
|
float LookAhead::MachineToEndPoint(int8_t drive, long coord)
|
||||||
{
|
{
|
||||||
return ((float)coord)/reprap.GetPlatform()->DriveStepsPerUnit(drive);
|
return ((float)coord)/reprap.GetPlatform()->DriveStepsPerUnit(drive);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
//Returns steps from units (mm) for a particular drive
|
||||||
long LookAhead::EndPointToMachine(int8_t drive, float coord)
|
long LookAhead::EndPointToMachine(int8_t drive, float coord)
|
||||||
{
|
{
|
||||||
return (long)roundf(coord*reprap.GetPlatform()->DriveStepsPerUnit(drive));
|
return (long)roundf(coord*reprap.GetPlatform()->DriveStepsPerUnit(drive));
|
||||||
|
|
265
Move.h
265
Move.h
|
@ -60,188 +60,204 @@ enum PointCoordinateSet
|
||||||
zSet = 4
|
zSet = 4
|
||||||
};
|
};
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This class implements a look-ahead buffer for moves. It allows colinear
|
||||||
|
* moves not to decelerate between them, sets velocities at ends and beginnings
|
||||||
|
* for angled moves, and so on. Entries are joined in a doubly-linked list
|
||||||
|
* to form a ring buffer.
|
||||||
|
*/
|
||||||
class LookAhead
|
class LookAhead
|
||||||
{
|
{
|
||||||
public:
|
|
||||||
|
|
||||||
friend class Move;
|
friend class Move;
|
||||||
friend class DDA;
|
friend class DDA;
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
LookAhead(Move* m, Platform* p, LookAhead* n);
|
LookAhead(Move* m, Platform* p, LookAhead* n);
|
||||||
void Init(const long ep[], float feedRate, float vv, bool ce, int8_t mt);
|
void Init(const long ep[], float feedRate, float vv, bool ce, int8_t mt); // Set up this move
|
||||||
LookAhead* Next();
|
LookAhead* Next(); // Next one in the ring
|
||||||
LookAhead* Previous();
|
LookAhead* Previous(); // Previous one in the ring
|
||||||
const long* MachineEndPoints() const;
|
const long* MachineEndPoints() const;
|
||||||
float MachineToEndPoint(int8_t drive);
|
float MachineToEndPoint(int8_t drive); // Convert a move endpoint to real mm coordinates
|
||||||
static float MachineToEndPoint(int8_t drive, long coord);
|
static float MachineToEndPoint(int8_t drive, long coord); // Convert any number to a real coordinate
|
||||||
static long EndPointToMachine(int8_t drive, float coord);
|
static long EndPointToMachine(int8_t drive, float coord); // Convert real mm to a machine coordinate
|
||||||
int8_t GetMovementType() const;
|
int8_t GetMovementType() const; // What sort of move is this?
|
||||||
float FeedRate() const;
|
float FeedRate() const; // How fast is the maximum speed for this move
|
||||||
float V() const;
|
float V() const; // The speed at the end of the move
|
||||||
void SetV(float vv);
|
void SetV(float vv); // Set the end speed
|
||||||
void SetFeedRate(float f);
|
void SetFeedRate(float f); // Set the desired feedrate
|
||||||
int8_t Processed() const;
|
int8_t Processed() const; // Where we are in the look-ahead prediction sequence
|
||||||
void SetProcessed(MovementState ms);
|
void SetProcessed(MovementState ms); // Set where we are the the look ahead processing
|
||||||
void SetDriveCoordinateAndZeroEndSpeed(float a, int8_t drive);
|
void SetDriveCoordinateAndZeroEndSpeed(float a, int8_t drive); // Force an end ppoint and st its speed to stopped
|
||||||
bool CheckEndStops() const;
|
bool CheckEndStops() const; // Are we checking endstops on this move?
|
||||||
void Release();
|
void Release(); // This move has been processed and executed
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
Move* move;
|
Move* move; // The main movement control class
|
||||||
Platform* platform;
|
Platform* platform; // The RepRap machine
|
||||||
LookAhead* next;
|
LookAhead* next; // Next entry in the ring
|
||||||
LookAhead* previous;
|
LookAhead* previous; // Previous entry in the ring
|
||||||
long endPoint[DRIVES+1]; // Should never use the +1, but safety first
|
long endPoint[DRIVES+1]; // Machine coordinates of the endpoint. Should never use the +1, but safety first
|
||||||
int8_t movementType;
|
int8_t movementType; // XY move, Z move, extruder only etc
|
||||||
float Cosine();
|
float Cosine(); // The angle between the previous move and this one
|
||||||
bool checkEndStops;
|
bool checkEndStops; // Check endstops for this move
|
||||||
float cosine;
|
float cosine; // Store for the cosine value - the function uses lazy evaluation
|
||||||
float v; // The feedrate we can actually do
|
float v; // The feedrate we can actually do
|
||||||
float feedRate; // The requested feedrate
|
float feedRate; // The requested feedrate
|
||||||
float instantDv;
|
float instantDv; // The slowest speed we can move at. > 0
|
||||||
volatile int8_t processed;
|
volatile int8_t processed; // The stage in the look ahead process that this move is at.
|
||||||
};
|
};
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This implements an integer space machine coordinates Bressenham-style DDA to step the drives.
|
||||||
|
* DDAs are stored in a linked list forming a ring buffer.
|
||||||
|
*/
|
||||||
class DDA
|
class DDA
|
||||||
{
|
{
|
||||||
public:
|
|
||||||
|
|
||||||
friend class Move;
|
friend class Move;
|
||||||
friend class LookAhead;
|
friend class LookAhead;
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
DDA(Move* m, Platform* p, DDA* n);
|
DDA(Move* m, Platform* p, DDA* n);
|
||||||
MovementProfile Init(LookAhead* lookAhead, float& u, float& v);
|
MovementProfile Init(LookAhead* lookAhead, float& u, float& v); // Set up the DDA. Also used experimentally in look ahead.
|
||||||
void Start(bool noTest);
|
void Start(bool noTest); // Start executing the DDA. I.e. move the move.
|
||||||
void Step();
|
void Step(); // Take one step of the DDA. Called by timed interrupt.
|
||||||
bool Active() const;
|
bool Active() const;
|
||||||
DDA* Next();
|
DDA* Next(); // Next entry in the ring
|
||||||
float InstantDv() const;
|
float InstantDv() const;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
MovementProfile AccelerationCalculation(float& u, float& v, MovementProfile result);
|
|
||||||
void SetXYAcceleration();
|
MovementProfile AccelerationCalculation(float& u, float& v, // Compute acceleration profiles
|
||||||
void SetEAcceleration(float eDistance);
|
MovementProfile result);
|
||||||
Move* move;
|
void SetXYAcceleration(); // Compute an XY acceleration
|
||||||
Platform* platform;
|
void SetEAcceleration(float eDistance); // Compute an extruder acceleration
|
||||||
DDA* next;
|
|
||||||
LookAhead* myLookAheadEntry;
|
Move* move; // The main movement control class
|
||||||
long counter[DRIVES];
|
Platform* platform; // The RepRap machine
|
||||||
long delta[DRIVES];
|
DDA* next; // The next one in the ring
|
||||||
bool directions[DRIVES];
|
LookAhead* myLookAheadEntry; // The look-ahead entry corresponding to this DDA
|
||||||
long totalSteps;
|
long counter[DRIVES]; // Step counters
|
||||||
long stepCount;
|
long delta[DRIVES]; // How far to move each drive
|
||||||
bool checkEndStops;
|
bool directions[DRIVES]; // Forwards or backwards?
|
||||||
float timeStep;
|
long totalSteps; // Total number of steps for this move
|
||||||
float velocity;
|
long stepCount; // How many steps we have already taken
|
||||||
long stopAStep;
|
bool checkEndStops; // Are we checking endstops?
|
||||||
long startDStep;
|
float timeStep; // The current timestep (seconds)
|
||||||
float distance;
|
float velocity; // The current velocity
|
||||||
float acceleration;
|
long stopAStep; // The stepcount at which we stop accelerating
|
||||||
float instantDv;
|
long startDStep; // The stepcount at which we start decelerating
|
||||||
|
float distance; // How long is the move in real distance
|
||||||
|
float acceleration; // The acceleration to use
|
||||||
|
float instantDv; // The lowest possible velocity
|
||||||
float feedRate;
|
float feedRate;
|
||||||
volatile bool active;
|
volatile bool active; // Is the DDA running?
|
||||||
};
|
};
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This is the master movement class. It controls all movement in the machine.
|
||||||
|
*/
|
||||||
class Move
|
class Move
|
||||||
{
|
{
|
||||||
|
friend class DDA;
|
||||||
|
|
||||||
public:
|
public:
|
||||||
|
|
||||||
Move(Platform* p, GCodes* g);
|
Move(Platform* p, GCodes* g);
|
||||||
void Init();
|
void Init(); // Start me up
|
||||||
void Spin();
|
void Spin(); // Called in a tight loop to keep the class going
|
||||||
void Exit();
|
void Exit(); // Shut down
|
||||||
bool GetCurrentState(float m[]); // takes account of all the rings and delays
|
bool GetCurrentState(float m[]); // Return the current position if possible. Send false otherwise
|
||||||
void LiveCoordinates(float m[]); // Just gives the last point at the end of the last DDA
|
void LiveCoordinates(float m[]); // Gives the last point at the end of the last complete DDA
|
||||||
void Interrupt();
|
void Interrupt(); // The hardware's (i.e. platform's) interrupt should call this.
|
||||||
void InterruptTime();
|
void InterruptTime(); // Test function - not used
|
||||||
bool AllMovesAreFinished();
|
bool AllMovesAreFinished(); // Is the look-ahead ring empty? Stops more moves being added as well.
|
||||||
void ResumeMoving();
|
void ResumeMoving(); // Allow moves to be added after a call to AllMovesAreFinished()
|
||||||
void DoLookAhead();
|
void DoLookAhead(); // Run the look-ahead procedure
|
||||||
void HitLowStop(int8_t drive, LookAhead* la, DDA* hitDDA);
|
void HitLowStop(int8_t drive, // What to do when a low endstop is hit
|
||||||
void HitHighStop(int8_t drive, LookAhead* la, DDA* hitDDA);
|
LookAhead* la, DDA* hitDDA);
|
||||||
void SetPositions(float move[]);
|
void HitHighStop(int8_t drive, // What to do when a high endstop is hit
|
||||||
void SetLiveCoordinates(float coords[]);
|
LookAhead* la, DDA* hitDDA);
|
||||||
void SetXBedProbePoint(int index, float x);
|
void SetPositions(float move[]); // Force the coordinates to be these
|
||||||
void SetYBedProbePoint(int index, float y);
|
void SetLiveCoordinates(float coords[]); // Force the live coordinates (see above) to be these
|
||||||
void SetZBedProbePoint(int index, float z);
|
void SetXBedProbePoint(int index, float x); // Record the X coordinate of a probe point
|
||||||
float xBedProbePoint(int index) const;
|
void SetYBedProbePoint(int index, float y); // Record the Y coordinate of a probe point
|
||||||
float yBedProbePoint(int index) const;
|
void SetZBedProbePoint(int index, float z); // Record the Z coordinate of a probe point
|
||||||
float zBedProbePoint(int index) const;
|
float xBedProbePoint(int index) const; // Get the X coordinate of a probe point
|
||||||
int NumberOfProbePoints() const;
|
float yBedProbePoint(int index) const; // Get the Y coordinate of a probe point
|
||||||
int NumberOfXYProbePoints() const;
|
float zBedProbePoint(int index)const ; // Get the Z coordinate of a probe point
|
||||||
bool AllProbeCoordinatesSet(int index) const;
|
int NumberOfProbePoints() const; // How many points to probe have been set? 0 if incomplete
|
||||||
bool XYProbeCoordinatesSet(int index) const;
|
int NumberOfXYProbePoints() const; // How many XY coordinates of probe points have been set (Zs may not have been probed yet)
|
||||||
void SetZProbing(bool probing);
|
bool AllProbeCoordinatesSet(int index) const; // XY, and Z all set for this one?
|
||||||
void SetProbedBedEquation();
|
bool XYProbeCoordinatesSet(int index) const; // Just XY set for this one?
|
||||||
float SecondDegreeTransformZ(float x, float y) const;
|
void SetZProbing(bool probing); // Set the Z probe live
|
||||||
float GetLastProbedZ() const;
|
void SetProbedBedEquation(); // When we have a full set of probed points, work out the bed's equation
|
||||||
void SetAxisCompensation(int8_t axis, float tangent);
|
float SecondDegreeTransformZ(float x, float y) const; // Used for second degree bed equation
|
||||||
void SetIdentityTransform();
|
float GetLastProbedZ() const; // What was the Z when the probe last fired?
|
||||||
void Transform(float move[]);
|
void SetAxisCompensation(int8_t axis, float tangent); // Set an axis-pair compensation angle
|
||||||
void InverseTransform(float move[]);
|
void SetIdentityTransform(); // Cancel the bed equation; does not reset axis angle compensation
|
||||||
void Diagnostics();
|
void Transform(float move[]) const; // Take a position and apply the bed and the axis-angle compensations
|
||||||
float ComputeCurrentCoordinate(int8_t drive, LookAhead* la, DDA* runningDDA);
|
void InverseTransform(float move[]) const; // Go from a transformed point back to user coordinates
|
||||||
void SetStepHypotenuse();
|
void Diagnostics(); // Report useful stuff
|
||||||
|
float ComputeCurrentCoordinate(int8_t drive,// Turn a DDA value back into a real world coordinate
|
||||||
|
LookAhead* la, DDA* runningDDA);
|
||||||
friend class DDA;
|
void SetStepHypotenuse(); // Set up the hypotenuse lengths for multiple axis steps, like step both X and Y at once
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
bool DDARingAdd(LookAhead* lookAhead);
|
bool DDARingAdd(LookAhead* lookAhead); // Add a processed look-ahead entry to the DDA ring
|
||||||
DDA* DDARingGet();
|
DDA* DDARingGet(); // Get the next DDA ring entry to be run
|
||||||
bool DDARingEmpty() const;
|
bool DDARingEmpty() const;
|
||||||
bool NoLiveMovement() const;
|
bool NoLiveMovement() const;
|
||||||
bool DDARingFull() const;
|
bool DDARingFull() const;
|
||||||
bool GetDDARingLock();
|
bool GetDDARingLock(); // Lock the ring so only this function may access it
|
||||||
void ReleaseDDARingLock();
|
void ReleaseDDARingLock(); // Release the DDA ring lock
|
||||||
bool LookAheadRingEmpty() const;
|
bool LookAheadRingEmpty() const;
|
||||||
bool LookAheadRingFull() const;
|
bool LookAheadRingFull() const;
|
||||||
bool LookAheadRingAdd(const long ep[], float feedRate, float vv, bool ce, int8_t movementType);
|
bool LookAheadRingAdd(const long ep[], float feedRate, float vv, bool ce, int8_t movementType);
|
||||||
LookAhead* LookAheadRingGet();
|
LookAhead* LookAheadRingGet(); // Get the next entry from the look-ahead ring
|
||||||
int8_t GetMovementType(const long sp[], const long ep[]) const;
|
int8_t GetMovementType(const long sp[], const long ep[]) const; // XY? Z? extruder only?
|
||||||
|
|
||||||
float liveCoordinates[DRIVES + 1];
|
Platform* platform; // The RepRap machine
|
||||||
|
GCodes* gCodes; // The G Codes processing class
|
||||||
|
|
||||||
Platform* platform;
|
// These implement the DDA ring
|
||||||
GCodes* gCodes;
|
|
||||||
|
|
||||||
DDA* dda;
|
DDA* dda;
|
||||||
DDA* ddaRingAddPointer;
|
DDA* ddaRingAddPointer;
|
||||||
DDA* ddaRingGetPointer;
|
DDA* ddaRingGetPointer;
|
||||||
volatile bool ddaRingLocked;
|
volatile bool ddaRingLocked;
|
||||||
|
|
||||||
|
// These implement the look-ahead ring
|
||||||
|
|
||||||
LookAhead* lookAheadRingAddPointer;
|
LookAhead* lookAheadRingAddPointer;
|
||||||
LookAhead* lookAheadRingGetPointer;
|
LookAhead* lookAheadRingGetPointer;
|
||||||
LookAhead* lastMove;
|
LookAhead* lastMove;
|
||||||
DDA* lookAheadDDA;
|
DDA* lookAheadDDA;
|
||||||
int lookAheadRingCount;
|
int lookAheadRingCount;
|
||||||
|
|
||||||
float lastTime;
|
float lastTime; // The last time we were called (secs)
|
||||||
bool addNoMoreMoves;
|
bool addNoMoreMoves; // If true, allow no more moves to be added to the look-ahead
|
||||||
bool active;
|
bool active; // Are we live and running?
|
||||||
float currentFeedrate;
|
float currentFeedrate; // Err... the current feed rate...
|
||||||
float nextMove[DRIVES + 1]; // Extra is for feedrate
|
float liveCoordinates[DRIVES + 1]; // The last endpoint that the machine moved to
|
||||||
float stepDistances[(1<<AXES)]; // Index bits: lsb -> dx, dy, dz <- msb
|
float nextMove[DRIVES + 1]; // The endpoint of the next move to processExtra entry is for feedrate
|
||||||
float extruderStepDistances[(1<<(DRIVES-AXES))]; // NB - limits us to 5 extruders
|
float stepDistances[(1<<AXES)]; // The entry for [0b011] is the hypotenuse of an X and Y step together etc. Index bits: lsb -> dx, dy, dz <- msb
|
||||||
long nextMachineEndPoints[DRIVES+1];
|
float extruderStepDistances[(1<<(DRIVES-AXES))];// Same as above for the extruders. NB - may limit us to 5 extruders
|
||||||
float xBedProbePoints[NUMBER_OF_PROBE_POINTS];
|
long nextMachineEndPoints[DRIVES+1]; // The next endpoint in machine coordinates (i.e. steps)
|
||||||
float yBedProbePoints[NUMBER_OF_PROBE_POINTS];
|
float xBedProbePoints[NUMBER_OF_PROBE_POINTS]; // The X coordinates of the points on the bed at which to probe
|
||||||
float zBedProbePoints[NUMBER_OF_PROBE_POINTS];
|
float yBedProbePoints[NUMBER_OF_PROBE_POINTS]; // The X coordinates of the points on the bed at which to probe
|
||||||
uint8_t probePointSet[NUMBER_OF_PROBE_POINTS];
|
float zBedProbePoints[NUMBER_OF_PROBE_POINTS]; // The X coordinates of the points on the bed at which to probe
|
||||||
|
uint8_t probePointSet[NUMBER_OF_PROBE_POINTS]; // Has the XY of this point been set? Has the Z been probed?
|
||||||
float aX, aY, aC; // Bed plane explicit equation z' = z + aX*x + aY*y + aC
|
float aX, aY, aC; // Bed plane explicit equation z' = z + aX*x + aY*y + aC
|
||||||
float tanXY, tanYZ, tanXZ; // 90 degrees + angle gives angle between axes
|
float tanXY, tanYZ, tanXZ; // Axis compensation - 90 degrees + angle gives angle between axes
|
||||||
float xRectangle, yRectangle;
|
float xRectangle, yRectangle; // The side lengths of the rectangle used for second-degree bed compensation
|
||||||
float lastZHit;
|
float lastZHit; // The last Z value hit by the probe
|
||||||
bool zProbing;
|
bool zProbing; // Are we bed probing as well as moving?
|
||||||
bool secondDegreeCompensation;
|
bool secondDegreeCompensation; // Are we using second degree bed compensation. If not, linear
|
||||||
float longWait;
|
float longWait; // A long time for things that need to be done occasionally
|
||||||
};
|
};
|
||||||
|
|
||||||
//********************************************************************************************************
|
//********************************************************************************************************
|
||||||
|
@ -274,7 +290,6 @@ inline float LookAhead::MachineToEndPoint(int8_t drive)
|
||||||
return ((float)(endPoint[drive]))/platform->DriveStepsPerUnit(drive);
|
return ((float)(endPoint[drive]))/platform->DriveStepsPerUnit(drive);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
inline float LookAhead::FeedRate() const
|
inline float LookAhead::FeedRate() const
|
||||||
{
|
{
|
||||||
return feedRate;
|
return feedRate;
|
||||||
|
|
|
@ -50,6 +50,8 @@ extern "C"
|
||||||
#include "lwip/src/include/lwip/stats.h"
|
#include "lwip/src/include/lwip/stats.h"
|
||||||
#include "lwip/src/include/lwip/tcp.h"
|
#include "lwip/src/include/lwip/tcp.h"
|
||||||
|
|
||||||
|
void RepRapNetworkSetMACAddress(const u8_t macAddress[]);
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
const int httpStateSize = MEMP_NUM_TCP_PCB + 1; // the +1 is in case of recovering from network errors
|
const int httpStateSize = MEMP_NUM_TCP_PCB + 1; // the +1 is in case of recovering from network errors
|
||||||
|
@ -317,6 +319,7 @@ void Network::AppendTransaction(RequestState* volatile* list, RequestState *r)
|
||||||
|
|
||||||
void Network::Init()
|
void Network::Init()
|
||||||
{
|
{
|
||||||
|
RepRapNetworkSetMACAddress(reprap.GetPlatform()->MACAddress());
|
||||||
init_ethernet();
|
init_ethernet();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
64
Platform.cpp
64
Platform.cpp
|
@ -43,7 +43,6 @@ void setup()
|
||||||
}
|
}
|
||||||
|
|
||||||
reprap.Init();
|
reprap.Init();
|
||||||
//reprap.GetMove()->InterruptTime(); // Uncomment this line to time the interrupt routine on startup
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void loop()
|
void loop()
|
||||||
|
@ -122,6 +121,7 @@ void Platform::Init()
|
||||||
nvData.ipAddress = IP_ADDRESS;
|
nvData.ipAddress = IP_ADDRESS;
|
||||||
nvData.netMask = NET_MASK;
|
nvData.netMask = NET_MASK;
|
||||||
nvData.gateWay = GATE_WAY;
|
nvData.gateWay = GATE_WAY;
|
||||||
|
nvData.macAddress = MAC_ADDRESS;
|
||||||
|
|
||||||
nvData.zProbeType = 0; // Default is to use the switch
|
nvData.zProbeType = 0; // Default is to use the switch
|
||||||
nvData.switchZProbeParameters.Init(0.0);
|
nvData.switchZProbeParameters.Init(0.0);
|
||||||
|
@ -160,8 +160,8 @@ void Platform::Init()
|
||||||
|
|
||||||
fileStructureInitialised = true;
|
fileStructureInitialised = true;
|
||||||
|
|
||||||
mcp.begin();
|
mcpDuet.begin(); //only call begin once in the entire execution, this begins the I2C comms on that channel for all objects
|
||||||
|
mcpExpansion.setMCP4461Address(0x2E); //not required for mcpDuet, as this uses the default address
|
||||||
sysDir = SYS_DIR;
|
sysDir = SYS_DIR;
|
||||||
configFile = CONFIG_FILE;
|
configFile = CONFIG_FILE;
|
||||||
|
|
||||||
|
@ -180,6 +180,7 @@ void Platform::Init()
|
||||||
potWipes = POT_WIPES;
|
potWipes = POT_WIPES;
|
||||||
senseResistor = SENSE_RESISTOR;
|
senseResistor = SENSE_RESISTOR;
|
||||||
maxStepperDigipotVoltage = MAX_STEPPER_DIGIPOT_VOLTAGE;
|
maxStepperDigipotVoltage = MAX_STEPPER_DIGIPOT_VOLTAGE;
|
||||||
|
numMixingDrives = NUM_MIXING_DRIVES;
|
||||||
|
|
||||||
// Z PROBE
|
// Z PROBE
|
||||||
|
|
||||||
|
@ -207,26 +208,30 @@ void Platform::Init()
|
||||||
webDir = WEB_DIR;
|
webDir = WEB_DIR;
|
||||||
gcodeDir = GCODE_DIR;
|
gcodeDir = GCODE_DIR;
|
||||||
tempDir = TEMP_DIR;
|
tempDir = TEMP_DIR;
|
||||||
|
/*
|
||||||
|
FIXME Nasty having to specify individually if a pin is arduino or not.
|
||||||
|
requires a unified variant file. If implemented this would be much better
|
||||||
|
to allow for different hardware in the future
|
||||||
|
*/
|
||||||
for (size_t i = 0; i < DRIVES; i++)
|
for (size_t i = 0; i < DRIVES; i++)
|
||||||
{
|
{
|
||||||
if (stepPins[i] >= 0)
|
if (stepPins[i] >= 0)
|
||||||
{
|
{
|
||||||
if (i > Z_AXIS)
|
if(i == E0_DRIVE || i == E3_DRIVE) //STEP_PINS {14, 25, 5, X2, 41, 39, X4, 49}
|
||||||
pinModeNonDue(stepPins[i], OUTPUT);
|
pinModeNonDue(stepPins[i], OUTPUT);
|
||||||
else
|
else
|
||||||
pinMode(stepPins[i], OUTPUT);
|
pinMode(stepPins[i], OUTPUT);
|
||||||
}
|
}
|
||||||
if (directionPins[i] >= 0)
|
if (directionPins[i] >= 0)
|
||||||
{
|
{
|
||||||
if (i > Z_AXIS)
|
if(i == E0_DRIVE) //DIRECTION_PINS {15, 26, 4, X3, 35, 53, 51, 48}
|
||||||
pinModeNonDue(directionPins[i], OUTPUT);
|
pinModeNonDue(directionPins[i], OUTPUT);
|
||||||
else
|
else
|
||||||
pinMode(directionPins[i], OUTPUT);
|
pinMode(directionPins[i], OUTPUT);
|
||||||
}
|
}
|
||||||
if (enablePins[i] >= 0)
|
if (enablePins[i] >= 0)
|
||||||
{
|
{
|
||||||
if (i >= Z_AXIS)
|
if(i == Z_AXIS || i==E0_DRIVE || i==E2_DRIVE) //ENABLE_PINS {29, 27, X1, X0, 37, X8, 50, 47}
|
||||||
pinModeNonDue(enablePins[i], OUTPUT);
|
pinModeNonDue(enablePins[i], OUTPUT);
|
||||||
else
|
else
|
||||||
pinMode(enablePins[i], OUTPUT);
|
pinMode(enablePins[i], OUTPUT);
|
||||||
|
@ -234,8 +239,7 @@ void Platform::Init()
|
||||||
Disable(i);
|
Disable(i);
|
||||||
driveEnabled[i] = false;
|
driveEnabled[i] = false;
|
||||||
}
|
}
|
||||||
|
for(size_t i = 0; i < DRIVES; i++)
|
||||||
for (size_t i = 0; i < AXES; i++)
|
|
||||||
{
|
{
|
||||||
if (lowStopPins[i] >= 0)
|
if (lowStopPins[i] >= 0)
|
||||||
{
|
{
|
||||||
|
@ -253,7 +257,7 @@ void Platform::Init()
|
||||||
{
|
{
|
||||||
if (heatOnPins[i] >= 0)
|
if (heatOnPins[i] >= 0)
|
||||||
{
|
{
|
||||||
if (i == 0) // heater 0 (bed heater) is a standard Arduino PWM pin
|
if(i == E0_HEATER || i==E1_HEATER) //HEAT_ON_PINS {6, X5, X7, 7, 8, 9}
|
||||||
{
|
{
|
||||||
pinMode(heatOnPins[i], OUTPUT);
|
pinMode(heatOnPins[i], OUTPUT);
|
||||||
}
|
}
|
||||||
|
@ -262,7 +266,6 @@ void Platform::Init()
|
||||||
pinModeNonDue(heatOnPins[i], OUTPUT);
|
pinModeNonDue(heatOnPins[i], OUTPUT);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
thermistorFilters[i].Init();
|
thermistorFilters[i].Init();
|
||||||
heaterAdcChannels[i] = PinToAdcChannel(tempSensePins[i]);
|
heaterAdcChannels[i] = PinToAdcChannel(tempSensePins[i]);
|
||||||
|
|
||||||
|
@ -276,8 +279,8 @@ void Platform::Init()
|
||||||
|
|
||||||
if (coolingFanPin >= 0)
|
if (coolingFanPin >= 0)
|
||||||
{
|
{
|
||||||
pinMode(coolingFanPin, OUTPUT);
|
//pinModeNonDue(coolingFanPin, OUTPUT); //not required as analogwrite does this automatically
|
||||||
analogWrite(coolingFanPin, (HEAT_ON == 0) ? 255 : 0); // turn auxiliary cooling fan off
|
analogWriteNonDue(coolingFanPin, 255); //inverse logic for Duet v0.6 this turns it off
|
||||||
}
|
}
|
||||||
|
|
||||||
InitialiseInterrupts();
|
InitialiseInterrupts();
|
||||||
|
@ -540,9 +543,6 @@ void Platform::Spin()
|
||||||
|
|
||||||
line->Spin();
|
line->Spin();
|
||||||
|
|
||||||
if (Time() - lastTime < 0.006)
|
|
||||||
return;
|
|
||||||
lastTime = Time();
|
|
||||||
ClassReport("Platform", longWait);
|
ClassReport("Platform", longWait);
|
||||||
|
|
||||||
}
|
}
|
||||||
|
@ -722,7 +722,6 @@ void Platform::SetDebug(int d)
|
||||||
case DiagnosticTest::TestSpinLockup:
|
case DiagnosticTest::TestSpinLockup:
|
||||||
debugCode = d; // tell the Spin function to loop
|
debugCode = d; // tell the Spin function to loop
|
||||||
break;
|
break;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
@ -898,12 +897,18 @@ void Platform::SetHeater(size_t heater, const float& power)
|
||||||
|
|
||||||
byte p = (byte) (255.0 * min<float>(1.0, max<float>(0.0, power)));
|
byte p = (byte) (255.0 * min<float>(1.0, max<float>(0.0, power)));
|
||||||
if (HEAT_ON == 0)
|
if (HEAT_ON == 0)
|
||||||
|
{
|
||||||
p = 255 - p;
|
p = 255 - p;
|
||||||
if (heater == 0)
|
if(heater == E0_HEATER || heater == E1_HEATER) //HEAT_ON_PINS {6, X5, X7, 7, 8, 9}
|
||||||
analogWrite(heatOnPins[heater], p);
|
{
|
||||||
else
|
|
||||||
analogWriteNonDue(heatOnPins[heater], p);
|
analogWriteNonDue(heatOnPins[heater], p);
|
||||||
}
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
analogWrite(heatOnPins[heater], p);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
EndStopHit Platform::Stopped(int8_t drive)
|
EndStopHit Platform::Stopped(int8_t drive)
|
||||||
{
|
{
|
||||||
|
@ -982,6 +987,7 @@ void Platform::Step(byte drive)
|
||||||
}
|
}
|
||||||
|
|
||||||
// current is in mA
|
// current is in mA
|
||||||
|
|
||||||
void Platform::SetMotorCurrent(byte drive, float current)
|
void Platform::SetMotorCurrent(byte drive, float current)
|
||||||
{
|
{
|
||||||
unsigned short pot = (unsigned short)(0.256*current*8.0*senseResistor/maxStepperDigipotVoltage);
|
unsigned short pot = (unsigned short)(0.256*current*8.0*senseResistor/maxStepperDigipotVoltage);
|
||||||
|
@ -989,18 +995,28 @@ void Platform::SetMotorCurrent(byte drive, float current)
|
||||||
// snprintf(scratchString, STRING_LENGTH, "%d", pot);
|
// snprintf(scratchString, STRING_LENGTH, "%d", pot);
|
||||||
// Message(HOST_MESSAGE, scratchString);
|
// Message(HOST_MESSAGE, scratchString);
|
||||||
// Message(HOST_MESSAGE, "\n");
|
// Message(HOST_MESSAGE, "\n");
|
||||||
mcp.setNonVolatileWiper(potWipes[drive], pot);
|
if(drive < 4)
|
||||||
mcp.setVolatileWiper(potWipes[drive], pot);
|
{
|
||||||
|
mcpDuet.setNonVolatileWiper(potWipes[drive], pot);
|
||||||
|
mcpDuet.setVolatileWiper(potWipes[drive], pot);
|
||||||
}
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
mcpExpansion.setNonVolatileWiper(potWipes[drive], pot);
|
||||||
|
mcpExpansion.setVolatileWiper(potWipes[drive], pot);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
//Changed to be compatible with existing gcode norms
|
//Changed to be compatible with existing gcode norms
|
||||||
// M106 S0 = fully off M106 S255 = fully on
|
// M106 S0 = fully off M106 S255 = fully on
|
||||||
void Platform::CoolingFan(float speed)
|
void Platform::CoolingFan(float speed)
|
||||||
{
|
{
|
||||||
if(coolingFanPin > 0)
|
if(coolingFanPin >= 0)
|
||||||
{
|
{
|
||||||
|
byte p =(byte)speed;
|
||||||
// The cooling fan output pin gets inverted if HEAT_ON == 0
|
// The cooling fan output pin gets inverted if HEAT_ON == 0
|
||||||
analogWriteNonDue(coolingFanPin, (uint32_t)( (HEAT_ON == 0) ? (255.0 - speed) : speed));
|
analogWriteNonDue(coolingFanPin, (HEAT_ON == 0) ? (255 - p) : p);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
121
Platform.h
121
Platform.h
|
@ -1,8 +1,8 @@
|
||||||
/****************************************************************************************************
|
/****************************************************************************************************
|
||||||
|
|
||||||
RepRapFirmware - Platform: RepRapPro Mendel with Duet controller
|
RepRapFirmware - Platform: RepRapPro Ormerod with Duet controller
|
||||||
|
|
||||||
Platform contains all the code and definitons to deal with machine-dependent things such as control
|
Platform contains all the code and definitions to deal with machine-dependent things such as control
|
||||||
pins, bed area, number of extruders, tolerable accelerations and speeds and so on.
|
pins, bed area, number of extruders, tolerable accelerations and speeds and so on.
|
||||||
|
|
||||||
No definitions that are system-independent should go in here. Put them in Configuration.h. Note that
|
No definitions that are system-independent should go in here. Put them in Configuration.h. Note that
|
||||||
|
@ -70,27 +70,32 @@ Licence: GPL
|
||||||
#define AXES 3 // The number of movement axes in the machine, usually just X, Y and Z. <= DRIVES
|
#define AXES 3 // The number of movement axes in the machine, usually just X, Y and Z. <= DRIVES
|
||||||
#define HEATERS 2 // The number of heaters in the machine; 0 is the heated bed even if there isn't one.
|
#define HEATERS 2 // The number of heaters in the machine; 0 is the heated bed even if there isn't one.
|
||||||
|
|
||||||
// The numbers of entries in each array must correspond with the values of DRIVES,
|
// The numbers of entries in each {} array definition must correspond with the values of DRIVES,
|
||||||
// AXES, or HEATERS. Set values to -1 to flag unavailability.
|
// AXES, or HEATERS. Set values to -1 to flag unavailability. Pins are the microcontroller pin numbers.
|
||||||
|
|
||||||
// DRIVES
|
// DRIVES
|
||||||
|
|
||||||
#define STEP_PINS {14, 25, 5, X2}
|
#define STEP_PINS {14, 25, 5, X2} // Full array for Duet + Duex4 is {14, 25, 5, X2, 41, 39, X4, 49}
|
||||||
#define DIRECTION_PINS {15, 26, 4, X3}
|
#define DIRECTION_PINS {15, 26, 4, X3} // Full array for Duet + Duex4 is {15, 26, 4, X3, 35, 53, 51, 48}
|
||||||
#define FORWARDS true // What to send to go...
|
#define FORWARDS true // What to send to go...
|
||||||
#define BACKWARDS false // ...in each direction
|
#define BACKWARDS false // ...in each direction
|
||||||
#define ENABLE_PINS {29, 27, X1, X0}
|
#define ENABLE_PINS {29, 27, X1, X0} // Full array for Duet + Duex4 is {29, 27, X1, X0, 37, X8, 50, 47}
|
||||||
#define ENABLE false // What to send to enable...
|
#define ENABLE false // What to send to enable...
|
||||||
#define DISABLE true // ...and disable a drive
|
#define DISABLE true // ...and disable a drive
|
||||||
#define DISABLE_DRIVES {false, false, true, false} // Set true to disable a drive when it becomes idle
|
#define DISABLE_DRIVES {false, false, true, false} // Set true to disable a drive when it becomes idle
|
||||||
#define LOW_STOP_PINS {11, -1, 60, 31}
|
#define LOW_STOP_PINS {11, -1, 60, 31} // Full array endstop pins for Duet + Duex4 is {11, 28, 60, 31, 24, 46, 45, 44}
|
||||||
#define HIGH_STOP_PINS {-1, 28, -1, -1}
|
#define HIGH_STOP_PINS {-1, 28, -1, -1}
|
||||||
#define ENDSTOP_HIT 1 // when a stop == this it is hit
|
#define ENDSTOP_HIT 1 // when a stop == this it is hit
|
||||||
|
|
||||||
|
// Indices for motor current digipots (if any)
|
||||||
|
// first 4 are for digipot 1,(on duet)
|
||||||
|
// second 4 for digipot 2(on expansion board)
|
||||||
|
// Full order is {1, 3, 2, 0, 1, 3, 2, 0}, only include as many as you have DRIVES defined
|
||||||
#define POT_WIPES {1, 3, 2, 0} // Indices for motor current digipots (if any)
|
#define POT_WIPES {1, 3, 2, 0} // Indices for motor current digipots (if any)
|
||||||
#define SENSE_RESISTOR 0.1 // Stepper motor current sense resistor
|
#define SENSE_RESISTOR 0.1 // Stepper motor current sense resistor (ohms)
|
||||||
#define MAX_STEPPER_DIGIPOT_VOLTAGE ( 3.3*2.5/(2.7+2.5) ) // Stepper motor current reference voltage
|
#define MAX_STEPPER_DIGIPOT_VOLTAGE ( 3.3*2.5/(2.7+2.5) ) // Stepper motor current reference voltage
|
||||||
|
|
||||||
#define Z_PROBE_AD_VALUE (400)
|
#define Z_PROBE_AD_VALUE (400) // Default for the Z probe - should be overwritten by experiment
|
||||||
#define Z_PROBE_STOP_HEIGHT (0.7) // mm
|
#define Z_PROBE_STOP_HEIGHT (0.7) // mm
|
||||||
#define Z_PROBE_PIN (0) // Analogue pin number
|
#define Z_PROBE_PIN (0) // Analogue pin number
|
||||||
#define Z_PROBE_MOD_PIN (61) // Digital pin number to turn the IR LED on (high) or off (low)
|
#define Z_PROBE_MOD_PIN (61) // Digital pin number to turn the IR LED on (high) or off (low)
|
||||||
|
@ -100,23 +105,29 @@ const unsigned int numZProbeReadingsAveraged = 8; // we average this number of r
|
||||||
#define ACCELERATIONS {800.0, 800.0, 10.0, 250.0} // mm/sec^2
|
#define ACCELERATIONS {800.0, 800.0, 10.0, 250.0} // mm/sec^2
|
||||||
#define DRIVE_STEPS_PER_UNIT {87.4890, 87.4890, 4000.0, 420.0}
|
#define DRIVE_STEPS_PER_UNIT {87.4890, 87.4890, 4000.0, 420.0}
|
||||||
#define INSTANT_DVS {10.0, 10.0, 0.2, 2.0} // (mm/sec) these are also the minimum feed rates which is why I (dc42) decreased X/Y from 15 to 10
|
#define INSTANT_DVS {10.0, 10.0, 0.2, 2.0} // (mm/sec) these are also the minimum feed rates which is why I (dc42) decreased X/Y from 15 to 10
|
||||||
|
#define NUM_MIXING_DRIVES 1; //number of mixing drives
|
||||||
|
|
||||||
// AXES
|
// AXES
|
||||||
|
|
||||||
#define AXIS_MAXIMA {220, 200, 200} // mm
|
#define AXIS_MAXIMA {220, 200, 200} // mm
|
||||||
#define AXIS_MINIMA {0, 0, 0} // mm
|
#define AXIS_MINIMA {0, 0, 0} // mm
|
||||||
#define HOME_FEEDRATES {50.0, 50.0, 1.0} // mm/sec
|
#define HOME_FEEDRATES {50.0, 50.0, 1.0} // mm/sec
|
||||||
#define HEAD_OFFSETS {0.0, 0.0, 0.0}
|
#define HEAD_OFFSETS {0.0, 0.0, 0.0} // mm
|
||||||
|
|
||||||
#define X_AXIS 0 // The index of the X axis
|
#define X_AXIS 0 // The index of the X axis in the arrays
|
||||||
#define Y_AXIS 1 // The index of the Y axis
|
#define Y_AXIS 1 // The index of the Y axis
|
||||||
#define Z_AXIS 2 // The index of the Z 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 first
|
// HEATERS - The bed is assumed to be the at index 0
|
||||||
|
|
||||||
#define TEMP_SENSE_PINS {5, 4} // Analogue pin numbers
|
#define TEMP_SENSE_PINS {5, 4} // Analogue pin numbers (full array for Duet+Duex4 = {5, 4, 0, 7, 8, 9} )
|
||||||
#define HEAT_ON_PINS {6, X5}
|
#define HEAT_ON_PINS {6, X5} // PWM pins (full array for Duet+Duex4 = {6, X5, X7, 7, 8, 9} )
|
||||||
|
|
||||||
// Bed thermistor: http://uk.farnell.com/epcos/b57863s103f040/sensor-miniature-ntc-10k/dp/1299930?Ntt=129-9930
|
// Bed thermistor: http://uk.farnell.com/epcos/b57863s103f040/sensor-miniature-ntc-10k/dp/1299930?Ntt=129-9930
|
||||||
// Hot end thermistor: http://www.digikey.co.uk/product-search/en?x=20&y=11&KeyWords=480-3137-ND
|
// Hot end thermistor: http://www.digikey.co.uk/product-search/en?x=20&y=11&KeyWords=480-3137-ND
|
||||||
|
@ -159,8 +170,8 @@ const float defaultPidMax[HEATERS] = {255, 180}; // maximum value of I-term, mus
|
||||||
|
|
||||||
#define STANDBY_TEMPERATURES {ABS_ZERO, ABS_ZERO} // We specify one for the bed, though it's not needed
|
#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 ACTIVE_TEMPERATURES {ABS_ZERO, ABS_ZERO}
|
||||||
#define COOLING_FAN_PIN X6
|
#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 HEAT_ON 0 // 0 for inverted heater (eg 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
|
// 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
|
const unsigned int adOversampleBits = 1; // number of bits we oversample when reading temperatures
|
||||||
|
@ -174,6 +185,11 @@ const unsigned int adDisconnectedReal = adRangeReal - 3; // we consider an ADC r
|
||||||
const unsigned int adDisconnectedVirtual = adDisconnectedReal << adOversampleBits;
|
const unsigned int adDisconnectedVirtual = adDisconnectedReal << adOversampleBits;
|
||||||
|
|
||||||
#define HOT_BED 0 // The index of the heated bed; set to -1 if there is no heated bed
|
#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
|
||||||
|
|
||||||
/****************************************************************************************************/
|
/****************************************************************************************************/
|
||||||
|
|
||||||
|
@ -182,25 +198,25 @@ const unsigned int adDisconnectedVirtual = adDisconnectedReal << adOversampleBit
|
||||||
#define MAX_FILES (10) // must be large enough to handle the max number of simultaneous web requests + file being printed
|
#define MAX_FILES (10) // must be large enough to handle the max number of simultaneous web requests + file being printed
|
||||||
#define FILE_BUF_LEN (256)
|
#define FILE_BUF_LEN (256)
|
||||||
#define SD_SPI (4) //Pin
|
#define SD_SPI (4) //Pin
|
||||||
#define WEB_DIR "0:/www/" // Place to find web files on the server
|
#define WEB_DIR "0:/www/" // Place to find web files on the SD card
|
||||||
#define GCODE_DIR "0:/gcodes/" // Ditto - g-codes
|
#define GCODE_DIR "0:/gcodes/" // Ditto - g-codes
|
||||||
#define SYS_DIR "0:/sys/" // Ditto - system files
|
#define SYS_DIR "0:/sys/" // Ditto - system files
|
||||||
#define TEMP_DIR "0:/tmp/" // Ditto - temporary files
|
#define TEMP_DIR "0:/tmp/" // Ditto - temporary files
|
||||||
#define FILE_LIST_SEPARATOR ','
|
#define FILE_LIST_LENGTH (1000) // Maximum length of file list
|
||||||
#define FILE_LIST_BRACKET '"'
|
|
||||||
#define FILE_LIST_LENGTH (1000) // Maximum length of file list - can't make it much longer unless we also make jsonResponse longer
|
|
||||||
|
|
||||||
#define FLASH_LED 'F' // Type byte of a message that is to flash an LED; the next two bytes define the frequency and M/S ratio.
|
#define FLASH_LED 'F' // Type byte of a message that is to flash an LED; the next two bytes define
|
||||||
#define DISPLAY_MESSAGE 'L' // Type byte of a message that is to appear on a local display; the L is not displayed; \f and \n should be supported.
|
// the frequency and M/S ratio.
|
||||||
|
#define DISPLAY_MESSAGE 'L' // Type byte of a message that is to appear on a local display; the L is
|
||||||
|
// not displayed; \f and \n should be supported.
|
||||||
#define HOST_MESSAGE 'H' // Type byte of a message that is to be sent to the host; the H is not sent.
|
#define HOST_MESSAGE 'H' // Type byte of a message that is to be sent to the host; the H is not sent.
|
||||||
#define DEBUG_MESSAGE 'D' // Type byte of a message that is to be sent for debugging; the D is not sent.
|
#define DEBUG_MESSAGE 'D' // Type byte of a message that is to be sent for debugging; the D is not sent.
|
||||||
|
#define MAC_ADDRESS {0xBE, 0xEF, 0xDE, 0xAD, 0xFE, 0xED}
|
||||||
|
|
||||||
|
|
||||||
/****************************************************************************************************/
|
/****************************************************************************************************/
|
||||||
|
|
||||||
// Miscellaneous...
|
// Miscellaneous...
|
||||||
|
|
||||||
//#define LED_PIN 13 // Indicator LED
|
|
||||||
|
|
||||||
#define BAUD_RATE 115200 // Communication speed of the USB if needed.
|
#define BAUD_RATE 115200 // Communication speed of the USB if needed.
|
||||||
|
|
||||||
const int atxPowerPin = 12; // Arduino Due pin number that controls the ATX power on/off
|
const int atxPowerPin = 12; // Arduino Due pin number that controls the ATX power on/off
|
||||||
|
@ -208,7 +224,6 @@ const int atxPowerPin = 12; // Arduino Due pin number that controls the ATX
|
||||||
const uint16_t lineInBufsize = 256; // use a power of 2 for good performance
|
const uint16_t lineInBufsize = 256; // use a power of 2 for good performance
|
||||||
const uint16_t lineOutBufSize = 2048; // ideally this should be large enough to hold the results of an M503 command,
|
const uint16_t lineOutBufSize = 2048; // ideally this should be large enough to hold the results of an M503 command,
|
||||||
// but could be reduced if we ever need the memory
|
// but could be reduced if we ever need the memory
|
||||||
const uint16_t NumZProbeReadingsAveraged = 8; // must be an even number, preferably a power of 2 for performance, and no greater than 64
|
|
||||||
|
|
||||||
/****************************************************************************************************/
|
/****************************************************************************************************/
|
||||||
|
|
||||||
|
@ -254,6 +269,7 @@ namespace DiagnosticTest
|
||||||
{
|
{
|
||||||
TestWatchdog = 1001, // test that we get a watchdog reset if the tick interrupt stops
|
TestWatchdog = 1001, // test that we get a watchdog reset if the tick interrupt stops
|
||||||
TestSpinLockup = 1002 // test that we get a software reset if a Spin() function takes too long
|
TestSpinLockup = 1002 // test that we get a software reset if a Spin() function takes too long
|
||||||
|
|
||||||
};
|
};
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -532,6 +548,8 @@ public:
|
||||||
const byte* NetMask() const;
|
const byte* NetMask() const;
|
||||||
void SetGateWay(byte gw[]);
|
void SetGateWay(byte gw[]);
|
||||||
const byte* GateWay() const;
|
const byte* GateWay() const;
|
||||||
|
void SetMACAddress(uint8_t mac[]);
|
||||||
|
const uint8_t* MACAddress() const;
|
||||||
|
|
||||||
friend class FileStore;
|
friend class FileStore;
|
||||||
|
|
||||||
|
@ -583,6 +601,11 @@ public:
|
||||||
bool SetZProbeParameters(const struct ZProbeParameters& params);
|
bool SetZProbeParameters(const struct ZProbeParameters& params);
|
||||||
bool MustHomeXYBeforeZ() const;
|
bool MustHomeXYBeforeZ() const;
|
||||||
|
|
||||||
|
// Mixing support
|
||||||
|
|
||||||
|
void SetMixingDrives(int);
|
||||||
|
int GetMixingDrives();
|
||||||
|
|
||||||
// Heat and temperature
|
// Heat and temperature
|
||||||
|
|
||||||
float GetTemperature(size_t heater) const; // Result is in degrees Celsius
|
float GetTemperature(size_t heater) const; // Result is in degrees Celsius
|
||||||
|
@ -619,6 +642,7 @@ private:
|
||||||
byte ipAddress[4];
|
byte ipAddress[4];
|
||||||
byte netMask[4];
|
byte netMask[4];
|
||||||
byte gateWay[4];
|
byte gateWay[4];
|
||||||
|
uint8_t macAddress[6];
|
||||||
Compatibility compatibility;
|
Compatibility compatibility;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -650,7 +674,10 @@ private:
|
||||||
float accelerations[DRIVES];
|
float accelerations[DRIVES];
|
||||||
float driveStepsPerUnit[DRIVES];
|
float driveStepsPerUnit[DRIVES];
|
||||||
float instantDvs[DRIVES];
|
float instantDvs[DRIVES];
|
||||||
MCP4461 mcp;
|
MCP4461 mcpDuet;
|
||||||
|
MCP4461 mcpExpansion;
|
||||||
|
|
||||||
|
|
||||||
int8_t potWipes[DRIVES];
|
int8_t potWipes[DRIVES];
|
||||||
float senseResistor;
|
float senseResistor;
|
||||||
float maxStepperDigipotVoltage;
|
float maxStepperDigipotVoltage;
|
||||||
|
@ -660,6 +687,7 @@ private:
|
||||||
volatile ZProbeAveragingFilter zProbeOnFilter; // Z probe readings we took with the IR turned on
|
volatile ZProbeAveragingFilter zProbeOnFilter; // Z probe readings we took with the IR turned on
|
||||||
volatile ZProbeAveragingFilter zProbeOffFilter; // Z probe readings we took with the IR turned off
|
volatile ZProbeAveragingFilter zProbeOffFilter; // Z probe readings we took with the IR turned off
|
||||||
volatile ThermistorAveragingFilter thermistorFilters[HEATERS]; // bed and extruder thermistor readings
|
volatile ThermistorAveragingFilter thermistorFilters[HEATERS]; // bed and extruder thermistor readings
|
||||||
|
int8_t numMixingDrives;
|
||||||
|
|
||||||
// AXES
|
// AXES
|
||||||
|
|
||||||
|
@ -916,6 +944,21 @@ inline void Platform::SetMaxFeedrate(int8_t drive, float value)
|
||||||
maxFeedrates[drive] = value;
|
maxFeedrates[drive] = value;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
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
|
// Drive the RepRap machine - Heat and temperature
|
||||||
|
@ -932,8 +975,6 @@ inline float Platform::HeatSampleTime() const
|
||||||
return heatSampleTime;
|
return heatSampleTime;
|
||||||
}
|
}
|
||||||
|
|
||||||
//****************************************************************************************************************
|
|
||||||
|
|
||||||
inline const byte* Platform::IPAddress() const
|
inline const byte* Platform::IPAddress() const
|
||||||
{
|
{
|
||||||
return nvData.ipAddress;
|
return nvData.ipAddress;
|
||||||
|
@ -949,6 +990,28 @@ inline const byte* Platform::GateWay() const
|
||||||
return nvData.gateWay;
|
return nvData.gateWay;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
inline void Platform::SetMACAddress(uint8_t mac[])
|
||||||
|
{
|
||||||
|
bool changed = false;
|
||||||
|
for(int8_t i = 0; i < 6; i++)
|
||||||
|
{
|
||||||
|
if (nvData.macAddress[i] != mac[i])
|
||||||
|
{
|
||||||
|
nvData.macAddress[i] = mac[i];
|
||||||
|
changed = true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (changed)
|
||||||
|
{
|
||||||
|
WriteNvData();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
inline const byte* Platform::MACAddress() const
|
||||||
|
{
|
||||||
|
return nvData.macAddress;
|
||||||
|
}
|
||||||
|
|
||||||
inline Line* Platform::GetLine() const
|
inline Line* Platform::GetLine() const
|
||||||
{
|
{
|
||||||
return line;
|
return line;
|
||||||
|
|
BIN
Release/RepRapFirmware-065e-dc42.bin
Normal file
BIN
Release/RepRapFirmware-065e-dc42.bin
Normal file
Binary file not shown.
|
@ -165,6 +165,7 @@ RepRap::RepRap() : active(false), debug(false), stopped(false), spinState(0), ti
|
||||||
gCodes = new GCodes(platform, webserver);
|
gCodes = new GCodes(platform, webserver);
|
||||||
move = new Move(platform, gCodes);
|
move = new Move(platform, gCodes);
|
||||||
heat = new Heat(platform, gCodes);
|
heat = new Heat(platform, gCodes);
|
||||||
|
toolList = NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
void RepRap::Init()
|
void RepRap::Init()
|
||||||
|
@ -177,7 +178,7 @@ void RepRap::Init()
|
||||||
webserver->Init();
|
webserver->Init();
|
||||||
move->Init();
|
move->Init();
|
||||||
heat->Init();
|
heat->Init();
|
||||||
|
currentTool = NULL;
|
||||||
const uint32_t wdtTicks = 256; // number of watchdog ticks @ 32768Hz/128 before the watchdog times out (max 4095)
|
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
|
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
|
active = true; // must do this before we start the network, else the watchdog may time out
|
||||||
|
@ -199,6 +200,9 @@ void RepRap::Init()
|
||||||
platform->Message(HOST_MESSAGE, "\n");
|
platform->Message(HOST_MESSAGE, "\n");
|
||||||
platform->Message(HOST_MESSAGE, NAME);
|
platform->Message(HOST_MESSAGE, NAME);
|
||||||
platform->Message(HOST_MESSAGE, " is up and running.\n");
|
platform->Message(HOST_MESSAGE, " is up and running.\n");
|
||||||
|
fastLoop = FLT_MAX;
|
||||||
|
slowLoop = 0.0;
|
||||||
|
lastTime = platform->Time();
|
||||||
}
|
}
|
||||||
|
|
||||||
void RepRap::Exit()
|
void RepRap::Exit()
|
||||||
|
@ -243,6 +247,15 @@ void RepRap::Spin()
|
||||||
|
|
||||||
spinState = 0;
|
spinState = 0;
|
||||||
ticksInSpinState = 0;
|
ticksInSpinState = 0;
|
||||||
|
// Keep track of the loop time
|
||||||
|
|
||||||
|
double t = platform->Time();
|
||||||
|
double dt = t - lastTime;
|
||||||
|
if(dt < fastLoop)
|
||||||
|
fastLoop = dt;
|
||||||
|
if(dt > slowLoop)
|
||||||
|
slowLoop = dt;
|
||||||
|
lastTime = t;
|
||||||
}
|
}
|
||||||
|
|
||||||
void RepRap::Diagnostics()
|
void RepRap::Diagnostics()
|
||||||
|
@ -252,6 +265,10 @@ void RepRap::Diagnostics()
|
||||||
heat->Diagnostics();
|
heat->Diagnostics();
|
||||||
gCodes->Diagnostics();
|
gCodes->Diagnostics();
|
||||||
webserver->Diagnostics();
|
webserver->Diagnostics();
|
||||||
|
snprintf(scratchString, STRING_LENGTH, "Slow loop secs: %f; fast: %f\n", slowLoop, fastLoop);
|
||||||
|
platform->Message(HOST_MESSAGE, scratchString);
|
||||||
|
fastLoop = FLT_MAX;
|
||||||
|
slowLoop = 0.0;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Turn off the heaters, disable the motors, and
|
// Turn off the heaters, disable the motors, and
|
||||||
|
@ -265,6 +282,13 @@ void RepRap::EmergencyStop()
|
||||||
|
|
||||||
//platform->DisableInterrupts();
|
//platform->DisableInterrupts();
|
||||||
|
|
||||||
|
Tool* t = toolList;
|
||||||
|
while(t)
|
||||||
|
{
|
||||||
|
t->Standby();
|
||||||
|
t = t->Next();
|
||||||
|
}
|
||||||
|
|
||||||
heat->Exit();
|
heat->Exit();
|
||||||
for(int8_t i = 0; i < HEATERS; i++)
|
for(int8_t i = 0; i < HEATERS; i++)
|
||||||
{
|
{
|
||||||
|
@ -290,6 +314,84 @@ void RepRap::EmergencyStop()
|
||||||
webserver->HandleReply("Emergency Stop! Reset the controller to continue.", false);
|
webserver->HandleReply("Emergency Stop! Reset the controller to continue.", false);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void RepRap::AddTool(Tool* t)
|
||||||
|
{
|
||||||
|
if(toolList == NULL)
|
||||||
|
{
|
||||||
|
toolList = t;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
toolList->AddTool(t);
|
||||||
|
}
|
||||||
|
|
||||||
|
void RepRap::SelectTool(int toolNumber)
|
||||||
|
{
|
||||||
|
Tool* t = toolList;
|
||||||
|
|
||||||
|
while(t)
|
||||||
|
{
|
||||||
|
if(t->Number() == toolNumber)
|
||||||
|
{
|
||||||
|
t->Activate(currentTool);
|
||||||
|
currentTool = t;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
t = t->Next();
|
||||||
|
}
|
||||||
|
|
||||||
|
platform->Message(HOST_MESSAGE, "Attempt to select and activate a non-existent tool.\n");
|
||||||
|
}
|
||||||
|
|
||||||
|
void RepRap::StandbyTool(int toolNumber)
|
||||||
|
{
|
||||||
|
Tool* t = toolList;
|
||||||
|
|
||||||
|
while(t)
|
||||||
|
{
|
||||||
|
if(t->Number() == toolNumber)
|
||||||
|
{
|
||||||
|
t->Standby();
|
||||||
|
if(currentTool == t)
|
||||||
|
currentTool = NULL;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
t = t->Next();
|
||||||
|
}
|
||||||
|
|
||||||
|
platform->Message(HOST_MESSAGE, "Attempt to standby a non-existent tool.\n");
|
||||||
|
}
|
||||||
|
|
||||||
|
void RepRap::SetToolVariables(int toolNumber, float x, float y, float z, float* standbyTemperatures, float* activeTemperatures)
|
||||||
|
{
|
||||||
|
Tool* t = toolList;
|
||||||
|
|
||||||
|
while(t)
|
||||||
|
{
|
||||||
|
if(t->Number() == toolNumber)
|
||||||
|
{
|
||||||
|
t->SetVariables(x, y, z, standbyTemperatures, activeTemperatures);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
t = t->Next();
|
||||||
|
}
|
||||||
|
platform->Message(HOST_MESSAGE, "Attempt to set-up a non-existent tool.\n");
|
||||||
|
}
|
||||||
|
|
||||||
|
void RepRap::GetCurrentToolOffset(float& x, float& y, float& z)
|
||||||
|
{
|
||||||
|
if(currentTool == NULL)
|
||||||
|
{
|
||||||
|
platform->Message(HOST_MESSAGE, "Attempt to get offset when no tool selected.\n");
|
||||||
|
x = 0.0;
|
||||||
|
y = 0.0;
|
||||||
|
z = 0.0;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
currentTool->GetOffset(x, y, z);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
void RepRap::Tick()
|
void RepRap::Tick()
|
||||||
{
|
{
|
||||||
if (active)
|
if (active)
|
||||||
|
@ -306,7 +408,6 @@ void RepRap::Tick()
|
||||||
{
|
{
|
||||||
platform->SetHeater(i, 0.0);
|
platform->SetHeater(i, 0.0);
|
||||||
}
|
}
|
||||||
|
|
||||||
for(uint8_t i = 0; i < DRIVES; i++)
|
for(uint8_t i = 0; i < DRIVES; i++)
|
||||||
{
|
{
|
||||||
platform->Disable(i);
|
platform->Disable(i);
|
||||||
|
@ -324,6 +425,7 @@ void RepRap::Tick()
|
||||||
// 1 = debug on
|
// 1 = debug on
|
||||||
// other = print stats and run code-specific tests
|
// other = print stats and run code-specific tests
|
||||||
void RepRap::SetDebug(int d)
|
void RepRap::SetDebug(int d)
|
||||||
|
|
||||||
{
|
{
|
||||||
switch(d)
|
switch(d)
|
||||||
{
|
{
|
||||||
|
|
|
@ -35,6 +35,7 @@ class Webserver;
|
||||||
class GCodes;
|
class GCodes;
|
||||||
class Move;
|
class Move;
|
||||||
class Heat;
|
class Heat;
|
||||||
|
class Tool;
|
||||||
class RepRap;
|
class RepRap;
|
||||||
class FileStore;
|
class FileStore;
|
||||||
|
|
||||||
|
@ -69,6 +70,7 @@ extern char scratchString[];
|
||||||
#include "GCodes.h"
|
#include "GCodes.h"
|
||||||
#include "Move.h"
|
#include "Move.h"
|
||||||
#include "Heat.h"
|
#include "Heat.h"
|
||||||
|
#include "Tool.h"
|
||||||
#include "Reprap.h"
|
#include "Reprap.h"
|
||||||
|
|
||||||
// std::min and std::max don't seem to work with this variant of gcc, so define our own ones here
|
// std::min and std::max don't seem to work with this variant of gcc, so define our own ones here
|
||||||
|
|
10
Reprap.h
10
Reprap.h
|
@ -34,6 +34,11 @@ class RepRap
|
||||||
void Diagnostics();
|
void Diagnostics();
|
||||||
bool Debug() const;
|
bool Debug() const;
|
||||||
void SetDebug(int d);
|
void SetDebug(int d);
|
||||||
|
void AddTool(Tool* t);
|
||||||
|
void SelectTool(int toolNumber);
|
||||||
|
void StandbyTool(int toolNumber);
|
||||||
|
void SetToolVariables(int toolNumber, float x, float y, float z, float* standbyTemperatures, float* activeTemperatures);
|
||||||
|
void GetCurrentToolOffset(float& x, float& y, float& z);
|
||||||
Platform* GetPlatform() const;
|
Platform* GetPlatform() const;
|
||||||
Move* GetMove() const;
|
Move* GetMove() const;
|
||||||
Heat* GetHeat() const;
|
Heat* GetHeat() const;
|
||||||
|
@ -52,9 +57,13 @@ class RepRap
|
||||||
Heat* heat;
|
Heat* heat;
|
||||||
GCodes* gCodes;
|
GCodes* gCodes;
|
||||||
Webserver* webserver;
|
Webserver* webserver;
|
||||||
|
Tool* toolList;
|
||||||
|
Tool* currentTool;
|
||||||
uint16_t ticksInSpinState;
|
uint16_t ticksInSpinState;
|
||||||
uint8_t spinState;
|
uint8_t spinState;
|
||||||
bool debug;
|
bool debug;
|
||||||
|
float fastLoop, slowLoop;
|
||||||
|
float lastTime;
|
||||||
bool stopped;
|
bool stopped;
|
||||||
bool active;
|
bool active;
|
||||||
bool resetting;
|
bool resetting;
|
||||||
|
@ -71,7 +80,6 @@ inline void RepRap::Interrupt() { move->Interrupt(); }
|
||||||
inline bool RepRap::IsStopped() const { return stopped; }
|
inline bool RepRap::IsStopped() const { return stopped; }
|
||||||
inline uint16_t RepRap::GetTicksInSpinState() const { return ticksInSpinState; }
|
inline uint16_t RepRap::GetTicksInSpinState() const { return ticksInSpinState; }
|
||||||
|
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
|
107
Tool.cpp
Normal file
107
Tool.cpp
Normal file
|
@ -0,0 +1,107 @@
|
||||||
|
/****************************************************************************************************
|
||||||
|
|
||||||
|
RepRapFirmware - Tool
|
||||||
|
|
||||||
|
This class implements a tool in the RepRap machine, usually (though not necessarily) an extruder.
|
||||||
|
|
||||||
|
Tools may have zero or more drives associated with them and zero or more heaters. There are a fixed number
|
||||||
|
of tools in a given RepRap, with fixed heaters and drives. All this is specified on reboot, and cannot
|
||||||
|
be altered dynamically. This restriction may be lifted in the future. Tool descriptions are stored in
|
||||||
|
GCode macros that are loaded on reboot.
|
||||||
|
|
||||||
|
-----------------------------------------------------------------------------------------------------
|
||||||
|
|
||||||
|
Version 0.1
|
||||||
|
|
||||||
|
Created on: Apr 11, 2014
|
||||||
|
|
||||||
|
Adrian Bowyer
|
||||||
|
RepRap Professional Ltd
|
||||||
|
http://reprappro.com
|
||||||
|
|
||||||
|
Licence: GPL
|
||||||
|
|
||||||
|
****************************************************************************************************/
|
||||||
|
|
||||||
|
#include "RepRapFirmware.h"
|
||||||
|
|
||||||
|
Tool::Tool(int tNum, int d[], int h[])
|
||||||
|
{
|
||||||
|
myNumber = tNum;
|
||||||
|
next = NULL;
|
||||||
|
active = false;
|
||||||
|
|
||||||
|
for(driveCount = 0; driveCount < DRIVES; driveCount++)
|
||||||
|
if(d[driveCount] < 0)
|
||||||
|
break;
|
||||||
|
if(driveCount > 0)
|
||||||
|
{
|
||||||
|
drives = new int[driveCount];
|
||||||
|
for(int8_t drive = 0; drive < driveCount; drive++)
|
||||||
|
drives[drive] = d[drive];
|
||||||
|
}
|
||||||
|
|
||||||
|
for(heaterCount = 0; heaterCount < HEATERS; heaterCount++)
|
||||||
|
if(h[heaterCount] < 0)
|
||||||
|
break;
|
||||||
|
if(heaterCount > 0)
|
||||||
|
{
|
||||||
|
heaters = new int[heaterCount];
|
||||||
|
for(int8_t heater = 0; heater < heaterCount; heater++)
|
||||||
|
heaters[heater] = h[heater];
|
||||||
|
}
|
||||||
|
|
||||||
|
x = 0.0;
|
||||||
|
y = 0.0;
|
||||||
|
z = 0.0;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Add a tool to the end of the linked list.
|
||||||
|
// (We must already be in it.)
|
||||||
|
|
||||||
|
void Tool::AddTool(Tool* t)
|
||||||
|
{
|
||||||
|
Tool* last = this;
|
||||||
|
Tool* n = next;
|
||||||
|
while(n)
|
||||||
|
{
|
||||||
|
last = n;
|
||||||
|
n = Next();
|
||||||
|
}
|
||||||
|
t->next = NULL; // Defensive...
|
||||||
|
last->next = t;
|
||||||
|
}
|
||||||
|
|
||||||
|
void Tool::Activate(Tool* currentlyActive)
|
||||||
|
{
|
||||||
|
if(active)
|
||||||
|
return;
|
||||||
|
if(currentlyActive)
|
||||||
|
currentlyActive->Standby();
|
||||||
|
for(int8_t heater = 0; heater < heaterCount; heater++)
|
||||||
|
reprap.GetHeat()->Activate(heaters[heater]);
|
||||||
|
active = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
void Tool::Standby()
|
||||||
|
{
|
||||||
|
if(!active)
|
||||||
|
return;
|
||||||
|
for(int8_t heater = 0; heater < heaterCount; heater++)
|
||||||
|
reprap.GetHeat()->Standby(heaters[heater]);
|
||||||
|
active = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
void Tool::SetVariables(float xx, float yy, float zz, float* standbyTemperatures, float* activeTemperatures)
|
||||||
|
{
|
||||||
|
x = xx;
|
||||||
|
y = yy;
|
||||||
|
z = zz;
|
||||||
|
for(int8_t heater = 0; heater < heaterCount; heater++)
|
||||||
|
{
|
||||||
|
reprap.GetHeat()->SetActiveTemperature(heaters[heater], activeTemperatures[heater]);
|
||||||
|
reprap.GetHeat()->SetStandbyTemperature(heaters[heater], standbyTemperatures[heater]);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
78
Tool.h
Normal file
78
Tool.h
Normal file
|
@ -0,0 +1,78 @@
|
||||||
|
/****************************************************************************************************
|
||||||
|
|
||||||
|
RepRapFirmware - Tool
|
||||||
|
|
||||||
|
This class implements a tool in the RepRap machine, usually (though not necessarily) an extruder.
|
||||||
|
|
||||||
|
Tools may have zero or more drives associated with them and zero or more heaters. There are a fixed number
|
||||||
|
of tools in a given RepRap, with fixed heaters and drives. All this is specified on reboot, and cannot
|
||||||
|
be altered dynamically. This restriction may be lifted in the future. Tool descriptions are stored in
|
||||||
|
GCode macros that are loaded on reboot.
|
||||||
|
|
||||||
|
-----------------------------------------------------------------------------------------------------
|
||||||
|
|
||||||
|
Version 0.1
|
||||||
|
|
||||||
|
Created on: Apr 11, 2014
|
||||||
|
|
||||||
|
Adrian Bowyer
|
||||||
|
RepRap Professional Ltd
|
||||||
|
http://reprappro.com
|
||||||
|
|
||||||
|
Licence: GPL
|
||||||
|
|
||||||
|
****************************************************************************************************/
|
||||||
|
|
||||||
|
#ifndef TOOL_H_
|
||||||
|
#define TOOL_H_
|
||||||
|
|
||||||
|
class Tool
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
|
||||||
|
Tool(int tNum, int d[], int h[]);
|
||||||
|
|
||||||
|
friend class RepRap;
|
||||||
|
|
||||||
|
protected:
|
||||||
|
|
||||||
|
Tool* Next();
|
||||||
|
int Number();
|
||||||
|
void Activate(Tool* currentlyActive);
|
||||||
|
void Standby();
|
||||||
|
void AddTool(Tool* t);
|
||||||
|
void SetVariables(float xx, float yy, float zz, float* standbyTemperatures, float* activeTemperatures);
|
||||||
|
void GetOffset(float& xx, float& yy, float& zz);
|
||||||
|
|
||||||
|
private:
|
||||||
|
|
||||||
|
int myNumber;
|
||||||
|
int* drives;
|
||||||
|
int driveCount;
|
||||||
|
int* heaters;
|
||||||
|
int heaterCount;
|
||||||
|
Tool* next;
|
||||||
|
float x, y, z;
|
||||||
|
bool active;
|
||||||
|
};
|
||||||
|
|
||||||
|
inline Tool* Tool::Next()
|
||||||
|
{
|
||||||
|
return next;
|
||||||
|
}
|
||||||
|
|
||||||
|
inline int Tool::Number()
|
||||||
|
{
|
||||||
|
return myNumber;
|
||||||
|
}
|
||||||
|
|
||||||
|
inline void Tool::GetOffset(float& xx, float& yy, float& zz)
|
||||||
|
{
|
||||||
|
xx = x;
|
||||||
|
yy = y;
|
||||||
|
zz = z;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#endif /* TOOL_H_ */
|
Reference in a new issue