Hooks added for (I hope) the final and complete set of all parameter-changing
M Codes that we will need. Network initialisation delayed until after the config.g file is run, to allow machine name etc to be set from that.
This commit is contained in:
parent
fa9b0d1478
commit
e8eafeda22
8 changed files with 197 additions and 81 deletions
186
GCodes.cpp
186
GCodes.cpp
|
@ -5,6 +5,10 @@ RepRapFirmware - G Codes
|
||||||
This class interprets G Codes from one or more sources, and calls the functions in Move, Heat etc
|
This class interprets G Codes from one or more sources, and calls the functions in Move, Heat etc
|
||||||
that drive the machine to do what the G Codes command.
|
that drive the machine to do what the G Codes command.
|
||||||
|
|
||||||
|
Most of the functions in here are designed not to wait, and they return a boolean. When you want them to do
|
||||||
|
something, you call them. If they return false, the machine can't do what you want yet. So you go away
|
||||||
|
and do something else. Then you try again. If they return true, the thing you wanted done has been done.
|
||||||
|
|
||||||
-----------------------------------------------------------------------------------------------------
|
-----------------------------------------------------------------------------------------------------
|
||||||
|
|
||||||
Version 0.1
|
Version 0.1
|
||||||
|
@ -45,7 +49,6 @@ void GCodes::Init()
|
||||||
fileGCode->SetFinished(true);
|
fileGCode->SetFinished(true);
|
||||||
serialGCode->SetFinished(true);
|
serialGCode->SetFinished(true);
|
||||||
moveAvailable = false;
|
moveAvailable = false;
|
||||||
// heatAvailable = false;
|
|
||||||
drivesRelative = true;
|
drivesRelative = true;
|
||||||
axesRelative = false;
|
axesRelative = false;
|
||||||
checkEndStops = false;
|
checkEndStops = false;
|
||||||
|
@ -59,9 +62,6 @@ void GCodes::Init()
|
||||||
homeY = false;
|
homeY = false;
|
||||||
homeZ = false;
|
homeZ = false;
|
||||||
homeZFinalMove = false;
|
homeZFinalMove = false;
|
||||||
// homeXQueued = false;
|
|
||||||
// homeYQueued = false;
|
|
||||||
// homeZQueued = false;
|
|
||||||
dwellWaiting = false;
|
dwellWaiting = false;
|
||||||
stackPointer = 0;
|
stackPointer = 0;
|
||||||
selectedHead = -1;
|
selectedHead = -1;
|
||||||
|
@ -71,7 +71,6 @@ void GCodes::Init()
|
||||||
zProbesSet = false;
|
zProbesSet = false;
|
||||||
probeCount = 0;
|
probeCount = 0;
|
||||||
cannedCycleMoveCount = 0;
|
cannedCycleMoveCount = 0;
|
||||||
// probeMoveQueued = false;
|
|
||||||
cannedCycleMoveQueued = false;
|
cannedCycleMoveQueued = false;
|
||||||
active = true;
|
active = true;
|
||||||
dwellTime = platform->Time();
|
dwellTime = platform->Time();
|
||||||
|
@ -84,6 +83,14 @@ void GCodes::Spin()
|
||||||
|
|
||||||
char b;
|
char b;
|
||||||
|
|
||||||
|
// Check each of the sources of G Codes (web, serial, and file) to
|
||||||
|
// see if what they are doing has been done. If it hasn't, return without
|
||||||
|
// looking at anything else.
|
||||||
|
//
|
||||||
|
// Note the order establishes a priority: web first, then serial, and file
|
||||||
|
// last. If file weren't last, then the others would never get a look in when
|
||||||
|
// a file was being printed.
|
||||||
|
|
||||||
if(!webGCode->Finished())
|
if(!webGCode->Finished())
|
||||||
{
|
{
|
||||||
webGCode->SetFinished(ActOnGcode(webGCode));
|
webGCode->SetFinished(ActOnGcode(webGCode));
|
||||||
|
@ -102,6 +109,9 @@ void GCodes::Spin()
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Now check if a G Code byte is available from each of the sources
|
||||||
|
// in the same order for the same reason.
|
||||||
|
|
||||||
if(webserver->GCodeAvailable())
|
if(webserver->GCodeAvailable())
|
||||||
{
|
{
|
||||||
if(webGCode->Put(webserver->ReadGCode()))
|
if(webGCode->Put(webserver->ReadGCode()))
|
||||||
|
@ -138,6 +148,11 @@ void GCodes::Diagnostics()
|
||||||
platform->Message(HOST_MESSAGE, "GCodes Diagnostics:\n");
|
platform->Message(HOST_MESSAGE, "GCodes Diagnostics:\n");
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// The wait till everything's done function. If you need the machine to
|
||||||
|
// be idle before you do something (for example homeing an axis, or shutting down) call this
|
||||||
|
// until it returns true. As a side-effect it loads moveBuffer with the last
|
||||||
|
// position and feedrate for you.
|
||||||
|
|
||||||
bool GCodes::AllMovesAreFinishedAndMoveBufferIsLoaded()
|
bool GCodes::AllMovesAreFinishedAndMoveBufferIsLoaded()
|
||||||
{
|
{
|
||||||
// Last one gone?
|
// Last one gone?
|
||||||
|
@ -159,6 +174,9 @@ bool GCodes::AllMovesAreFinishedAndMoveBufferIsLoaded()
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Save (some of) the state of the machine for recovery in the future.
|
||||||
|
// Call repeatedly till it returns true.
|
||||||
|
|
||||||
bool GCodes::Push()
|
bool GCodes::Push()
|
||||||
{
|
{
|
||||||
if(stackPointer >= STACK)
|
if(stackPointer >= STACK)
|
||||||
|
@ -178,6 +196,8 @@ bool GCodes::Push()
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Recover a saved state. Call repeatedly till it returns true.
|
||||||
|
|
||||||
bool GCodes::Pop()
|
bool GCodes::Pop()
|
||||||
{
|
{
|
||||||
if(stackPointer <= 0)
|
if(stackPointer <= 0)
|
||||||
|
@ -209,6 +229,7 @@ bool GCodes::Pop()
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// This function is called for a G Code that makes a move.
|
||||||
// If the Move class can't receive the move (i.e. things have to wait)
|
// If the Move class can't receive the move (i.e. things have to wait)
|
||||||
// this returns false, otherwise true.
|
// this returns false, otherwise true.
|
||||||
|
|
||||||
|
@ -245,26 +266,24 @@ bool GCodes::ReadMove(float* m, bool& ce)
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
bool GCodes::ReadHeat(float* h)
|
|
||||||
{
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
// To execute any move, call this until it returns true.
|
// To execute any move, call this until it returns true.
|
||||||
// false entries in action[] will be ignored.
|
// moveToDo[] entries corresponding with false entries in action[] will
|
||||||
|
// be ignored. Recall that moveToDo[DRIVES] should contain the feedrate
|
||||||
|
// you want (if action[DRIVES] is true).
|
||||||
|
|
||||||
bool GCodes::DoCannedCycleMove(float moveToDo[], bool action[], bool ce)
|
bool GCodes::DoCannedCycleMove(float moveToDo[], bool action[], bool ce)
|
||||||
{
|
{
|
||||||
|
// Is the move already running?
|
||||||
|
|
||||||
if(cannedCycleMoveQueued)
|
if(cannedCycleMoveQueued)
|
||||||
{
|
{ // Yes.
|
||||||
if(!Pop()) // Wait for the move to finish
|
if(!Pop()) // Wait for the move to finish then restore the state
|
||||||
return false;
|
return false;
|
||||||
cannedCycleMoveQueued = false;
|
cannedCycleMoveQueued = false;
|
||||||
return true;
|
return true;
|
||||||
} else
|
} else
|
||||||
{
|
{ // No.
|
||||||
if(!Push()) // Wait for the RepRap to finish whatever it was doing
|
if(!Push()) // Wait for the RepRap to finish whatever it was doing and save it's state
|
||||||
return false;
|
return false;
|
||||||
for(int8_t drive = 0; drive <= DRIVES; drive++)
|
for(int8_t drive = 0; drive <= DRIVES; drive++)
|
||||||
{
|
{
|
||||||
|
@ -278,6 +297,9 @@ bool GCodes::DoCannedCycleMove(float moveToDo[], bool action[], bool ce)
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Home one or more of the axes. Which ones are decided by the
|
||||||
|
// booleans homeX, homeY and homeZ.
|
||||||
|
|
||||||
bool GCodes::DoHome()
|
bool GCodes::DoHome()
|
||||||
{
|
{
|
||||||
// Treat more or less like any other move
|
// Treat more or less like any other move
|
||||||
|
@ -405,6 +427,10 @@ bool GCodes::DoSingleZProbe()
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// This probes multiple points on the bed (usually three in a
|
||||||
|
// triangle), then sets the bed transformation to compensate
|
||||||
|
// for the bed not quite being the plane Z = 0.
|
||||||
|
|
||||||
bool GCodes::DoMultipleZProbe()
|
bool GCodes::DoMultipleZProbe()
|
||||||
{
|
{
|
||||||
if(DoSingleZProbe())
|
if(DoSingleZProbe())
|
||||||
|
@ -420,6 +446,10 @@ bool GCodes::DoMultipleZProbe()
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// This returns the (X, Y) points to probe the bed at probe point count. When probing,
|
||||||
|
// it returns false. If called after probing has ended it returns true, and the Z coordinate
|
||||||
|
// probed is also returned.
|
||||||
|
|
||||||
bool GCodes::GetProbeCoordinates(int count, float& x, float& y, float& z)
|
bool GCodes::GetProbeCoordinates(int count, float& x, float& y, float& z)
|
||||||
{
|
{
|
||||||
switch(count)
|
switch(count)
|
||||||
|
@ -444,6 +474,10 @@ bool GCodes::GetProbeCoordinates(int count, float& x, float& y, float& z)
|
||||||
return zProbesSet;
|
return zProbesSet;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Return the current coordinates as a printable string. Coordinates
|
||||||
|
// are updated at the end of each movement, so this won't tell you
|
||||||
|
// where you are mid-movement.
|
||||||
|
|
||||||
// FIXME - needs to deal with multiple extruders
|
// FIXME - needs to deal with multiple extruders
|
||||||
|
|
||||||
char* GCodes::GetCurrentCoordinates()
|
char* GCodes::GetCurrentCoordinates()
|
||||||
|
@ -455,6 +489,7 @@ char* GCodes::GetCurrentCoordinates()
|
||||||
return scratchString;
|
return scratchString;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Set up a file to print, but don't print it yet.
|
||||||
|
|
||||||
void GCodes::QueueFileToPrint(char* fileName)
|
void GCodes::QueueFileToPrint(char* fileName)
|
||||||
{
|
{
|
||||||
|
@ -463,6 +498,9 @@ void GCodes::QueueFileToPrint(char* fileName)
|
||||||
platform->Message(HOST_MESSAGE, "GCode file not found\n");
|
platform->Message(HOST_MESSAGE, "GCode file not found\n");
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Run the configuration G Code file to set up the machine. Usually just called once
|
||||||
|
// on re-boot.
|
||||||
|
|
||||||
void GCodes::RunConfigurationGCodes()
|
void GCodes::RunConfigurationGCodes()
|
||||||
{
|
{
|
||||||
fileToPrint = platform->GetFileStore(platform->GetSysDir(), platform->GetConfigFile(), false);
|
fileToPrint = platform->GetFileStore(platform->GetSysDir(), platform->GetConfigFile(), false);
|
||||||
|
@ -477,11 +515,11 @@ void GCodes::RunConfigurationGCodes()
|
||||||
|
|
||||||
|
|
||||||
// Function to handle dwell delays. Return true for
|
// Function to handle dwell delays. Return true for
|
||||||
// Dwell finished, false otherwise.
|
// dwell finished, false otherwise.
|
||||||
|
|
||||||
bool GCodes::DoDwell(GCodeBuffer *gb)
|
bool GCodes::DoDwell(GCodeBuffer *gb)
|
||||||
{
|
{
|
||||||
unsigned long dwell;
|
float dwell;
|
||||||
|
|
||||||
if(gb->Seen('P'))
|
if(gb->Seen('P'))
|
||||||
dwell = 0.001*(float)gb->GetLValue(); // P values are in milliseconds; we need seconds
|
dwell = 0.001*(float)gb->GetLValue(); // P values are in milliseconds; we need seconds
|
||||||
|
@ -493,7 +531,7 @@ bool GCodes::DoDwell(GCodeBuffer *gb)
|
||||||
if(!reprap.GetMove()->AllMovesAreFinished())
|
if(!reprap.GetMove()->AllMovesAreFinished())
|
||||||
return false;
|
return false;
|
||||||
|
|
||||||
// Are we already in a dwell?
|
// Are we already in the dwell?
|
||||||
|
|
||||||
if(dwellWaiting)
|
if(dwellWaiting)
|
||||||
{
|
{
|
||||||
|
@ -513,6 +551,9 @@ bool GCodes::DoDwell(GCodeBuffer *gb)
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Set distance offsets and working and standby temperatures for
|
||||||
|
// an extruder. I.e. handle a G10.
|
||||||
|
|
||||||
bool GCodes::SetOffsets(GCodeBuffer *gb)
|
bool GCodes::SetOffsets(GCodeBuffer *gb)
|
||||||
{
|
{
|
||||||
int8_t head;
|
int8_t head;
|
||||||
|
@ -572,6 +613,8 @@ void GCodes::LoadMoveBufferFromGCode(GCodeBuffer *gb)
|
||||||
moveBuffer[DRIVES] = gFeedRate; // We always set it, as Move may have modified the last one.
|
moveBuffer[DRIVES] = gFeedRate; // We always set it, as Move may have modified the last one.
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// This sets positions. I.e. it handles G92.
|
||||||
|
|
||||||
bool GCodes::SetPositions(GCodeBuffer *gb)
|
bool GCodes::SetPositions(GCodeBuffer *gb)
|
||||||
{
|
{
|
||||||
if(!AllMovesAreFinishedAndMoveBufferIsLoaded())
|
if(!AllMovesAreFinishedAndMoveBufferIsLoaded())
|
||||||
|
@ -584,16 +627,26 @@ bool GCodes::SetPositions(GCodeBuffer *gb)
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
void GCodes::DisableDrives()
|
// Does what it says.
|
||||||
|
|
||||||
|
bool GCodes::DisableDrives()
|
||||||
{
|
{
|
||||||
|
if(!AllMovesAreFinishedAndMoveBufferIsLoaded())
|
||||||
|
return false;
|
||||||
for(int8_t drive = 0; drive < DRIVES; drive++)
|
for(int8_t drive = 0; drive < DRIVES; drive++)
|
||||||
platform->Disable(drive);
|
platform->Disable(drive);
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
void GCodes::StandbyHeaters()
|
// Does what it says.
|
||||||
|
|
||||||
|
bool GCodes::StandbyHeaters()
|
||||||
{
|
{
|
||||||
|
if(!AllMovesAreFinishedAndMoveBufferIsLoaded())
|
||||||
|
return false;
|
||||||
for(int8_t heater = 0; heater < DRIVES; heater++)
|
for(int8_t heater = 0; heater < DRIVES; heater++)
|
||||||
reprap.GetHeat()->Standby(heater);
|
reprap.GetHeat()->Standby(heater);
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
// If the GCode to act on is completed, this returns true,
|
// If the GCode to act on is completed, this returns true,
|
||||||
|
@ -649,7 +702,7 @@ bool GCodes::ActOnGcode(GCodeBuffer *gb)
|
||||||
result = DoHome();
|
result = DoHome();
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 31:
|
case 31: // Return the probe value, or set probe variables
|
||||||
if(gb->Seen(gCodeLetters[Z_AXIS]))
|
if(gb->Seen(gCodeLetters[Z_AXIS]))
|
||||||
{
|
{
|
||||||
platform->SetZProbeStopHeight(gb->GetFValue());
|
platform->SetZProbeStopHeight(gb->GetFValue());
|
||||||
|
@ -674,8 +727,8 @@ bool GCodes::ActOnGcode(GCodeBuffer *gb)
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 91: // Relative coordinates
|
case 91: // Relative coordinates
|
||||||
drivesRelative = true;
|
drivesRelative = true; // Non-axis movements (i.e. extruders)
|
||||||
axesRelative = true;
|
axesRelative = true; // Axis movements (i.e. X, Y and Z)
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 92: // Set position
|
case 92: // Set position
|
||||||
|
@ -697,16 +750,19 @@ bool GCodes::ActOnGcode(GCodeBuffer *gb)
|
||||||
{
|
{
|
||||||
case 0: // Stop
|
case 0: // Stop
|
||||||
case 1: // Sleep
|
case 1: // Sleep
|
||||||
if(!AllMovesAreFinishedAndMoveBufferIsLoaded())
|
if(fileBeingPrinted != NULL)
|
||||||
|
{
|
||||||
|
fileToPrint = fileBeingPrinted;
|
||||||
|
fileBeingPrinted = NULL;
|
||||||
|
}
|
||||||
|
if(!DisableDrives())
|
||||||
return false;
|
return false;
|
||||||
DisableDrives();
|
if(!StandbyHeaters())
|
||||||
StandbyHeaters();
|
return false; // Should never happen
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 18: // Motors off
|
case 18: // Motors off
|
||||||
if(!AllMovesAreFinishedAndMoveBufferIsLoaded())
|
result = DisableDrives();
|
||||||
return false;
|
|
||||||
DisableDrives();
|
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 20: // Deprecated...
|
case 20: // Deprecated...
|
||||||
|
@ -744,6 +800,9 @@ bool GCodes::ActOnGcode(GCodeBuffer *gb)
|
||||||
|
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case 85: // Set inactive time
|
||||||
|
break;
|
||||||
|
|
||||||
case 92: // Set steps/mm for each axis
|
case 92: // Set steps/mm for each axis
|
||||||
if(reprap.debug())
|
if(reprap.debug())
|
||||||
platform->GetLine()->Write("Steps/mm: ");
|
platform->GetLine()->Write("Steps/mm: ");
|
||||||
|
@ -787,11 +846,8 @@ bool GCodes::ActOnGcode(GCodeBuffer *gb)
|
||||||
platform->Message(HOST_MESSAGE, "Fan off received\n");
|
platform->Message(HOST_MESSAGE, "Fan off received\n");
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 116: // Wait for everything
|
case 112: // Emergency stop
|
||||||
if(!AllMovesAreFinishedAndMoveBufferIsLoaded())
|
break;
|
||||||
return false;
|
|
||||||
result = reprap.GetHeat()->AllHeatersAtSetTemperatures();
|
|
||||||
break;
|
|
||||||
|
|
||||||
case 111: // Debug level
|
case 111: // Debug level
|
||||||
if(gb->Seen('S'))
|
if(gb->Seen('S'))
|
||||||
|
@ -808,6 +864,12 @@ bool GCodes::ActOnGcode(GCodeBuffer *gb)
|
||||||
result = false;
|
result = false;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case 116: // Wait for everything, especially set temperatures
|
||||||
|
if(!AllMovesAreFinishedAndMoveBufferIsLoaded())
|
||||||
|
return false;
|
||||||
|
result = reprap.GetHeat()->AllHeatersAtSetTemperatures();
|
||||||
|
break;
|
||||||
|
|
||||||
case 120:
|
case 120:
|
||||||
result = Push();
|
result = Push();
|
||||||
break;
|
break;
|
||||||
|
@ -828,6 +890,9 @@ bool GCodes::ActOnGcode(GCodeBuffer *gb)
|
||||||
platform->Message(HOST_MESSAGE, "M127 - valves not yet implemented\n");
|
platform->Message(HOST_MESSAGE, "M127 - valves not yet implemented\n");
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case 135: // Set PID sample interval
|
||||||
|
break;
|
||||||
|
|
||||||
case 140: // Set bed temperature
|
case 140: // Set bed temperature
|
||||||
if(gb->Seen('S'))
|
if(gb->Seen('S'))
|
||||||
{
|
{
|
||||||
|
@ -851,11 +916,11 @@ bool GCodes::ActOnGcode(GCodeBuffer *gb)
|
||||||
}else{
|
}else{
|
||||||
value = -1;
|
value = -1;
|
||||||
}
|
}
|
||||||
float accel = platform->Acceleration(i, value);
|
platform->SetAcceleration(i, value);
|
||||||
if(reprap.debug())
|
if(reprap.debug())
|
||||||
{
|
{
|
||||||
platform->GetLine()->Write(gCodeLetters[i]);
|
platform->GetLine()->Write(gCodeLetters[i]);
|
||||||
platform->GetLine()->Write(ftoa(NULL,accel,1));
|
platform->GetLine()->Write(ftoa(NULL,platform->Acceleration(i),1));
|
||||||
platform->GetLine()->Write(" ");
|
platform->GetLine()->Write(" ");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -863,12 +928,42 @@ bool GCodes::ActOnGcode(GCodeBuffer *gb)
|
||||||
platform->GetLine()->Write("\n");
|
platform->GetLine()->Write("\n");
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 906: // Motor currents
|
case 203: // Set maximum feedrates
|
||||||
|
break;
|
||||||
|
|
||||||
|
case 205: //M205 advanced settings: minimum travel speed S=while printing T=travel only, B=minimum segment time X= maximum xy jerk, Z=maximum Z jerk
|
||||||
|
break;
|
||||||
|
|
||||||
|
case 208: // Set maximum axis lengths
|
||||||
|
break;
|
||||||
|
|
||||||
|
case 210: // Set homing feedrates
|
||||||
|
break;
|
||||||
|
|
||||||
|
case 301: // Set PID values
|
||||||
|
break;
|
||||||
|
|
||||||
|
case 302: // Allow cold extrudes
|
||||||
|
break;
|
||||||
|
|
||||||
|
case 304: // Set thermistor parameters
|
||||||
|
break;
|
||||||
|
|
||||||
|
case 500: // Set password
|
||||||
|
break;
|
||||||
|
|
||||||
|
case 501: // Set machine name
|
||||||
|
break;
|
||||||
|
|
||||||
|
case 502: // Set IP address
|
||||||
|
break;
|
||||||
|
|
||||||
|
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]))
|
if(gb->Seen(gCodeLetters[i]))
|
||||||
{
|
{
|
||||||
value = gb->GetFValue();
|
value = gb->GetFValue(); // mA
|
||||||
platform->SetMotorCurrent(i, value);
|
platform->SetMotorCurrent(i, value);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -892,7 +987,7 @@ bool GCodes::ActOnGcode(GCodeBuffer *gb)
|
||||||
for(int8_t i = AXES; i < DRIVES; i++)
|
for(int8_t i = AXES; i < DRIVES; i++)
|
||||||
{
|
{
|
||||||
if(selectedHead == i - AXES)
|
if(selectedHead == i - AXES)
|
||||||
reprap.GetHeat()->Standby(selectedHead + 1); // 0 is the Bed
|
reprap.GetHeat()->Standby(selectedHead + 1); // + 1 because 0 is the Bed
|
||||||
}
|
}
|
||||||
for(int8_t i = AXES; i < DRIVES; i++)
|
for(int8_t i = AXES; i < DRIVES; i++)
|
||||||
{
|
{
|
||||||
|
@ -923,6 +1018,8 @@ bool GCodes::ActOnGcode(GCodeBuffer *gb)
|
||||||
|
|
||||||
//*************************************************************************************
|
//*************************************************************************************
|
||||||
|
|
||||||
|
// This class stores a single G Code and provides functions to allow it to be parsed
|
||||||
|
|
||||||
GCodeBuffer::GCodeBuffer(Platform* p, char* id)
|
GCodeBuffer::GCodeBuffer(Platform* p, char* id)
|
||||||
{
|
{
|
||||||
platform = p;
|
platform = p;
|
||||||
|
@ -936,6 +1033,9 @@ void GCodeBuffer::Init()
|
||||||
inComment = false;
|
inComment = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Add a byte to the code being assembled. If false is returned, the code is
|
||||||
|
// not yet complete. If true, it is complete and ready to be acted upon.
|
||||||
|
|
||||||
bool GCodeBuffer::Put(char c)
|
bool GCodeBuffer::Put(char c)
|
||||||
{
|
{
|
||||||
bool result = false;
|
bool result = false;
|
||||||
|
@ -987,7 +1087,7 @@ bool GCodeBuffer::Seen(char c)
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Get a float after a G Code letter
|
// Get a float after a G Code letter found by a call to Seen()
|
||||||
|
|
||||||
float GCodeBuffer::GetFValue()
|
float GCodeBuffer::GetFValue()
|
||||||
{
|
{
|
||||||
|
@ -1007,6 +1107,10 @@ float GCodeBuffer::GetFValue()
|
||||||
// be -1. It absorbs "M/Gnnn " (including the space) from the
|
// be -1. It absorbs "M/Gnnn " (including the space) from the
|
||||||
// start and returns a pointer to the next location.
|
// start and returns a pointer to the next location.
|
||||||
|
|
||||||
|
// It would be nice if the string was preceded by (say) 'S', but
|
||||||
|
// for legacy compatibility (M code to queue a file) that can't
|
||||||
|
// be done.
|
||||||
|
|
||||||
char* GCodeBuffer::GetString()
|
char* GCodeBuffer::GetString()
|
||||||
{
|
{
|
||||||
readPointer = 0;
|
readPointer = 0;
|
||||||
|
|
7
GCodes.h
7
GCodes.h
|
@ -26,7 +26,7 @@ Licence: GPL
|
||||||
|
|
||||||
#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
|
||||||
|
|
||||||
// Small class to hold an individual GCode
|
// Small class to hold an individual GCode and provide functions to allow it to be parsed
|
||||||
|
|
||||||
class GCodeBuffer
|
class GCodeBuffer
|
||||||
{
|
{
|
||||||
|
@ -67,7 +67,6 @@ class GCodes
|
||||||
void Exit();
|
void Exit();
|
||||||
void RunConfigurationGCodes();
|
void RunConfigurationGCodes();
|
||||||
bool ReadMove(float* m, bool& ce);
|
bool ReadMove(float* m, bool& ce);
|
||||||
bool ReadHeat(float* h);
|
|
||||||
void QueueFileToPrint(char* fileName);
|
void QueueFileToPrint(char* fileName);
|
||||||
bool GetProbeCoordinates(int count, float& x, float& y, float& z);
|
bool GetProbeCoordinates(int count, float& x, float& y, float& z);
|
||||||
char* GetCurrentCoordinates();
|
char* GetCurrentCoordinates();
|
||||||
|
@ -90,8 +89,8 @@ class GCodes
|
||||||
bool NoHome();
|
bool NoHome();
|
||||||
bool Push();
|
bool Push();
|
||||||
bool Pop();
|
bool Pop();
|
||||||
void DisableDrives();
|
bool DisableDrives();
|
||||||
void StandbyHeaters();
|
bool StandbyHeaters();
|
||||||
|
|
||||||
int8_t Heater(int8_t head);
|
int8_t Heater(int8_t head);
|
||||||
Platform* platform;
|
Platform* platform;
|
||||||
|
|
2
Move.cpp
2
Move.cpp
|
@ -45,7 +45,7 @@ Move::Move(Platform* p, GCodes* g)
|
||||||
lookAheadRingGetPointer = new LookAhead(this, platform, lookAheadRingGetPointer);
|
lookAheadRingGetPointer = new LookAhead(this, platform, lookAheadRingGetPointer);
|
||||||
lookAheadRingAddPointer->next = lookAheadRingGetPointer;
|
lookAheadRingAddPointer->next = lookAheadRingGetPointer;
|
||||||
|
|
||||||
// Set the lookahead backwards pointers
|
// Set the lookahead backwards pointers (some oxymoron, surely?)
|
||||||
|
|
||||||
lookAheadRingGetPointer = lookAheadRingAddPointer;
|
lookAheadRingGetPointer = lookAheadRingAddPointer;
|
||||||
for(i = 0; i <= LOOK_AHEAD_RING_LENGTH; i++)
|
for(i = 0; i <= LOOK_AHEAD_RING_LENGTH; i++)
|
||||||
|
|
12
Platform.cpp
12
Platform.cpp
|
@ -64,7 +64,7 @@ void Platform::Init()
|
||||||
|
|
||||||
line->Init();
|
line->Init();
|
||||||
|
|
||||||
network->Init();
|
//network->Init();
|
||||||
|
|
||||||
massStorage->Init();
|
massStorage->Init();
|
||||||
|
|
||||||
|
@ -93,15 +93,10 @@ 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;
|
||||||
// zProbeGradient = Z_PROBE_GRADIENT;
|
|
||||||
// zProbeConstant = Z_PROBE_CONSTANT;
|
|
||||||
zProbePin = Z_PROBE_PIN;
|
zProbePin = Z_PROBE_PIN;
|
||||||
zProbeCount = 0;
|
zProbeCount = 0;
|
||||||
zProbeSum = 0;
|
zProbeSum = 0;
|
||||||
zProbeValue = 0;
|
zProbeValue = 0;
|
||||||
// zProbeStarting = false;
|
|
||||||
// zProbeHigh = Z_PROBE_HIGH;
|
|
||||||
// zProbeLow = Z_PROBE_LOW;
|
|
||||||
zProbeADValue = Z_PROBE_AD_VALUE;
|
zProbeADValue = Z_PROBE_AD_VALUE;
|
||||||
zProbeStopHeight = Z_PROBE_STOP_HEIGHT;
|
zProbeStopHeight = Z_PROBE_STOP_HEIGHT;
|
||||||
|
|
||||||
|
@ -197,6 +192,11 @@ void Platform::Init()
|
||||||
active = true;
|
active = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void Platform::StartNetwork()
|
||||||
|
{
|
||||||
|
network->Init();
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
//int zcount; // NASTY - FIX ME
|
//int zcount; // NASTY - FIX ME
|
||||||
|
|
||||||
|
|
37
Platform.h
37
Platform.h
|
@ -151,24 +151,6 @@ Licence: GPL
|
||||||
|
|
||||||
// Networking
|
// Networking
|
||||||
|
|
||||||
// Enter a MAC address and IP address for your controller below.
|
|
||||||
// The IP address will be dependent on your local network:
|
|
||||||
//#define MAC { 0xDE, 0xAD, 0xBE, 0xEF, 0xFE, 0xED };
|
|
||||||
//#define MAC_BYTES 6
|
|
||||||
//
|
|
||||||
//#define IP0 192
|
|
||||||
//#define IP1 168
|
|
||||||
//#define IP2 1
|
|
||||||
//#define IP3 14
|
|
||||||
//
|
|
||||||
//#define IP_BYTES 4
|
|
||||||
|
|
||||||
//#define ETH_B_PIN 10
|
|
||||||
|
|
||||||
// port 80 is default for HTTP
|
|
||||||
|
|
||||||
//#define HTTP_PORT 80
|
|
||||||
|
|
||||||
// Seconds to wait after serving a page
|
// Seconds to wait after serving a page
|
||||||
|
|
||||||
#define CLIENT_CLOSE_DELAY 0.002
|
#define CLIENT_CLOSE_DELAY 0.002
|
||||||
|
@ -425,6 +407,7 @@ class Platform
|
||||||
|
|
||||||
MassStorage* GetMassStorage();
|
MassStorage* GetMassStorage();
|
||||||
FileStore* GetFileStore(char* directory, char* fileName, bool write);
|
FileStore* GetFileStore(char* directory, char* fileName, bool write);
|
||||||
|
void StartNetwork();
|
||||||
char* GetWebDir(); // Where the htm etc files are
|
char* GetWebDir(); // Where the htm etc files are
|
||||||
char* GetGCodeDir(); // Where the gcodes are
|
char* GetGCodeDir(); // Where the gcodes are
|
||||||
char* GetSysDir(); // Where the system files are
|
char* GetSysDir(); // Where the system files are
|
||||||
|
@ -442,7 +425,8 @@ class Platform
|
||||||
void SetMotorCurrent(byte drive, float current);
|
void SetMotorCurrent(byte drive, float current);
|
||||||
float DriveStepsPerUnit(int8_t drive);
|
float DriveStepsPerUnit(int8_t drive);
|
||||||
void SetDriveStepsPerUnit(int8_t drive, float value);
|
void SetDriveStepsPerUnit(int8_t drive, float value);
|
||||||
float Acceleration(int8_t drive, float value);
|
float Acceleration(int8_t drive);
|
||||||
|
void SetAcceleration(int8_t drive, float value);
|
||||||
float MaxFeedrate(int8_t drive);
|
float MaxFeedrate(int8_t drive);
|
||||||
float InstantDv(int8_t drive);
|
float InstantDv(int8_t drive);
|
||||||
float HomeFeedRate(int8_t drive);
|
float HomeFeedRate(int8_t drive);
|
||||||
|
@ -458,10 +442,6 @@ class Platform
|
||||||
|
|
||||||
float GetTemperature(int8_t heater); // Result is in degrees celsius
|
float GetTemperature(int8_t heater); // Result is in degrees celsius
|
||||||
void SetHeater(int8_t heater, const float& power); // power is a fraction in [0,1]
|
void SetHeater(int8_t heater, const float& power); // power is a fraction in [0,1]
|
||||||
//void SetStandbyTemperature(int8_t heater, const float& t);
|
|
||||||
//void SetActiveTemperature(int8_t heater, const float& t);
|
|
||||||
//float StandbyTemperature(int8_t heater);
|
|
||||||
//float ActiveTemperature(int8_t heater);
|
|
||||||
float PidKp(int8_t heater);
|
float PidKp(int8_t heater);
|
||||||
float PidKi(int8_t heater);
|
float PidKi(int8_t heater);
|
||||||
float PidKd(int8_t heater);
|
float PidKd(int8_t heater);
|
||||||
|
@ -631,11 +611,14 @@ inline void Platform::SetDriveStepsPerUnit(int8_t drive, float value)
|
||||||
driveStepsPerUnit[drive] = value;
|
driveStepsPerUnit[drive] = value;
|
||||||
}
|
}
|
||||||
|
|
||||||
inline float Platform::Acceleration(int8_t drive, float value = -1)
|
inline float Platform::Acceleration(int8_t drive)
|
||||||
{
|
{
|
||||||
if(drive >= 0 && drive < DRIVES && value > 0)
|
return accelerations[drive];
|
||||||
accelerations[drive] = value;
|
}
|
||||||
return accelerations[drive];
|
|
||||||
|
inline void Platform::SetAcceleration(int8_t drive, float value)
|
||||||
|
{
|
||||||
|
accelerations[drive] = value;
|
||||||
}
|
}
|
||||||
|
|
||||||
inline float Platform::InstantDv(int8_t drive)
|
inline float Platform::InstantDv(int8_t drive)
|
||||||
|
|
|
@ -177,6 +177,7 @@ void RepRap::Init()
|
||||||
heat->Init();
|
heat->Init();
|
||||||
active = true;
|
active = true;
|
||||||
gCodes->RunConfigurationGCodes();
|
gCodes->RunConfigurationGCodes();
|
||||||
|
platform->StartNetwork(); // Need to do this hare, as the configuration GCodes may set IP address etc.
|
||||||
platform->Message(HOST_MESSAGE, "RepRapPro RepRap Firmware (Re)Started\n");
|
platform->Message(HOST_MESSAGE, "RepRapPro RepRap Firmware (Re)Started\n");
|
||||||
// platform->Message(HOST_MESSAGE, "Free memory: ");
|
// platform->Message(HOST_MESSAGE, "Free memory: ");
|
||||||
// sprintf(scratchString,"%d\n",platform->GetFreeMemory());
|
// sprintf(scratchString,"%d\n",platform->GetFreeMemory());
|
||||||
|
|
|
@ -288,10 +288,36 @@ Click a file to <span data-bind="text: fileAction"></span><br>
|
||||||
|
|
||||||
<hr>
|
<hr>
|
||||||
|
|
||||||
|
<form action="reprap.htm?upload=myFile"
|
||||||
|
enctype="multipart/form-data" method="post">
|
||||||
|
<p>
|
||||||
|
Upload a G Code file: <br>
|
||||||
|
<input type="file" name="datafile" size="40">
|
||||||
|
</p>
|
||||||
|
<div>
|
||||||
|
<input type="submit" value="Upload">
|
||||||
|
</div>
|
||||||
|
</form>
|
||||||
|
|
||||||
|
<!--
|
||||||
|
<form onSubmit="return checkFileName(this)" action="upload.htm"
|
||||||
|
enctype="multipart/form-data" method="post">
|
||||||
|
<p>
|
||||||
|
Upload a G Code file :<br>
|
||||||
|
<input type="file" name="datafile" size="40">
|
||||||
|
</p>
|
||||||
|
<div>
|
||||||
|
<input type="submit" value="Upload">
|
||||||
|
</div>
|
||||||
|
</form>
|
||||||
|
-->
|
||||||
|
<!--
|
||||||
<form data-bind="submit: function(data, event) { uploadGCode(data, event) }">
|
<form data-bind="submit: function(data, event) { uploadGCode(data, event) }">
|
||||||
Upload a G Code file :
|
Upload a G Code file :
|
||||||
<input type="file" name="datafile" size="30"><button type="submit">Upload</button>
|
<input type="file" name="datafile" size="30"><button type="submit">Upload</button>
|
||||||
</form>
|
</form>
|
||||||
|
-->
|
||||||
|
|
||||||
<br>
|
<br>
|
||||||
<button data-bind="text: deleteButton, click: function(data, event) { deleteFile(data, event) }"></button>
|
<button data-bind="text: deleteButton, click: function(data, event) { deleteFile(data, event) }"></button>
|
||||||
</div>
|
</div>
|
||||||
|
|
|
@ -327,6 +327,9 @@ void Webserver::GetJsonResponse(char* request)
|
||||||
strcat(jsonResponse, ftoa(0, liveCoordinates[drive], 2));
|
strcat(jsonResponse, ftoa(0, liveCoordinates[drive], 2));
|
||||||
strcat(jsonResponse, "\",");
|
strcat(jsonResponse, "\",");
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// FIXME: should loop through all Es
|
||||||
|
|
||||||
strcat(jsonResponse, "\"");
|
strcat(jsonResponse, "\"");
|
||||||
strcat(jsonResponse, ftoa(0, liveCoordinates[AXES], 4));
|
strcat(jsonResponse, ftoa(0, liveCoordinates[AXES], 4));
|
||||||
strcat(jsonResponse, "\"");
|
strcat(jsonResponse, "\"");
|
||||||
|
|
Reference in a new issue