Welcome to mirror list, hosted at ThFree Co, Russian Federation.

github.com/Duet3D/RepRapFirmware.git - Unnamed repository; edit this file 'description' to name the repository.
summaryrefslogtreecommitdiff
path: root/src
diff options
context:
space:
mode:
authorDavid Crocker <dcrocker@eschertech.com>2017-09-21 21:27:40 +0300
committerDavid Crocker <dcrocker@eschertech.com>2017-09-21 21:29:52 +0300
commit370060e84b9f30dd5d9edff817baaba154106c7c (patch)
treeaa399d680427189e6a8c62572c304b9b16118406 /src
parent77d6718860bd6ad383d29e0708c600fcba855116 (diff)
Version 1.20 alpha 2
Removed define of printf=iprintf in build settings Removed Platform::Time() function, use millis() or millis64() instead Added event logging to SD card. MessageType is now a bitmap. Implemented M929. Enable pullup resistors on endstops 10 and 11 SCARA printers can now use the manual bed levelling assistant When using the manual bed levelling assitant, don't give an error if the bed screw corrections were out of range, and always leave the first screw alone M552 now supports connection to a specified SSID M572 now allows multiple D values Thermocouple type letter in M305 command may now be in lower case Bug fix: G29 bed probing on a SCARA printer gave spurious "not reachable" warnings and skipped probe points Protect against a dud command line containing the letter M being interpreted as a M0 command Fix reference to towers in the error message when trying to move a SCARA printer before homing it When updating firmware, warn that USB will disconnect Fix duplicate error messatge when opening a gcode file fails
Diffstat (limited to 'src')
-rw-r--r--src/Configuration.h8
-rw-r--r--src/Duet/Network.cpp29
-rw-r--r--src/Duet/Network.h2
-rw-r--r--src/Duet/NetworkTransaction.cpp22
-rw-r--r--src/Duet/Webserver.cpp70
-rw-r--r--src/Duet/Webserver.h2
-rw-r--r--src/DuetNG/DuetEthernet/Network.cpp13
-rw-r--r--src/DuetNG/DuetEthernet/Network.h2
-rw-r--r--src/DuetNG/DuetWiFi/Network.cpp50
-rw-r--r--src/DuetNG/DuetWiFi/Network.h7
-rw-r--r--src/DuetNG/DuetWiFi/WifiFirmwareUploader.cpp12
-rw-r--r--src/DuetNG/FirmwareUpdater.cpp6
-rw-r--r--src/DuetNG/FtpResponder.cpp10
-rw-r--r--src/DuetNG/HttpResponder.cpp43
-rw-r--r--src/DuetNG/NetworkResponder.cpp9
-rw-r--r--src/DuetNG/NetworkResponder.h2
-rw-r--r--src/DuetNG/TelnetResponder.cpp4
-rw-r--r--src/GCodes/GCodeBuffer.cpp45
-rw-r--r--src/GCodes/GCodeQueue.cpp2
-rw-r--r--src/GCodes/GCodes.cpp181
-rw-r--r--src/GCodes/GCodes.h5
-rw-r--r--src/GCodes/GCodes2.cpp125
-rw-r--r--src/Heating/Heat.cpp2
-rw-r--r--src/Heating/Heat.h2
-rw-r--r--src/Heating/Pid.cpp44
-rw-r--r--src/Heating/Sensors/CurrentLoopTemperatureSensor.cpp2
-rw-r--r--src/Heating/Sensors/RtdSensor31865.cpp2
-rw-r--r--src/Heating/Sensors/ThermocoupleSensor31856.cpp4
-rw-r--r--src/Libraries/General/IP4String.cpp22
-rw-r--r--src/Libraries/General/IP4String.h25
-rw-r--r--src/Libraries/General/StringRef.cpp10
-rw-r--r--src/Libraries/General/StringRef.h1
-rw-r--r--src/Logger.cpp142
-rw-r--r--src/Logger.h37
-rw-r--r--src/MessageType.h39
-rw-r--r--src/Movement/BedProbing/RandomProbePointSet.cpp13
-rw-r--r--src/Movement/BedProbing/RandomProbePointSet.h2
-rw-r--r--src/Movement/DDA.cpp4
-rw-r--r--src/Movement/Kinematics/Kinematics.cpp12
-rw-r--r--src/Movement/Kinematics/Kinematics.h10
-rw-r--r--src/Movement/Kinematics/LinearDeltaKinematics.cpp10
-rw-r--r--src/Movement/Kinematics/LinearDeltaKinematics.h2
-rw-r--r--src/Movement/Kinematics/ScaraKinematics.cpp8
-rw-r--r--src/Movement/Kinematics/ScaraKinematics.h5
-rw-r--r--src/Movement/Kinematics/ZLeadscrewKinematics.cpp56
-rw-r--r--src/Movement/Kinematics/ZLeadscrewKinematics.h6
-rw-r--r--src/Movement/Move.cpp61
-rw-r--r--src/Movement/Move.h12
-rw-r--r--src/OutputMemory.cpp30
-rw-r--r--src/OutputMemory.h4
-rw-r--r--src/Platform.cpp468
-rw-r--r--src/Platform.h34
-rw-r--r--src/PrintMonitor.cpp42
-rw-r--r--src/PrintMonitor.h6
-rw-r--r--src/RepRap.cpp70
-rw-r--r--src/RepRap.h4
-rw-r--r--src/RepRapFirmware.cpp2
-rw-r--r--src/Scanner.cpp20
-rw-r--r--src/Scanner.h2
-rw-r--r--src/Storage/FileData.h5
-rw-r--r--src/Storage/FileStore.cpp56
-rw-r--r--src/Storage/FileStore.h9
-rw-r--r--src/Storage/MassStorage.cpp18
-rw-r--r--src/Tools/Filament.cpp4
-rw-r--r--src/Tools/Tool.cpp4
-rw-r--r--src/Version.h4
66 files changed, 1223 insertions, 741 deletions
diff --git a/src/Configuration.h b/src/Configuration.h
index eb740ce7..3828be15 100644
--- a/src/Configuration.h
+++ b/src/Configuration.h
@@ -44,9 +44,10 @@ const float NEARLY_ABS_ZERO = -273.0; // Celsius
const float ROOM_TEMPERATURE = 21.0; // Celsius
// Timeouts
-const float LONG_TIME = 300.0; // Seconds
+const uint32_t LongTime = 300000; // Milliseconds (5 minutes)
const uint32_t MinimumWarningInterval = 4000; // Milliseconds
const uint32_t FanCheckInterval = 500; // Milliseconds
+const uint32_t LogFlushInterval = 15000; // Milliseconds
const uint32_t DriverCoolingTimeout = 4000; // Milliseconds
const float DefaultMessageTimeout = 10.0; // How long a message is displayed by default, in seconds
@@ -191,8 +192,8 @@ const float DefaultRetractLength = 2.0;
const float DefaultArcSegmentLength = 0.2; // G2 and G3 arc movement commands get split into segments this long
-const float DEFAULT_IDLE_TIMEOUT = 30.0; // Seconds
-const float DEFAULT_IDLE_CURRENT_FACTOR = 0.3; // Proportion of normal motor current that we use for idle hold
+const uint32_t DefaultIdleTimeout = 30000; // Milliseconds
+const float DefaultIdleCurrentFactor = 0.3; // Proportion of normal motor current that we use for idle hold
// Triggers
@@ -226,6 +227,7 @@ const unsigned int MaxStackDepth = 5; // Maximum depth of stack
#define CONFIG_FILE "config.g"
#define DEFAULT_FILE "default.g"
+#define DEFAULT_LOG_FILE "eventlog.txt"
#define EOF_STRING "<!-- **EoF** -->"
diff --git a/src/Duet/Network.cpp b/src/Duet/Network.cpp
index af191656..874e79ae 100644
--- a/src/Duet/Network.cpp
+++ b/src/Duet/Network.cpp
@@ -46,6 +46,7 @@
#include "RepRap.h"
#include "Webserver.h"
#include "Version.h"
+#include "Libraries/General/IP4String.h"
extern "C"
{
@@ -160,7 +161,7 @@ static void ethernet_rx_callback(uint32_t ul_status)
static void conn_err(void *arg, err_t err)
{
// Report the error to the monitor
- reprap.GetPlatform().MessageF(HOST_MESSAGE, "Network: Connection error, code %d\n", err);
+ reprap.GetPlatform().MessageF(UsbMessage, "Network: Connection error, code %d\n", err);
// Tell the higher levels about the error
ConnectionState *cs = (ConnectionState*)arg;
@@ -178,7 +179,7 @@ static err_t conn_recv(void *arg, tcp_pcb *pcb, pbuf *p, err_t err)
{
if (cs->pcb != pcb)
{
- reprap.GetPlatform().Message(HOST_MESSAGE, "Network: Mismatched pcb in conn_recv!\n");
+ reprap.GetPlatform().Message(UsbMessage, "Network: Mismatched pcb in conn_recv!\n");
tcp_abort(pcb);
return ERR_ABRT;
}
@@ -281,7 +282,7 @@ void Network::Init()
webserver = new Webserver(&platform, this);
webserver->Init();
- longWait = platform.Time();
+ longWait = millis();
}
void Network::Exit()
@@ -415,7 +416,7 @@ void Network::Spin(bool full)
state = NetworkEstablishingLink;
UnlockLWIP();
- platform.Message(HOST_MESSAGE, "Network down\n");
+ platform.Message(UsbMessage, "Network down\n");
platform.ClassReport(longWait);
return;
}
@@ -450,7 +451,7 @@ void Network::Spin(bool full)
DoMdnsAnnounce();
UnlockLWIP();
- platform.MessageF(HOST_MESSAGE, "Network up, IP=%d.%d.%d.%d\n", ip[0], ip[1], ip[2], ip[3]);
+ platform.MessageF(UsbMessage, "Network up, IP=%s\n", IP4String(ip).c_str());
platform.ClassReport(longWait);
return;
}
@@ -564,7 +565,7 @@ bool Network::ReceiveInput(pbuf *pb, ConnectionState* cs)
NetworkTransaction* r = freeTransactions;
if (r == nullptr)
{
- platform.Message(HOST_MESSAGE, "Network::ReceiveInput() - no free transactions!\n");
+ platform.Message(UsbMessage, "Network::ReceiveInput() - no free transactions!\n");
return false;
}
@@ -583,14 +584,14 @@ ConnectionState *Network::ConnectionAccepted(tcp_pcb *pcb)
ConnectionState *cs = freeConnections;
if (cs == nullptr)
{
- platform.Message(HOST_MESSAGE, "Network::ConnectionAccepted() - no free ConnectionStates!\n");
+ platform.Message(UsbMessage, "Network::ConnectionAccepted() - no free ConnectionStates!\n");
return nullptr;
}
NetworkTransaction* transaction = freeTransactions;
if (transaction == nullptr)
{
- platform.Message(HOST_MESSAGE, "Network::ConnectionAccepted() - no free transactions!\n");
+ platform.Message(UsbMessage, "Network::ConnectionAccepted() - no free transactions!\n");
return nullptr;
}
@@ -723,7 +724,7 @@ bool Network::ConnectionClosedGracefully(ConnectionState *cs)
NetworkTransaction *transaction = freeTransactions;
if (transaction == nullptr)
{
- platform.Message(HOST_MESSAGE, "Network::ConnectionClosedGracefully() - no free transactions!\n");
+ platform.Message(UsbMessage, "Network::ConnectionClosedGracefully() - no free transactions!\n");
return false;
}
@@ -835,11 +836,9 @@ void Network::Enable(int mode, StringRef& reply)
// Get the network state into the reply buffer, returning true if there is some sort of error
bool Network::GetNetworkState(StringRef& reply)
{
- const uint8_t * const config_ip = platform.GetIPAddress();
- const uint8_t * const ipAddress = ethernet_get_ipaddress();
- reply.printf("Network is %s, configured IP address: %u.%u.%u.%u, actual IP address: %u.%u.%u.%u",
- (isEnabled) ? "enabled" : "disabled",
- config_ip[0], config_ip[1], config_ip[2], config_ip[3], ipAddress[0], ipAddress[1], ipAddress[2], ipAddress[3]);
+ reply.printf("Network is %s, configured IP address: %s, actual IP address: %s",
+ (isEnabled) ? "enabled" : "disabled",
+ IP4String(platform.GetIPAddress()).c_str(), IP4String(ethernet_get_ipaddress()).c_str());
return false;
}
@@ -1056,7 +1055,7 @@ bool Network::AcquireTransaction(ConnectionState *cs)
NetworkTransaction *acquiredTransaction = freeTransactions;
if (acquiredTransaction == nullptr)
{
- platform.Message(HOST_MESSAGE, "Network: Could not acquire free transaction!\n");
+ platform.Message(UsbMessage, "Network: Could not acquire free transaction!\n");
return false;
}
freeTransactions = acquiredTransaction->next;
diff --git a/src/Duet/Network.h b/src/Duet/Network.h
index 142f7e63..9d4329b0 100644
--- a/src/Duet/Network.h
+++ b/src/Duet/Network.h
@@ -115,7 +115,7 @@ public:
private:
Platform& platform;
Webserver *webserver;
- float longWait;
+ uint32_t longWait;
void AppendTransaction(NetworkTransaction* volatile * list, NetworkTransaction *r);
void PrependTransaction(NetworkTransaction* volatile * list, NetworkTransaction *r);
diff --git a/src/Duet/NetworkTransaction.cpp b/src/Duet/NetworkTransaction.cpp
index c19bd372..0cdb6352 100644
--- a/src/Duet/NetworkTransaction.cpp
+++ b/src/Duet/NetworkTransaction.cpp
@@ -28,7 +28,7 @@ static err_t conn_poll(void *arg, tcp_pcb *pcb)
sendingRetries++;
if (sendingRetries == TCP_MAX_SEND_RETRIES)
{
- reprap.GetPlatform().MessageF(HOST_MESSAGE, "Network: Could not transmit data after %.1f seconds\n", (float)TCP_WRITE_TIMEOUT / 1000.0);
+ reprap.GetPlatform().MessageF(UsbMessage, "Network: Could not transmit data after %.1f seconds\n", (float)TCP_WRITE_TIMEOUT / 1000.0);
tcp_abort(pcb);
return ERR_ABRT;
}
@@ -39,14 +39,14 @@ static err_t conn_poll(void *arg, tcp_pcb *pcb)
writeResult = tcp_write(pcb, sendingWindow + (sendingWindowSize - sentDataOutstanding), sentDataOutstanding, 0);
if (ERR_IS_FATAL(writeResult))
{
- reprap.GetPlatform().MessageF(HOST_MESSAGE, "Network: Failed to write data in conn_poll (code %d)\n", writeResult);
+ reprap.GetPlatform().MessageF(UsbMessage, "Network: Failed to write data in conn_poll (code %d)\n", writeResult);
tcp_abort(pcb);
return ERR_ABRT;
}
if (writeResult != ERR_OK && reprap.Debug(moduleNetwork))
{
- reprap.GetPlatform().MessageF(HOST_MESSAGE, "Network: tcp_write resulted in error code %d\n", writeResult);
+ reprap.GetPlatform().MessageF(UsbMessage, "Network: tcp_write resulted in error code %d\n", writeResult);
}
}
@@ -56,20 +56,20 @@ static err_t conn_poll(void *arg, tcp_pcb *pcb)
outputResult = tcp_output(pcb);
if (ERR_IS_FATAL(outputResult))
{
- reprap.GetPlatform().MessageF(HOST_MESSAGE, "Network: Failed to output data in conn_poll (code %d)\n", outputResult);
+ reprap.GetPlatform().MessageF(UsbMessage, "Network: Failed to output data in conn_poll (code %d)\n", outputResult);
tcp_abort(pcb);
return ERR_ABRT;
}
if (outputResult != ERR_OK && reprap.Debug(moduleNetwork))
{
- reprap.GetPlatform().MessageF(HOST_MESSAGE, "Network: tcp_output resulted in error code %d\n", outputResult);
+ reprap.GetPlatform().MessageF(UsbMessage, "Network: tcp_output resulted in error code %d\n", outputResult);
}
}
}
else
{
- reprap.GetPlatform().Message(HOST_MESSAGE, "Network: Mismatched pcb in conn_poll!\n");
+ reprap.GetPlatform().Message(UsbMessage, "Network: Mismatched pcb in conn_poll!\n");
}
return ERR_OK;
}
@@ -91,7 +91,7 @@ static err_t conn_sent(void *arg, tcp_pcb *pcb, u16_t len)
}
else
{
- reprap.GetPlatform().Message(HOST_MESSAGE, "Network: Mismatched pcb in conn_sent!\n");
+ reprap.GetPlatform().Message(UsbMessage, "Network: Mismatched pcb in conn_sent!\n");
}
return ERR_OK;
}
@@ -330,7 +330,7 @@ bool NetworkTransaction::Send()
writeResult = tcp_write(cs->pcb, sendingWindow, bytesBeingSent, 0);
if (ERR_IS_FATAL(writeResult))
{
- reprap.GetPlatform().MessageF(HOST_MESSAGE, "Network: Failed to write data in Send (code %d)\n", writeResult);
+ reprap.GetPlatform().MessageF(UsbMessage, "Network: Failed to write data in Send (code %d)\n", writeResult);
tcp_abort(cs->pcb);
return false;
}
@@ -338,14 +338,14 @@ bool NetworkTransaction::Send()
outputResult = tcp_output(cs->pcb);
if (ERR_IS_FATAL(outputResult))
{
- reprap.GetPlatform().MessageF(HOST_MESSAGE, "Network: Failed to output data in Send (code %d)\n", outputResult);
+ reprap.GetPlatform().MessageF(UsbMessage, "Network: Failed to output data in Send (code %d)\n", outputResult);
tcp_abort(cs->pcb);
return false;
}
if (outputResult != ERR_OK && reprap.Debug(moduleNetwork))
{
- reprap.GetPlatform().MessageF(HOST_MESSAGE, "Network: tcp_output resulted in error code %d\n", outputResult);
+ reprap.GetPlatform().MessageF(UsbMessage, "Network: tcp_output resulted in error code %d\n", outputResult);
}
// Set LwIP callbacks for ACK and retransmission handling
@@ -592,7 +592,7 @@ void NetworkTransaction::Discard()
{
if (reprap.Debug(moduleNetwork))
{
- reprap.GetPlatform().Message(HOST_MESSAGE, "Network: Discard() is handling a graceful disconnect\n");
+ reprap.GetPlatform().Message(UsbMessage, "Network: Discard() is handling a graceful disconnect\n");
}
reprap.GetNetwork().ConnectionClosed(cs, false);
}
diff --git a/src/Duet/Webserver.cpp b/src/Duet/Webserver.cpp
index 4fce67d3..da2fc779 100644
--- a/src/Duet/Webserver.cpp
+++ b/src/Duet/Webserver.cpp
@@ -109,7 +109,7 @@ Webserver::Webserver(Platform *p, Network *n) : platform(p), network(n), webserv
void Webserver::Init()
{
// initialise the webserver class
- longWait = platform->Time();
+ longWait = millis();
webserverActive = true;
readingConnection = NoConnection;
@@ -178,7 +178,7 @@ void Webserver::Spin()
case TransactionStatus::acquired: type = "acquired"; break;
default: type = "unknown"; break;
}
- platform->MessageF(HOST_MESSAGE, "Incoming transaction: Type %s at local port %d (remote port %d)\n",
+ platform->MessageF(UsbMessage, "Incoming transaction: Type %s at local port %d (remote port %d)\n",
type, localPort, currentTransaction->GetRemotePort());
}
@@ -233,7 +233,7 @@ void Webserver::Spin()
{
// We failed to find a transaction for a reading connection.
// This should never happen, but if it does, terminate this connection instantly
- platform->Message(HOST_MESSAGE, "Error: Transaction for reading connection not found\n");
+ platform->Message(UsbMessage, "Error: Transaction for reading connection not found\n");
Network::Terminate(readingConnection);
}
network->Unlock(); // unlock LWIP again
@@ -247,7 +247,7 @@ void Webserver::Exit()
ftpInterpreter->CancelUpload();
//telnetInterpreter->CancelUpload(); // Telnet doesn't support fast file uploads
- platform->Message(HOST_MESSAGE, "Webserver class exited.\n");
+ platform->Message(UsbMessage, "Webserver class exited.\n");
webserverActive = false;
}
@@ -308,14 +308,14 @@ void Webserver::ConnectionLost(Connection conn)
}
else
{
- platform->MessageF(GENERIC_MESSAGE, "Error: Webserver should handle disconnect event at local port %d, but no handler was found!\n", localPort);
+ platform->MessageF(GenericMessage, "Error: Webserver should handle disconnect event at local port %d, but no handler was found!\n", localPort);
return;
}
// Print some debug information and notify the protocol interpreter
if (reprap.Debug(moduleWebserver))
{
- platform->MessageF(HOST_MESSAGE, "ConnectionLost called for local port %d (remote port %d)\n", localPort, Network::GetRemotePort(conn));
+ platform->MessageF(UsbMessage, "ConnectionLost called for local port %d (remote port %d)\n", localPort, Network::GetRemotePort(conn));
}
interpreter->ConnectionLost(conn);
@@ -385,7 +385,7 @@ bool ProtocolInterpreter::StartUpload(FileStore *file, const char *fileName)
return true;
}
- platform->Message(GENERIC_MESSAGE, "Error: Could not open file while starting upload!\n");
+ platform->Message(GenericMessage, "Error: Could not open file while starting upload!\n");
return false;
}
@@ -409,14 +409,14 @@ void ProtocolInterpreter::DoFastUpload()
// See if we can output a debug message
if (reprap.Debug(moduleWebserver))
{
- platform->MessageF(HOST_MESSAGE, "Writing %u bytes of upload data\n", len);
+ platform->MessageF(UsbMessage, "Writing %u bytes of upload data\n", len);
}
// Writing data usually takes a while, so keep LwIP running while this is being done
network->Unlock();
if (!fileBeingUploaded.Write(buffer, len))
{
- platform->Message(GENERIC_MESSAGE, "Error: Could not write upload data!\n");
+ platform->Message(GenericMessage, "Error: Could not write upload data!\n");
CancelUpload();
while (!network->Lock());
@@ -438,14 +438,14 @@ bool ProtocolInterpreter::FinishUpload(uint32_t fileLength)
if (uploadState == uploadOK && !fileBeingUploaded.Flush())
{
uploadState = uploadError;
- platform->Message(GENERIC_MESSAGE, "Error: Could not flush remaining data while finishing upload!\n");
+ platform->Message(GenericMessage, "Error: Could not flush remaining data while finishing upload!\n");
}
// Check the file length is as expected
if (uploadState == uploadOK && fileLength != 0 && fileBeingUploaded.Length() != fileLength)
{
uploadState = uploadError;
- platform->MessageF(GENERIC_MESSAGE, "Error: Uploaded file size is different (%u vs. expected %u bytes)!\n", fileBeingUploaded.Length(), fileLength);
+ platform->MessageF(GenericMessage, "Error: Uploaded file size is different (%u vs. expected %u bytes)!\n", fileBeingUploaded.Length(), fileLength);
}
// Close the file
@@ -588,7 +588,7 @@ void Webserver::HttpInterpreter::DoFastUpload()
writeBufIndex = 0;
if (!success)
{
- platform->Message(GENERIC_MESSAGE, "Error: Could not write upload data!\n");
+ platform->Message(GenericMessage, "Error: Could not write upload data!\n");
CancelUpload();
while (!network->Lock()) { }
@@ -662,7 +662,7 @@ void Webserver::HttpInterpreter::SendFile(const char* nameOfFileToSend, bool isW
char nameBuf[FILENAME_LENGTH + 1];
strcpy(nameBuf, nameOfFileToSend);
strcat(nameBuf, ".gz");
- fileToSend = platform->GetFileStore(platform->GetWebDir(), nameBuf, false);
+ fileToSend = platform->GetFileStore(platform->GetWebDir(), nameBuf, OpenMode::read);
if (fileToSend != nullptr)
{
zip = true;
@@ -672,14 +672,14 @@ void Webserver::HttpInterpreter::SendFile(const char* nameOfFileToSend, bool isW
// If that failed, try to open the normal version of the file
if (fileToSend == nullptr)
{
- fileToSend = platform->GetFileStore(platform->GetWebDir(), nameOfFileToSend, false);
+ fileToSend = platform->GetFileStore(platform->GetWebDir(), nameOfFileToSend, OpenMode::read);
}
// If we still couldn't find the file and it was an HTML file, return the 404 error page
if (fileToSend == nullptr && (StringEndsWith(nameOfFileToSend, ".html") || StringEndsWith(nameOfFileToSend, ".htm")))
{
nameOfFileToSend = FOUR04_PAGE_FILE;
- fileToSend = platform->GetFileStore(platform->GetWebDir(), nameOfFileToSend, false);
+ fileToSend = platform->GetFileStore(platform->GetWebDir(), nameOfFileToSend, OpenMode::read);
}
if (fileToSend == nullptr)
@@ -691,7 +691,7 @@ void Webserver::HttpInterpreter::SendFile(const char* nameOfFileToSend, bool isW
}
else
{
- fileToSend = platform->GetFileStore(FS_PREFIX, nameOfFileToSend, false);
+ fileToSend = platform->GetFileStore(FS_PREFIX, nameOfFileToSend, OpenMode::read);
if (fileToSend == nullptr)
{
RejectMessage("not found", 404);
@@ -778,7 +778,7 @@ void Webserver::HttpInterpreter::SendGCodeReply()
if (reprap.Debug(moduleWebserver))
{
- platform->MessageF(HOST_MESSAGE, "Sending G-Code reply to client %d of %d (length %u)\n", clientsServed, numSessions, gcodeReply->DataLength());
+ platform->MessageF(UsbMessage, "Sending G-Code reply to client %d of %d (length %u)\n", clientsServed, numSessions, gcodeReply->DataLength());
}
}
@@ -964,7 +964,7 @@ void Webserver::HttpInterpreter::GetJsonResponse(const char* request, OutputBuff
else if (StringEquals(request, "gcode") && GetKeyValue("gcode") != nullptr)
{
RegularGCodeInput * const httpInput = reprap.GetGCodes().GetHTTPInput();
- httpInput->Put(HTTP_MESSAGE, GetKeyValue("gcode"));
+ httpInput->Put(HttpMessage, GetKeyValue("gcode"));
response->printf("{\"buff\":%u}", httpInput->BufferSpaceLeft());
}
else if (StringEquals(request, "upload"))
@@ -1106,7 +1106,7 @@ void Webserver::HttpInterpreter::ConnectionLost(Connection conn)
{
if (reprap.Debug(moduleWebserver))
{
- platform->MessageF(HOST_MESSAGE, "POST upload for '%s' has been cancelled!\n", filenameBeingUploaded);
+ platform->MessageF(UsbMessage, "POST upload for '%s' has been cancelled!\n", filenameBeingUploaded);
}
sessions[i].isPostUploading = false;
CancelUpload();
@@ -1464,18 +1464,18 @@ bool Webserver::HttpInterpreter::ProcessMessage()
{
if (reprap.Debug(moduleWebserver))
{
- platform->MessageF(HOST_MESSAGE, "HTTP req, command words {", numCommandWords);
+ platform->MessageF(UsbMessage, "HTTP req, command words {", numCommandWords);
for (size_t i = 0; i < numCommandWords; ++i)
{
- platform->MessageF(HOST_MESSAGE, " %s", commandWords[i]);
+ platform->MessageF(UsbMessage, " %s", commandWords[i]);
}
- platform->Message(HOST_MESSAGE, " }, parameters {");
+ platform->Message(UsbMessage, " }, parameters {");
for (size_t i = 0; i < numQualKeys; ++i)
{
- platform->MessageF(HOST_MESSAGE, " %s=%s", qualifiers[i].key, qualifiers[i].value);
+ platform->MessageF(UsbMessage, " %s=%s", qualifiers[i].key, qualifiers[i].value);
}
- platform->Message(HOST_MESSAGE, " }\n");
+ platform->Message(UsbMessage, " }\n");
}
if (numCommandWords < 2)
@@ -1554,7 +1554,7 @@ bool Webserver::HttpInterpreter::ProcessMessage()
}
// Start a new file upload
- FileStore *file = platform->GetFileStore(FS_PREFIX, qualifiers[0].value, true);
+ FileStore *file = platform->GetFileStore(FS_PREFIX, qualifiers[0].value, OpenMode::write);
if (!StartUpload(file, qualifiers[0].value))
{
return RejectMessage("could not start file upload");
@@ -1581,7 +1581,7 @@ bool Webserver::HttpInterpreter::ProcessMessage()
if (reprap.Debug(moduleWebserver))
{
- platform->MessageF(HOST_MESSAGE, "Start uploading file %s length %lu\n", qualifiers[0].value, postFileLength);
+ platform->MessageF(UsbMessage, "Start uploading file %s length %lu\n", qualifiers[0].value, postFileLength);
}
uploadedBytes = 0;
@@ -1613,7 +1613,7 @@ bool Webserver::HttpInterpreter::ProcessMessage()
// Reject the current message. Always returns true to indicate that we should stop reading the message.
bool Webserver::HttpInterpreter::RejectMessage(const char* response, unsigned int code)
{
- platform->MessageF(HOST_MESSAGE, "Webserver: rejecting message with: %s\n", response);
+ platform->MessageF(UsbMessage, "Webserver: rejecting message with: %s\n", response);
NetworkTransaction *transaction = webserver->currentTransaction;
transaction->Printf("HTTP/1.1 %u %s\nConnection: close\n\n", code, response);
@@ -1800,7 +1800,7 @@ void Webserver::FtpInterpreter::ConnectionEstablished()
connectedClients++;
if (reprap.Debug(moduleWebserver))
{
- platform->Message(HOST_MESSAGE, "Webserver: FTP connection established!\n");
+ platform->Message(UsbMessage, "Webserver: FTP connection established!\n");
}
// Is this a new connection on the data port?
@@ -1886,7 +1886,7 @@ bool Webserver::FtpInterpreter::CharFromClient(char c)
if (clientPointer == ARRAY_UPB(clientMessage))
{
clientPointer = 0;
- platform->Message(HOST_MESSAGE, "Webserver: Buffer overflow in FTP server!\n");
+ platform->Message(UsbMessage, "Webserver: Buffer overflow in FTP server!\n");
return true;
}
@@ -1901,7 +1901,7 @@ bool Webserver::FtpInterpreter::CharFromClient(char c)
if (reprap.Debug(moduleWebserver))
{
- platform->MessageF(HOST_MESSAGE, "FtpInterpreter::ProcessLine called with state %d:\n%s\n", state, clientMessage);
+ platform->MessageF(UsbMessage, "FtpInterpreter::ProcessLine called with state %d:\n%s\n", state, clientMessage);
}
if (clientPointer > 1) // only process a new line if we actually received data
@@ -1913,7 +1913,7 @@ bool Webserver::FtpInterpreter::CharFromClient(char c)
if (reprap.Debug(moduleWebserver))
{
- platform->Message(HOST_MESSAGE, "FtpInterpreter::ProcessLine call finished.\n");
+ platform->Message(UsbMessage, "FtpInterpreter::ProcessLine call finished.\n");
}
clientPointer = 0;
@@ -2221,7 +2221,7 @@ void Webserver::FtpInterpreter::ProcessLine()
{
ReadFilename(4);
- FileStore *file = platform->GetFileStore(currentDir, filename, true);
+ FileStore *file = platform->GetFileStore(currentDir, filename, OpenMode::write);
if (StartUpload(file, filename))
{
SendReply(150, "OK to send data.");
@@ -2239,7 +2239,7 @@ void Webserver::FtpInterpreter::ProcessLine()
{
ReadFilename(4);
- FileStore *file = platform->GetFileStore(currentDir, filename, false);
+ FileStore *file = platform->GetFileStore(currentDir, filename, OpenMode::read);
if (file == nullptr)
{
SendReply(550, "Failed to open file.");
@@ -2583,7 +2583,7 @@ bool Webserver::TelnetInterpreter::CharFromClient(char c)
if (clientPointer == ARRAY_UPB(clientMessage))
{
clientPointer = 0;
- platform->Message(HOST_MESSAGE, "Webserver: Buffer overflow in Telnet server!\n");
+ platform->Message(UsbMessage, "Webserver: Buffer overflow in Telnet server!\n");
return true;
}
break;
@@ -2642,7 +2642,7 @@ bool Webserver::TelnetInterpreter::ProcessLine()
// All other codes are stored for the GCodes class
RegularGCodeInput * const telnetInput = reprap.GetGCodes().GetTelnetInput();
- telnetInput->Put(TELNET_MESSAGE, clientMessage);
+ telnetInput->Put(TelnetMessage, clientMessage);
break;
}
return false;
diff --git a/src/Duet/Webserver.h b/src/Duet/Webserver.h
index 09fb0bbb..fdadd94d 100644
--- a/src/Duet/Webserver.h
+++ b/src/Duet/Webserver.h
@@ -337,7 +337,7 @@ protected:
NetworkTransaction *currentTransaction;
volatile Connection readingConnection;
- float longWait;
+ uint32_t longWait;
};
inline bool ProtocolInterpreter::CanParseData() { return true; }
diff --git a/src/DuetNG/DuetEthernet/Network.cpp b/src/DuetNG/DuetEthernet/Network.cpp
index 3009bc28..0915cbae 100644
--- a/src/DuetNG/DuetEthernet/Network.cpp
+++ b/src/DuetNG/DuetEthernet/Network.cpp
@@ -14,6 +14,7 @@
#include "TelnetResponder.h"
#include "wizchip_conf.h"
#include "Wiznet/Internet/DHCP/dhcp.h"
+#include "Libraries/General/IP4String.h"
const Port DefaultPortNumbers[NumProtocols] = { DefaultHttpPort, DefaultFtpPort, DefaultTelnetPort };
const char * const ProtocolNames[NumProtocols] = { "HTTP", "FTP", "TELNET" };
@@ -41,7 +42,7 @@ void Network::Init()
{
// Ensure that the W5500 chip is in the reset state
pinMode(EspResetPin, OUTPUT_LOW);
- longWait = platform.Time();
+ longWait = millis();
lastTickMillis = millis();
NetworkBuffer::AllocateBuffers(NetworkBufferCount);
@@ -198,7 +199,7 @@ void Network::Activate()
}
else
{
- platform.Message(NETWORK_INFO_MESSAGE, "Network disabled.\n");
+ platform.Message(NetworkInfoMessage, "Network disabled.\n");
}
}
}
@@ -213,9 +214,9 @@ bool Network::GetNetworkState(StringRef& reply)
{
const uint8_t * const config_ip = platform.GetIPAddress();
const int enableState = EnableState();
- reply.printf("Network is %s, configured IP address: %u.%u.%u.%u, actual IP address: %u.%u.%u.%u",
+ reply.printf("Network is %s, configured IP address: %s, actual IP address: %s",
(enableState == 0) ? "disabled" : "enabled",
- config_ip[0], config_ip[1], config_ip[2], config_ip[3], ipAddress[0], ipAddress[1], ipAddress[2], ipAddress[3]);
+ IP4String(config_ip).c_str(), IP4String(ipAddress).c_str());
return false;
}
@@ -329,7 +330,7 @@ void Network::Spin(bool full)
if (full)
{
InitSockets();
- platform.MessageF(NETWORK_INFO_MESSAGE, "Network running, IP address = %u.%u.%u.%u\n", ipAddress[0], ipAddress[1], ipAddress[2], ipAddress[3]);
+ platform.MessageF(NetworkInfoMessage, "Network running, IP address = %s\n", IP4String(ipAddress).c_str());
state = NetworkState::active;
}
break;
@@ -426,7 +427,7 @@ void Network::Enable(int mode, StringRef& reply)
if (state != NetworkState::disabled)
{
Stop();
- platform.Message(NETWORK_INFO_MESSAGE, "Network stopped\n");
+ platform.Message(NetworkInfoMessage, "Network stopped\n");
}
}
diff --git a/src/DuetNG/DuetEthernet/Network.h b/src/DuetNG/DuetEthernet/Network.h
index 0df03fc3..7e205cbb 100644
--- a/src/DuetNG/DuetEthernet/Network.h
+++ b/src/DuetNG/DuetEthernet/Network.h
@@ -96,7 +96,7 @@ private:
NetworkResponder *nextResponderToPoll;
FtpResponder *ftpResponder;
TelnetResponder *telnetResponder;
- float longWait;
+ uint32_t longWait;
uint32_t lastTickMillis;
Socket sockets[NumTcpSockets];
diff --git a/src/DuetNG/DuetWiFi/Network.cpp b/src/DuetNG/DuetWiFi/Network.cpp
index 24e84ddf..c67f9ce0 100644
--- a/src/DuetNG/DuetWiFi/Network.cpp
+++ b/src/DuetNG/DuetWiFi/Network.cpp
@@ -11,6 +11,7 @@
#include "FtpResponder.h"
#include "TelnetResponder.h"
#include "WifiFirmwareUploader.h"
+#include "Libraries/General/IP4String.h"
// Define exactly one of the following as 1, the other as zero
// The PDC seems to be too slow to work reliably without getting transmit underruns, so we use the DMAC now.
@@ -119,7 +120,7 @@ Network::Network(Platform& p) : platform(p), nextResponderToPoll(nullptr), uploa
responders = new HttpResponder(responders);
}
- strcpy(ssid, "(unknown)");
+ strcpy(actualSsid, "(unknown)");
strcpy(wiFiServerVersion, "(unknown)");
}
@@ -127,8 +128,7 @@ void Network::Init()
{
// Make sure the ESP8266 is held in the reset state
ResetWiFi();
- longWait = platform.Time();
- lastTickMillis = millis();
+ longWait = lastTickMillis = millis();
NetworkBuffer::AllocateBuffers(NetworkBufferCount);
@@ -286,7 +286,7 @@ void Network::Activate()
}
else
{
- platform.Message(HOST_MESSAGE, "Network disabled.\n");
+ platform.Message(UsbMessage, "Network disabled.\n");
}
}
}
@@ -316,7 +316,7 @@ bool Network::GetNetworkState(StringRef& reply)
reply.cat(TranslateWiFiState(currentMode));
if (currentMode == WiFiState::connected || currentMode == WiFiState::runningAsAccessPoint)
{
- reply.catf("%s, IP address %u.%u.%u.%u", ssid, ipAddress[0], ipAddress[1], ipAddress[2], ipAddress[3]);
+ reply.catf("%s, IP address %s", actualSsid, IP4String(ipAddress).c_str());
}
break;
default:
@@ -428,7 +428,7 @@ void Network::Spin(bool full)
if (now - lastTickMillis >= WiFiStableMillis)
{
// Setup the SPI controller in slave mode and assign the CS pin to it
- platform.Message(NETWORK_INFO_MESSAGE, "WiFi module started\n");
+ platform.Message(NetworkInfoMessage, "WiFi module started\n");
SetupSpi(); // set up the SPI subsystem
// Read the status to get the WiFi server version
@@ -441,7 +441,7 @@ void Network::Spin(bool full)
// Set the hostname before anything else is done
if (SendCommand(NetworkCommand::networkSetHostName, 0, 0, hostname, HostNameLength, nullptr, 0) != ResponseEmpty)
{
- reprap.GetPlatform().Message(NETWORK_INFO_MESSAGE, "Error: Could not set WiFi hostname\n");
+ reprap.GetPlatform().Message(NetworkInfoMessage, "Error: Could not set WiFi hostname\n");
}
state = NetworkState::active;
@@ -451,7 +451,7 @@ void Network::Spin(bool full)
{
// Something went wrong, maybe a bad firmware image was flashed
// Disable the WiFi chip again in this case
- platform.MessageF(NETWORK_INFO_MESSAGE, "Error: Failed to initialise WiFi module, code %d\n", rc);
+ platform.MessageF(NetworkInfoMessage, "Error: Failed to initialise WiFi module, code %d\n", rc);
Stop();
}
}
@@ -496,7 +496,7 @@ void Network::Spin(bool full)
}
else if (requestedMode == WiFiState::connected)
{
- rslt = SendCommand(NetworkCommand::networkStartClient, 0, 0, nullptr, 0, nullptr, 0);
+ rslt = SendCommand(NetworkCommand::networkStartClient, 0, 0, requestedSsid, SsidLength, nullptr, 0);
}
else if (requestedMode == WiFiState::runningAsAccessPoint)
{
@@ -510,7 +510,7 @@ void Network::Spin(bool full)
else
{
Stop();
- platform.MessageF(NETWORK_INFO_MESSAGE, "Failed to change WiFi mode (code %d)\n", rslt);
+ platform.MessageF(NetworkInfoMessage, "Failed to change WiFi mode (code %d)\n", rslt);
}
}
else if (currentMode == WiFiState::connected || currentMode == WiFiState::runningAsAccessPoint)
@@ -587,18 +587,18 @@ void Network::Spin(bool full)
ipAddress[i] = (uint8_t)(ip & 255);
ip >>= 8;
}
- SafeStrncpy(ssid, status.Value().ssid, SsidLength);
+ SafeStrncpy(actualSsid, status.Value().ssid, SsidLength);
}
InitSockets();
reconnectCount = 0;
- platform.MessageF(NETWORK_INFO_MESSAGE, "Wifi module is %s%s, IP address %u.%u.%u.%u\n",
+ platform.MessageF(NetworkInfoMessage, "Wifi module is %s%s, IP address %s\n",
TranslateWiFiState(currentMode),
- ssid,
- ipAddress[0], ipAddress[1], ipAddress[2], ipAddress[3]);
+ actualSsid,
+ IP4String(ipAddress).c_str());
}
else
{
- platform.MessageF(NETWORK_INFO_MESSAGE, "Wifi module is %s\n", TranslateWiFiState(currentMode));
+ platform.MessageF(NetworkInfoMessage, "Wifi module is %s\n", TranslateWiFiState(currentMode));
}
}
}
@@ -670,8 +670,7 @@ void Network::Diagnostics(MessageType mtype)
if (currentMode == WiFiState::connected || currentMode == WiFiState::runningAsAccessPoint)
{
- platform.MessageF(mtype, "WiFi IP address %d.%d.%d.%d\n",
- r.ipAddress & 255, (r.ipAddress >> 8) & 255, (r.ipAddress >> 16) & 255, (r.ipAddress >> 24) & 255);
+ platform.MessageF(mtype, "WiFi IP address %s\n", IP4String(r.ipAddress).c_str());
}
if (currentMode == WiFiState::connected)
@@ -709,13 +708,20 @@ void Network::Diagnostics(MessageType mtype)
platform.Message(mtype, "\n");
}
-void Network::Enable(int mode, StringRef& reply)
+// Enable or disable the network
+void Network::Enable(int mode, const StringRef& ssid, StringRef& reply)
{
// Translate enable mode to desired WiFi mode
const WiFiState modeRequested = (mode == 0) ? WiFiState::idle
: (mode == 1) ? WiFiState::connected
: (mode == 2) ? WiFiState::runningAsAccessPoint
: WiFiState::disabled;
+ if (modeRequested == WiFiState::connected)
+ {
+ memset(requestedSsid, 0, sizeof(requestedSsid));
+ SafeStrncpy(requestedSsid, ssid.Pointer(), ARRAY_SIZE(requestedSsid));
+ }
+
if (activated)
{
if (modeRequested == WiFiState::disabled)
@@ -725,7 +731,7 @@ void Network::Enable(int mode, StringRef& reply)
if (state != NetworkState::disabled)
{
Stop();
- platform.Message(GENERIC_MESSAGE, "WiFi module stopped\n");
+ platform.Message(GenericMessage, "WiFi module stopped\n");
}
}
else
@@ -827,7 +833,7 @@ void Network::SetHostname(const char *name)
{
if (SendCommand(NetworkCommand::networkSetHostName, 0, 0, hostname, HostNameLength, nullptr, 0) != ResponseEmpty)
{
- platform.Message(GENERIC_MESSAGE, "Error: Could not set WiFi hostname\n");
+ platform.Message(GenericMessage, "Error: Could not set WiFi hostname\n");
}
}
}
@@ -1318,11 +1324,11 @@ void Network::GetNewStatus()
rcvr.Value().messageBuffer[ARRAY_UPB(rcvr.Value().messageBuffer)] = 0;
if (rslt < 0)
{
- platform.Message(NETWORK_INFO_MESSAGE, "Error retrieving WiFi status message\n");
+ platform.Message(NetworkInfoMessage, "Error retrieving WiFi status message\n");
}
else if (rslt > 0 && rcvr.Value().messageBuffer[0] != 0)
{
- platform.MessageF(NETWORK_INFO_MESSAGE, "WiFi reported error: %s\n", rcvr.Value().messageBuffer);
+ platform.MessageF(NetworkInfoMessage, "WiFi reported error: %s\n", rcvr.Value().messageBuffer);
}
}
diff --git a/src/DuetNG/DuetWiFi/Network.h b/src/DuetNG/DuetWiFi/Network.h
index d9c46721..4c97f7e8 100644
--- a/src/DuetNG/DuetWiFi/Network.h
+++ b/src/DuetNG/DuetWiFi/Network.h
@@ -53,7 +53,7 @@ public:
void DisableProtocol(int protocol, StringRef& reply);
void ReportProtocols(StringRef& reply) const;
- void Enable(int mode, StringRef& reply); // enable or disable the network
+ void Enable(int mode, const StringRef& ssid, StringRef& reply); // enable or disable the network
bool GetNetworkState(StringRef& reply);
int EnableState() const;
@@ -130,7 +130,7 @@ private:
NetworkResponder *nextResponderToPoll;
FtpResponder *ftpResponder;
TelnetResponder *telnetResponder;
- float longWait;
+ uint32_t longWait;
uint32_t lastTickMillis;
WifiFirmwareUploader *uploader;
@@ -152,7 +152,8 @@ private:
uint8_t netmask[4];
uint8_t gateway[4];
char hostname[16]; // Limit DHCP hostname to 15 characters + terminating 0
- char ssid[SsidLength + 1];
+ char requestedSsid[SsidLength + 1];
+ char actualSsid[SsidLength + 1];
unsigned int spiTxUnderruns;
unsigned int spiRxOverruns;
diff --git a/src/DuetNG/DuetWiFi/WifiFirmwareUploader.cpp b/src/DuetNG/DuetWiFi/WifiFirmwareUploader.cpp
index eb27e402..8a30af16 100644
--- a/src/DuetNG/DuetWiFi/WifiFirmwareUploader.cpp
+++ b/src/DuetNG/DuetWiFi/WifiFirmwareUploader.cpp
@@ -81,7 +81,7 @@ void WifiFirmwareUploader::MessageF(const char *fmt, ...)
{
va_list vargs;
va_start(vargs, fmt);
- reprap.GetPlatform().MessageF(FIRMWARE_UPDATE_MESSAGE, fmt, vargs);
+ reprap.GetPlatform().MessageF(FirmwareUpdateMessage, fmt, vargs);
va_end(vargs);
}
@@ -690,7 +690,7 @@ void WifiFirmwareUploader::Spin()
uploadPort.end(); // disable the port, it has a high interrupt priority
if (uploadResult == EspUploadResult::success)
{
- reprap.GetPlatform().Message(FIRMWARE_UPDATE_MESSAGE, "Upload successful\n");
+ reprap.GetPlatform().Message(FirmwareUpdateMessage, "Upload successful\n");
if (restartModeOnCompletion == 1)
{
reprap.GetNetwork().Start();
@@ -702,7 +702,7 @@ void WifiFirmwareUploader::Spin()
}
else
{
- reprap.GetPlatform().MessageF(FIRMWARE_UPDATE_MESSAGE, "Error: Installation failed due to %s error\n", resultMessages[(size_t)uploadResult]);
+ reprap.GetPlatform().MessageF(FirmwareUpdateMessage, "Error: Installation failed due to %s error\n", resultMessages[(size_t)uploadResult]);
// Not safe to restart the network
reprap.GetNetwork().ResetWiFi();
}
@@ -718,10 +718,10 @@ void WifiFirmwareUploader::Spin()
void WifiFirmwareUploader::SendUpdateFile(const char *file, const char *dir, uint32_t address)
{
Platform& platform = reprap.GetPlatform();
- uploadFile = platform.GetFileStore(dir, file, false);
+ uploadFile = platform.GetFileStore(dir, file, OpenMode::read);
if (uploadFile == nullptr)
{
- platform.MessageF(FIRMWARE_UPDATE_MESSAGE, "Failed to open file %s\n", file);
+ platform.MessageF(FirmwareUpdateMessage, "Failed to open file %s\n", file);
return;
}
@@ -729,7 +729,7 @@ void WifiFirmwareUploader::SendUpdateFile(const char *file, const char *dir, uin
if (fileSize == 0)
{
uploadFile->Close();
- platform.MessageF(FIRMWARE_UPDATE_MESSAGE, "Upload file is empty %s\n", file);
+ platform.MessageF(FirmwareUpdateMessage, "Upload file is empty %s\n", file);
return;
}
diff --git a/src/DuetNG/FirmwareUpdater.cpp b/src/DuetNG/FirmwareUpdater.cpp
index 4359b548..f8735903 100644
--- a/src/DuetNG/FirmwareUpdater.cpp
+++ b/src/DuetNG/FirmwareUpdater.cpp
@@ -29,17 +29,17 @@ namespace FirmwareUpdater
#ifdef DUET_WIFI
if ((moduleMap & (1 << WifiExternalFirmwareModule)) != 0 && (moduleMap & ((1 << WifiFirmwareModule) | (1 << WifiFilesModule))) != 0)
{
- reprap.GetPlatform().Message(GENERIC_MESSAGE, "Invalid combination of firmware update modules\n");
+ reprap.GetPlatform().Message(ErrorMessage, "Invalid combination of firmware update modules\n");
return false;
}
if ((moduleMap & (1 << WifiFirmwareModule)) != 0 && !reprap.GetPlatform().GetMassStorage()->FileExists(SYS_DIR, WIFI_FIRMWARE_FILE))
{
- reprap.GetPlatform().MessageF(GENERIC_MESSAGE, "File %s not found\n", WIFI_FIRMWARE_FILE);
+ reprap.GetPlatform().MessageF(ErrorMessage, "File %s not found\n", WIFI_FIRMWARE_FILE);
return false;
}
if ((moduleMap & (1 << WifiFilesModule)) != 0 && !reprap.GetPlatform().GetMassStorage()->FileExists(SYS_DIR, WIFI_WEB_FILE))
{
- reprap.GetPlatform().MessageF(GENERIC_MESSAGE, "File %s not found\n", WIFI_WEB_FILE);
+ reprap.GetPlatform().MessageF(ErrorMessage, "File %s not found\n", WIFI_WEB_FILE);
return false;
}
#endif
diff --git a/src/DuetNG/FtpResponder.cpp b/src/DuetNG/FtpResponder.cpp
index d4fcaa69..0d5567e8 100644
--- a/src/DuetNG/FtpResponder.cpp
+++ b/src/DuetNG/FtpResponder.cpp
@@ -350,14 +350,14 @@ void FtpResponder::DoUpload()
{
if (reprap.Debug(moduleWebserver))
{
- GetPlatform().MessageF(HOST_MESSAGE, "Writing %u bytes of upload data\n", len);
+ GetPlatform().MessageF(UsbMessage, "Writing %u bytes of upload data\n", len);
}
dataSocket->Taken(len);
if (!fileBeingUploaded.Write(buffer, len))
{
uploadError = true;
- GetPlatform().Message(GENERIC_MESSAGE, "Error: Could not write upload data!\n");
+ GetPlatform().Message(ErrorMessage, "Could not write upload data!\n");
CancelUpload();
responderState = ResponderState::pasvTransferComplete;
@@ -426,7 +426,7 @@ void FtpResponder::CharFromClient(char c)
if (clientPointer > ARRAY_UPB(clientMessage))
{
clientPointer = 0;
- GetPlatform().Message(HOST_MESSAGE, "Webserver: Buffer overflow in FTP server!\n");
+ GetPlatform().Message(UsbMessage, "Webserver: Buffer overflow in FTP server!\n");
}
break;
}
@@ -697,7 +697,7 @@ void FtpResponder::ProcessLine()
else if (StringStartsWith(clientMessage, "STOR"))
{
const char *filename = GetParameter("STOR");
- FileStore *file = GetPlatform().GetFileStore(currentDirectory, filename, true);
+ FileStore *file = GetPlatform().GetFileStore(currentDirectory, filename, OpenMode::write);
if (file != nullptr)
{
StartUpload(file, filename);
@@ -715,7 +715,7 @@ void FtpResponder::ProcessLine()
else if (StringStartsWith(clientMessage, "RETR"))
{
const char *filename = GetParameter("RETR");
- fileBeingSent = GetPlatform().GetFileStore(currentDirectory, filename, false);
+ fileBeingSent = GetPlatform().GetFileStore(currentDirectory, filename, OpenMode::read);
if (fileBeingSent != nullptr)
{
outBuf->printf("150 Opening data connection for %s (%lu bytes).\r\n", filename, fileBeingSent->Length());
diff --git a/src/DuetNG/HttpResponder.cpp b/src/DuetNG/HttpResponder.cpp
index 4b8ff8d6..0c5e4734 100644
--- a/src/DuetNG/HttpResponder.cpp
+++ b/src/DuetNG/HttpResponder.cpp
@@ -8,6 +8,7 @@
#include "HttpResponder.h"
#include "GCodes/GCodes.h"
#include "PrintMonitor.h"
+#include "Libraries/General/IP4String.h"
#define KO_START "rr_"
const size_t KoFirst = 3;
@@ -449,12 +450,14 @@ bool HttpResponder::GetJsonResponse(const char* request, OutputBuffer *&response
{
// Wrong password
response->copy("{\"err\":1}");
+ reprap.GetPlatform().MessageF(LogMessage, "HTTP client %s attempted login with incorrect password\n", IP4String(GetRemoteIP()).c_str());
return true;
}
if (!Authenticate())
{
// No more HTTP sessions available
response->copy("{\"err\":2}");
+ reprap.GetPlatform().MessageF(LogMessage, "HTTP client %s attempted login but no more sessions available\n", IP4String(GetRemoteIP()).c_str());
return true;
}
}
@@ -473,6 +476,7 @@ bool HttpResponder::GetJsonResponse(const char* request, OutputBuffer *&response
// Client has been logged in
response->printf("{\"err\":0,\"sessionTimeout\":%u,\"boardType\":\"%s\"}", HttpSessionTimeout, GetPlatform().GetBoardString());
+ reprap.GetPlatform().MessageF(LogMessage, "HTTP client %s login succeeded\n", IP4String(GetRemoteIP()).c_str());
}
else if (!CheckAuthenticated())
{
@@ -482,6 +486,7 @@ bool HttpResponder::GetJsonResponse(const char* request, OutputBuffer *&response
else if (StringEquals(request, "disconnect"))
{
response->printf("{\"err\":%d}", (RemoveAuthentication()) ? 0 : 1);
+ reprap.GetPlatform().MessageF(LogMessage, "HTTP client %s disconnected\n", IP4String(GetRemoteIP()).c_str());
}
else if (StringEquals(request, "status"))
{
@@ -508,7 +513,7 @@ bool HttpResponder::GetJsonResponse(const char* request, OutputBuffer *&response
else if (StringEquals(request, "gcode") && GetKeyValue("gcode") != nullptr)
{
RegularGCodeInput * const httpInput = reprap.GetGCodes().GetHTTPInput();
- httpInput->Put(HTTP_MESSAGE, GetKeyValue("gcode"));
+ httpInput->Put(HttpMessage, GetKeyValue("gcode"));
response->printf("{\"buff\":%u}", httpInput->BufferSpaceLeft());
}
else if (StringEquals(request, "upload"))
@@ -633,7 +638,7 @@ bool HttpResponder::Authenticate()
if (numSessions < MaxHttpSessions)
{
- sessions[numSessions].ip = skt->GetRemoteIP();
+ sessions[numSessions].ip = GetRemoteIP();
sessions[numSessions].lastQueryTime = millis();
sessions[numSessions].isPostUploading = false;
numSessions++;
@@ -645,7 +650,7 @@ bool HttpResponder::Authenticate()
// Check and update the authentication
bool HttpResponder::CheckAuthenticated()
{
- const uint32_t remoteIP = skt->GetRemoteIP();
+ const uint32_t remoteIP = GetRemoteIP();
for (size_t i = 0; i < numSessions; i++)
{
if (sessions[i].ip == remoteIP)
@@ -704,7 +709,7 @@ void HttpResponder::SendFile(const char* nameOfFileToSend, bool isWebFile)
char nameBuf[FILENAME_LENGTH + 1];
strcpy(nameBuf, nameOfFileToSend);
strcat(nameBuf, ".gz");
- fileToSend = GetPlatform().GetFileStore(GetPlatform().GetWebDir(), nameBuf, false);
+ fileToSend = GetPlatform().GetFileStore(GetPlatform().GetWebDir(), nameBuf, OpenMode::read);
if (fileToSend != nullptr)
{
zip = true;
@@ -714,14 +719,14 @@ void HttpResponder::SendFile(const char* nameOfFileToSend, bool isWebFile)
// If that failed, try to open the normal version of the file
if (fileToSend == nullptr)
{
- fileToSend = GetPlatform().GetFileStore(GetPlatform().GetWebDir(), nameOfFileToSend, false);
+ fileToSend = GetPlatform().GetFileStore(GetPlatform().GetWebDir(), nameOfFileToSend, OpenMode::read);
}
// If we still couldn't find the file and it was an HTML file, return the 404 error page
if (fileToSend == nullptr && (StringEndsWith(nameOfFileToSend, ".html") || StringEndsWith(nameOfFileToSend, ".htm")))
{
nameOfFileToSend = FOUR04_PAGE_FILE;
- fileToSend = GetPlatform().GetFileStore(GetPlatform().GetWebDir(), nameOfFileToSend, false);
+ fileToSend = GetPlatform().GetFileStore(GetPlatform().GetWebDir(), nameOfFileToSend, OpenMode::read);
}
if (fileToSend == nullptr)
@@ -733,7 +738,7 @@ void HttpResponder::SendFile(const char* nameOfFileToSend, bool isWebFile)
}
else
{
- fileToSend = GetPlatform().GetFileStore(FS_PREFIX, nameOfFileToSend, false);
+ fileToSend = GetPlatform().GetFileStore(FS_PREFIX, nameOfFileToSend, OpenMode::read);
if (fileToSend == nullptr)
{
RejectMessage("not found", 404);
@@ -821,7 +826,7 @@ void HttpResponder::SendGCodeReply()
if (reprap.Debug(moduleWebserver))
{
- GetPlatform().MessageF(HOST_MESSAGE, "Sending G-Code reply to client %d of %d (length %u)\n", clientsServed, numSessions, gcodeReply->DataLength());
+ GetPlatform().MessageF(UsbMessage, "Sending G-Code reply to client %d of %d (length %u)\n", clientsServed, numSessions, gcodeReply->DataLength());
}
}
@@ -932,18 +937,18 @@ void HttpResponder::ProcessMessage()
{
if (reprap.Debug(moduleWebserver))
{
- GetPlatform().MessageF(HOST_MESSAGE, "HTTP req, command words {", numCommandWords);
+ GetPlatform().MessageF(UsbMessage, "HTTP req, command words {", numCommandWords);
for (size_t i = 0; i < numCommandWords; ++i)
{
- GetPlatform().MessageF(HOST_MESSAGE, " %s", commandWords[i]);
+ GetPlatform().MessageF(UsbMessage, " %s", commandWords[i]);
}
- GetPlatform().Message(HOST_MESSAGE, " }, parameters {");
+ GetPlatform().Message(UsbMessage, " }, parameters {");
for (size_t i = 0; i < numQualKeys; ++i)
{
- GetPlatform().MessageF(HOST_MESSAGE, " %s=%s", qualifiers[i].key, qualifiers[i].value);
+ GetPlatform().MessageF(UsbMessage, " %s=%s", qualifiers[i].key, qualifiers[i].value);
}
- GetPlatform().Message(HOST_MESSAGE, " }\n");
+ GetPlatform().Message(UsbMessage, " }\n");
}
if (numCommandWords < 2)
@@ -1013,7 +1018,7 @@ void HttpResponder::ProcessMessage()
}
// Start a new file upload
- FileStore *file = GetPlatform().GetFileStore(FS_PREFIX, qualifiers[0].value, true);
+ FileStore *file = GetPlatform().GetFileStore(FS_PREFIX, qualifiers[0].value, OpenMode::write);
if (file == nullptr)
{
RejectMessage("could not create file");
@@ -1043,12 +1048,12 @@ void HttpResponder::ProcessMessage()
if (reprap.Debug(moduleWebserver))
{
- GetPlatform().MessageF(HOST_MESSAGE, "Start uploading file %s length %lu\n", qualifiers[0].value, postFileLength);
+ GetPlatform().MessageF(UsbMessage, "Start uploading file %s length %lu\n", qualifiers[0].value, postFileLength);
}
uploadedBytes = 0;
// Keep track of the connection that is now uploading
- const uint32_t remoteIP = skt->GetRemoteIP();
+ const uint32_t remoteIP = GetRemoteIP();
const uint16_t remotePort = skt->GetRemotePort();
for(size_t i = 0; i < numSessions; i++)
{
@@ -1075,7 +1080,7 @@ void HttpResponder::RejectMessage(const char* response, unsigned int code)
{
if (reprap.Debug(moduleWebserver))
{
- GetPlatform().MessageF(HOST_MESSAGE, "Webserver: rejecting message with: %u %s\n", code, response);
+ GetPlatform().MessageF(UsbMessage, "Webserver: rejecting message with: %u %s\n", code, response);
}
outBuf->printf("HTTP/1.1 %u %s\nConnection: close\n\n", code, response);
Commit();
@@ -1095,7 +1100,7 @@ void HttpResponder::DoUpload()
if (!fileBeingUploaded.Write(buffer, len))
{
uploadError = true;
- GetPlatform().Message(GENERIC_MESSAGE, "Error: Could not write upload data!\n");
+ GetPlatform().Message(ErrorMessage, "Could not write upload data!\n");
CancelUpload();
SendJsonResponse("upload");
return;
@@ -1106,7 +1111,7 @@ void HttpResponder::DoUpload()
if (uploadedBytes >= postFileLength)
{
// Reset POST upload state for this client
- const uint32_t remoteIP = skt->GetRemoteIP();
+ const uint32_t remoteIP = GetRemoteIP();
for (size_t i = 0; i < numSessions; i++)
{
if (sessions[i].ip == remoteIP && sessions[i].isPostUploading)
diff --git a/src/DuetNG/NetworkResponder.cpp b/src/DuetNG/NetworkResponder.cpp
index aea2b227..61932c12 100644
--- a/src/DuetNG/NetworkResponder.cpp
+++ b/src/DuetNG/NetworkResponder.cpp
@@ -230,14 +230,14 @@ void NetworkResponder::FinishUpload(uint32_t fileLength, time_t fileLastModified
if (!fileBeingUploaded.Flush())
{
uploadError = true;
- GetPlatform().Message(GENERIC_MESSAGE, "Error: Could not flush remaining data while finishing upload!\n");
+ GetPlatform().Message(ErrorMessage, "Could not flush remaining data while finishing upload!\n");
}
// Check the file length is as expected
if (fileLength != 0 && fileBeingUploaded.Length() != fileLength)
{
uploadError = true;
- GetPlatform().MessageF(GENERIC_MESSAGE, "Error: Uploaded file size is different (%u vs. expected %u bytes)!\n", fileBeingUploaded.Length(), fileLength);
+ GetPlatform().MessageF(ErrorMessage, "Uploaded file size is different (%u vs. expected %u bytes)!\n", fileBeingUploaded.Length(), fileLength);
}
// Close the file
@@ -264,4 +264,9 @@ void NetworkResponder::FinishUpload(uint32_t fileLength, time_t fileLastModified
filenameBeingUploaded[0] = 0;
}
+uint32_t NetworkResponder::GetRemoteIP() const
+{
+ return (skt == nullptr) ? 0 : skt->GetRemoteIP();
+}
+
// End
diff --git a/src/DuetNG/NetworkResponder.h b/src/DuetNG/NetworkResponder.h
index d611bcbc..6e4ace6c 100644
--- a/src/DuetNG/NetworkResponder.h
+++ b/src/DuetNG/NetworkResponder.h
@@ -76,6 +76,8 @@ protected:
void FinishUpload(uint32_t fileLength, time_t fileLastModified);
virtual void CancelUpload();
+ uint32_t GetRemoteIP() const;
+
static Platform& GetPlatform() { return reprap.GetPlatform(); }
static Network& GetNetwork() { return reprap.GetNetwork(); }
diff --git a/src/DuetNG/TelnetResponder.cpp b/src/DuetNG/TelnetResponder.cpp
index 0d731e08..13f570c4 100644
--- a/src/DuetNG/TelnetResponder.cpp
+++ b/src/DuetNG/TelnetResponder.cpp
@@ -185,7 +185,7 @@ void TelnetResponder::CharFromClient(char c)
if (clientPointer > ARRAY_UPB(clientMessage))
{
clientPointer = 0;
- GetPlatform().Message(HOST_MESSAGE, "Webserver: Buffer overflow in Telnet server!\n");
+ GetPlatform().Message(UsbMessage, "Webserver: Buffer overflow in Telnet server!\n");
}
break;
}
@@ -212,7 +212,7 @@ void TelnetResponder::ProcessLine()
{
// All other codes are stored for the GCodes class
RegularGCodeInput * const telnetInput = reprap.GetGCodes().GetTelnetInput();
- telnetInput->Put(TELNET_MESSAGE, clientMessage);
+ telnetInput->Put(TelnetMessage, clientMessage);
haveCompleteLine = false;
clientPointer = 0;
}
diff --git a/src/GCodes/GCodeBuffer.cpp b/src/GCodes/GCodeBuffer.cpp
index 05941b4a..ab8f42b6 100644
--- a/src/GCodes/GCodeBuffer.cpp
+++ b/src/GCodes/GCodeBuffer.cpp
@@ -90,7 +90,7 @@ bool GCodeBuffer::Put(char c)
gcodeBuffer[gcodePointer] = 0;
if (reprap.Debug(moduleGcodes) && gcodeBuffer[0] != 0 && !writingFileDirectory) // don't bother echoing blank/comment lines
{
- reprap.GetPlatform().MessageF(DEBUG_MESSAGE, "%s: %s\n", identity, gcodeBuffer);
+ reprap.GetPlatform().MessageF(DebugMessage, "%s: %s\n", identity, gcodeBuffer);
}
// Deal with line numbers and checksums
@@ -149,7 +149,7 @@ bool GCodeBuffer::Put(char c)
{
if (gcodePointer >= (int)GCODE_LENGTH)
{
- reprap.GetPlatform().MessageF(GENERIC_MESSAGE, "Error: G-Code buffer '%s' length overflow\n", identity);
+ reprap.GetPlatform().MessageF(ErrorMessage, "G-Code buffer '%s' length overflow\n", identity);
Init();
}
else
@@ -247,19 +247,32 @@ bool GCodeBuffer::Seen(char c)
return false;
}
-// Return the first G, M or T command letter. Needed so that we don't pick up a spurious command letter form inside a string parameter.
+// Return the first G, M or T command letter. Needed so that we don't pick up a spurious command letter from inside a string parameter.
char GCodeBuffer::GetCommandLetter()
{
readPointer = 0;
for (;;)
{
char b = gcodeBuffer[readPointer];
- if (b == 0 || b == ';') break;
+ if (b == 0 || b == ';' || b == '"' || b == '(')
+ {
+ break;
+ }
b = (char)toupper(b);
- if (b == 'G' || b == 'M' || b == 'T')
+ if (b == 'T')
{
return b;
}
+ if (b == 'G' || b == 'M')
+ {
+ // Check that the command letter is followed by a digit. This is mostly to avoid a malformed string in which the first letter is M being interpreted as M0.
+ const char b2 = gcodeBuffer[readPointer + 1];
+ if (b2 >= '0' && b2 <= '9')
+ {
+ return b;
+ }
+ break;
+ }
++readPointer;
}
readPointer = -1;
@@ -271,7 +284,7 @@ float GCodeBuffer::GetFValue()
{
if (readPointer < 0)
{
- reprap.GetPlatform().Message(GENERIC_MESSAGE, "Error: GCodes: Attempt to read a GCode float before a search.\n");
+ reprap.GetPlatform().Message(ErrorMessage, "GCodes: Attempt to read a GCode float before a search.\n");
return 0.0;
}
float result = (float) strtod(&gcodeBuffer[readPointer + 1], 0);
@@ -284,7 +297,7 @@ const void GCodeBuffer::GetFloatArray(float a[], size_t& returnedLength, bool do
{
if (readPointer < 0)
{
- reprap.GetPlatform().Message(GENERIC_MESSAGE, "Error: GCodes: Attempt to read a GCode float array before a search.\n");
+ reprap.GetPlatform().Message(ErrorMessage, "GCodes: Attempt to read a GCode float array before a search.\n");
returnedLength = 0;
return;
}
@@ -295,7 +308,7 @@ const void GCodeBuffer::GetFloatArray(float a[], size_t& returnedLength, bool do
{
if (length >= returnedLength) // array limit has been set in here
{
- reprap.GetPlatform().MessageF(GENERIC_MESSAGE, "Error: GCodes: Attempt to read a GCode float array that is too long: %s\n", gcodeBuffer);
+ reprap.GetPlatform().MessageF(ErrorMessage, "GCodes: Attempt to read a GCode float array that is too long: %s\n", gcodeBuffer);
readPointer = -1;
returnedLength = 0;
return;
@@ -334,7 +347,7 @@ const void GCodeBuffer::GetLongArray(long l[], size_t& returnedLength)
{
if (readPointer < 0)
{
- reprap.GetPlatform().Message(GENERIC_MESSAGE, "Error: GCodes: Attempt to read a GCode long array before a search.\n");
+ reprap.GetPlatform().Message(ErrorMessage, "GCodes: Attempt to read a GCode long array before a search.\n");
return;
}
@@ -344,7 +357,7 @@ const void GCodeBuffer::GetLongArray(long l[], size_t& returnedLength)
{
if (length >= returnedLength) // Array limit has been set in here
{
- reprap.GetPlatform().MessageF(GENERIC_MESSAGE, "Error: GCodes: Attempt to read a GCode long array that is too long: %s\n", gcodeBuffer);
+ reprap.GetPlatform().MessageF(ErrorMessage, "GCodes: Attempt to read a GCode long array that is too long: %s\n", gcodeBuffer);
readPointer = -1;
returnedLength = 0;
return;
@@ -371,7 +384,7 @@ const char* GCodeBuffer::GetString()
{
if (readPointer < 0)
{
- reprap.GetPlatform().Message(GENERIC_MESSAGE, "Error: GCodes: Attempt to read a GCode string before a search.\n");
+ reprap.GetPlatform().Message(ErrorMessage, "GCodes: Attempt to read a GCode string before a search.\n");
return "";
}
const char* const result = &gcodeBuffer[readPointer + 1];
@@ -385,7 +398,7 @@ bool GCodeBuffer::GetQuotedString(const StringRef& str)
str.Clear();
if (readPointer < 0)
{
- reprap.GetPlatform().Message(GENERIC_MESSAGE, "Error: GCodes: Attempt to read a GCode string before a search.\n");
+ reprap.GetPlatform().Message(ErrorMessage, "GCodes: Attempt to read a GCode string before a search.\n");
return false;
}
++readPointer; // skip the character that introduced the string
@@ -473,7 +486,7 @@ const char* GCodeBuffer::GetUnprecedentedString(bool optional)
readPointer = -1;
if (!optional)
{
- reprap.GetPlatform().Message(GENERIC_MESSAGE, "Error: GCodes: String expected but not seen.\n");
+ reprap.GetPlatform().Message(ErrorMessage, "GCodes: String expected but not seen.\n");
}
return nullptr;
}
@@ -488,7 +501,7 @@ int32_t GCodeBuffer::GetIValue()
{
if (readPointer < 0)
{
- reprap.GetPlatform().Message(GENERIC_MESSAGE, "Error: GCodes: Attempt to read a GCode int before a search.\n");
+ reprap.GetPlatform().Message(ErrorMessage, "GCodes: Attempt to read a GCode int before a search.\n");
readPointer = -1;
return 0;
}
@@ -502,7 +515,7 @@ uint32_t GCodeBuffer::GetUIValue()
{
if (readPointer < 0)
{
- reprap.GetPlatform().Message(GENERIC_MESSAGE, "Error: GCodes: Attempt to read a GCode int before a search.\n");
+ reprap.GetPlatform().Message(ErrorMessage, "GCodes: Attempt to read a GCode int before a search.\n");
readPointer = -1;
return 0;
}
@@ -592,7 +605,7 @@ bool GCodeBuffer::GetIPAddress(uint8_t ip[4])
{
if (readPointer < 0)
{
- reprap.GetPlatform().Message(GENERIC_MESSAGE, "Error: GCodes: Attempt to read a GCode string before a search.\n");
+ reprap.GetPlatform().Message(ErrorMessage, "GCodes: Attempt to read a GCode string before a search.\n");
return false;
}
const char* p = &gcodeBuffer[readPointer + 1];
diff --git a/src/GCodes/GCodeQueue.cpp b/src/GCodes/GCodeQueue.cpp
index e54e8b5a..3172eddb 100644
--- a/src/GCodes/GCodeQueue.cpp
+++ b/src/GCodes/GCodeQueue.cpp
@@ -136,7 +136,7 @@ bool GCodeQueue::QueueCode(GCodeBuffer &gb, uint32_t segmentsLeft)
{
if (reprap.Debug(moduleGcodes))
{
- reprap.GetPlatform().Message(DEBUG_MESSAGE, "(swap) ");
+ reprap.GetPlatform().Message(DebugMessage, "(swap) ");
}
if (!gb.Put(codeToRun, codeToRunLength))
{
diff --git a/src/GCodes/GCodes.cpp b/src/GCodes/GCodes.cpp
index f3ce50ea..66edcd13 100644
--- a/src/GCodes/GCodes.cpp
+++ b/src/GCodes/GCodes.cpp
@@ -52,15 +52,15 @@ GCodes::GCodes(Platform& p) :
serialInput = new StreamGCodeInput(SERIAL_MAIN_DEVICE);
auxInput = new StreamGCodeInput(SERIAL_AUX_DEVICE);
- httpGCode = new GCodeBuffer("http", HTTP_MESSAGE, false);
- telnetGCode = new GCodeBuffer("telnet", TELNET_MESSAGE, true);
- fileGCode = new GCodeBuffer("file", GENERIC_MESSAGE, true);
- serialGCode = new GCodeBuffer("serial", HOST_MESSAGE, true);
- auxGCode = new GCodeBuffer("aux", AUX_MESSAGE, false);
- daemonGCode = new GCodeBuffer("daemon", GENERIC_MESSAGE, false);
- queuedGCode = new GCodeBuffer("queue", GENERIC_MESSAGE, false);
+ httpGCode = new GCodeBuffer("http", HttpMessage, false);
+ telnetGCode = new GCodeBuffer("telnet", TelnetMessage, true);
+ fileGCode = new GCodeBuffer("file", GenericMessage, true);
+ serialGCode = new GCodeBuffer("serial", UsbMessage, true);
+ auxGCode = new GCodeBuffer("aux", LcdMessage, false);
+ daemonGCode = new GCodeBuffer("daemon", GenericMessage, false);
+ queuedGCode = new GCodeBuffer("queue", GenericMessage, false);
#ifdef DUET_NG
- autoPauseGCode = new GCodeBuffer("autopause", GENERIC_MESSAGE, false);
+ autoPauseGCode = new GCodeBuffer("autopause", GenericMessage, false);
#endif
codeQueue = new GCodeQueue();
}
@@ -91,7 +91,7 @@ void GCodes::Init()
toolChangeParam = DefaultToolChangeParam;
active = true;
fileSize = 0;
- longWait = platform.Time();
+ longWait = millis();
limitAxes = true;
SetAllAxesNotHomed();
for (size_t i = 0; i < NUM_FANS; ++i)
@@ -473,13 +473,14 @@ void GCodes::Spin()
#ifdef DUET_NG
if (isAutoPaused)
{
- platform.Message(GENERIC_MESSAGE, "Print auto-paused due to low voltage\n");
+ platform.Message(LoggedGenericMessage, "Print auto-paused due to low voltage\n");
reprap.GetHeat().SuspendHeaters(false); // resume the heaters, we may have turned them off while we executed the pause macro
}
else
#endif
{
reply.copy("Printing paused");
+ platform.Message(LogMessage, "Printing paused\n");
}
gb.SetState(GCodeState::normal);
}
@@ -533,6 +534,7 @@ void GCodes::Spin()
fileGCode->MachineState().feedrate = pauseRestorePoint.feedRate;
isPaused = false;
reply.copy("Printing resumed");
+ platform.Message(LogMessage, "Printing resumed\n");
gb.SetState(GCodeState::normal);
}
break;
@@ -628,7 +630,7 @@ void GCodes::Spin()
}
else
{
- platform.MessageF(GENERIC_MESSAGE, "Warning: skipping grid point (%.1f, %.1f) because Z probe cannot reach it\n", x, y);
+ platform.MessageF(WarningMessage, "Skipping grid point (%.1f, %.1f) because Z probe cannot reach it\n", x, y);
gb.SetState(GCodeState::gridProbing5);
}
}
@@ -662,7 +664,7 @@ void GCodes::Spin()
}
else if (reprap.GetPlatform().GetZProbeResult() == EndStopHit::lowHit)
{
- platform.Message(GENERIC_MESSAGE, "Error: Z probe already triggered before probing move started");
+ platform.Message(ErrorMessage, "Z probe already triggered before probing move started");
gb.SetState(GCodeState::normal);
if (platform.GetZProbeType() != 0 && !probeIsDeployed)
{
@@ -703,7 +705,7 @@ void GCodes::Spin()
platform.SetProbing(false);
if (!zProbeTriggered)
{
- platform.Message(GENERIC_MESSAGE, "Error: Z probe was not triggered during probing move\n");
+ platform.Message(ErrorMessage, "Z probe was not triggered during probing move\n");
gb.SetState(GCodeState::normal);
if (platform.GetZProbeType() != 0 && !probeIsDeployed)
{
@@ -859,7 +861,7 @@ void GCodes::Spin()
else if (reprap.GetPlatform().GetZProbeResult() == EndStopHit::lowHit) // check for probe already triggered at start
{
// Z probe is already triggered at the start of the move, so abandon the probe and record an error
- platform.Message(GENERIC_MESSAGE, "Error: Z probe already triggered at start of probing move\n");
+ platform.Message(ErrorMessage, "Z probe already triggered at start of probing move\n");
if (g30ProbePointIndex >= 0)
{
reprap.GetMove().SetZBedProbePoint(g30ProbePointIndex, platform.GetZProbeDiveHeight(), true, true);
@@ -908,7 +910,7 @@ void GCodes::Spin()
platform.SetProbing(false);
if (!zProbeTriggered)
{
- platform.Message(GENERIC_MESSAGE, "Error: Z probe was not triggered during probing move\n");
+ platform.Message(ErrorMessage, "Z probe was not triggered during probing move\n");
heightError = 0.0;
probingError = true;
}
@@ -1009,7 +1011,7 @@ void GCodes::Spin()
}
else if (g30SValue > -2)
{
- reprap.GetMove().FinishedBedProbing(g30SValue, reply);
+ error = reprap.GetMove().FinishedBedProbing(g30SValue, reply);
}
}
@@ -1088,7 +1090,7 @@ void GCodes::Spin()
reprap.GetCurrentTool()->GetFilament()->Load(filamentToLoad);
if (reprap.Debug(moduleGcodes))
{
- platform.MessageF(GENERIC_MESSAGE, "Filament %s loaded", filamentToLoad);
+ platform.MessageF(LoggedGenericMessage, "Filament %s loaded", filamentToLoad);
}
}
gb.SetState(GCodeState::normal);
@@ -1100,7 +1102,7 @@ void GCodes::Spin()
{
if (reprap.Debug(moduleGcodes))
{
- platform.MessageF(GENERIC_MESSAGE, "Filament %s unloaded", reprap.GetCurrentTool()->GetFilament()->GetName());
+ platform.MessageF(LoggedGenericMessage, "Filament %s unloaded", reprap.GetCurrentTool()->GetFilament()->GetName());
}
reprap.GetCurrentTool()->GetFilament()->Unload();
}
@@ -1108,7 +1110,7 @@ void GCodes::Spin()
break;
default: // should not happen
- platform.Message(GENERIC_MESSAGE, "Error: undefined GCodeState\n");
+ platform.Message(ErrorMessage, "Undefined GCodeState\n");
gb.SetState(GCodeState::normal);
break;
}
@@ -1135,13 +1137,13 @@ void GCodes::Spin()
{
if (displayNoToolWarning)
{
- platform.Message(GENERIC_MESSAGE, "Attempting to extrude with no tool selected.\n");
+ platform.Message(ErrorMessage, "Attempting to extrude with no tool selected.\n");
displayNoToolWarning = false;
lastWarningMillis = now;
}
if (displayDeltaNotHomedWarning)
{
- platform.Message(GENERIC_MESSAGE, "Attempt to move the head of a Delta or SCARA printer before homing the towers\n");
+ platform.Message(ErrorMessage, "Attempt to move the head of a Delta or SCARA printer before homing it\n");
displayDeltaNotHomedWarning = false;
lastWarningMillis = now;
}
@@ -1340,7 +1342,7 @@ void GCodes::CheckTriggers()
)
{
scratchString.printf("Extruder %u reports %s", lastFilamentErrorExtruder, FilamentSensor::GetErrorMessage(lastFilamentError));
- platform.SendAlert(GENERIC_MESSAGE, scratchString.Pointer(), "Filament error", 1, 0.0, 0);
+ platform.SendAlert(GenericMessage, scratchString.Pointer(), "Filament error", 1, 0.0, 0);
DoPause(*daemonGCode, false);
lastFilamentError = FilamentSensorStatus::ok;
}
@@ -1361,7 +1363,7 @@ void GCodes::DoEmergencyStop()
{
reprap.EmergencyStop();
Reset();
- platform.Message(GENERIC_MESSAGE, "Emergency Stop! Reset the controller to continue.");
+ platform.Message(GenericMessage, "Emergency Stop! Reset the controller to continue.");
}
// Pause the print. Before calling this, check that we are doing a file print that isn't already paused and get the movement lock.
@@ -1446,7 +1448,7 @@ void GCodes::DoPause(GCodeBuffer& gb, bool isAuto)
if (reprap.Debug(moduleGcodes))
{
- platform.MessageF(GENERIC_MESSAGE, "Paused print, file offset=%u\n", pauseRestorePoint.filePos);
+ platform.MessageF(GenericMessage, "Paused print, file offset=%u\n", pauseRestorePoint.filePos);
}
}
@@ -1522,7 +1524,7 @@ bool GCodes::AutoShutdown()
return false;
}
CancelPrint(false, false);
- platform.Message(GENERIC_MESSAGE, "Print cancelled due to low voltage\n");
+ platform.Message(WarningMessage, "Print cancelled due to low voltage\n");
return true;
}
return true;
@@ -1538,7 +1540,7 @@ bool GCodes::AutoResume()
{
DoFileMacro(*autoPauseGCode, POWER_RESTORE_G, true);
}
- platform.Message(GENERIC_MESSAGE, "Print auto-resumed\n");
+ platform.Message(LoggedGenericMessage, "Print auto-resumed\n");
}
return true;
}
@@ -1555,10 +1557,10 @@ void GCodes::SaveResumeInfo()
const char* const printingFilename = reprap.GetPrintMonitor().GetPrintingFilename();
if (printingFilename != nullptr)
{
- FileStore * const f = platform.GetFileStore(platform.GetSysDir(), RESUME_AFTER_POWER_FAIL_G, true);
+ FileStore * const f = platform.GetFileStore(platform.GetSysDir(), RESUME_AFTER_POWER_FAIL_G, OpenMode::write);
if (f == nullptr)
{
- platform.MessageF(GENERIC_MESSAGE, "Error: failed to create file %s", RESUME_AFTER_POWER_FAIL_G);
+ platform.MessageF(ErrorMessage, "Failed to create file %s", RESUME_AFTER_POWER_FAIL_G);
}
else
{
@@ -1628,12 +1630,12 @@ void GCodes::SaveResumeInfo()
}
if (ok)
{
- platform.Message(GENERIC_MESSAGE, "Resume-after-power-fail state saved\n");
+ platform.Message(LoggedGenericMessage, "Resume-after-power-fail state saved\n");
}
else
{
platform.GetMassStorage()->Delete(platform.GetSysDir(), RESUME_AFTER_POWER_FAIL_G, true);
- platform.MessageF(GENERIC_MESSAGE, "Error: failed to write or close file %s\n", RESUME_AFTER_POWER_FAIL_G);
+ platform.MessageF(ErrorMessage, "Failed to write or close file %s\n", RESUME_AFTER_POWER_FAIL_G);
}
}
@@ -1694,7 +1696,7 @@ bool GCodes::Push(GCodeBuffer& gb)
const bool ok = gb.PushState();
if (!ok)
{
- platform.Message(GENERIC_MESSAGE, "Push(): stack overflow!\n");
+ platform.Message(ErrorMessage, "Push(): stack overflow!\n");
}
return ok;
}
@@ -1704,7 +1706,7 @@ void GCodes::Pop(GCodeBuffer& gb)
{
if (!gb.PopState())
{
- platform.Message(GENERIC_MESSAGE, "Pop(): stack underflow!\n");
+ platform.Message(ErrorMessage, "Pop(): stack underflow!\n");
}
}
@@ -1804,7 +1806,7 @@ bool GCodes::LoadExtrusionAndFeedrateFromGCode(GCodeBuffer& gb, int moveType)
}
else
{
- platform.Message(GENERIC_MESSAGE, "Error: multiple E parameters in G1 commands are not supported in absolute extrusion mode\n");
+ platform.Message(ErrorMessage, "Multiple E parameters in G1 commands are not supported in absolute extrusion mode\n");
}
}
}
@@ -2210,13 +2212,13 @@ void GCodes::ClearMove()
// Return true if the file was found or it wasn't and we were asked to report that fact.
bool GCodes::DoFileMacro(GCodeBuffer& gb, const char* fileName, bool reportMissing, bool runningM502)
{
- FileStore * const f = platform.GetFileStore(platform.GetSysDir(), fileName, false);
+ FileStore * const f = platform.GetFileStore(platform.GetSysDir(), fileName, OpenMode::read);
if (f == nullptr)
{
if (reportMissing)
{
// Don't use snprintf into scratchString here, because fileName may be aliased to scratchString
- platform.MessageF(GENERIC_MESSAGE, "Macro file %s not found.\n", fileName);
+ platform.MessageF(WarningMessage, "Macro file %s not found.\n", fileName);
return true;
}
return false;
@@ -2401,7 +2403,7 @@ bool GCodes::ExecuteG30(GCodeBuffer& gb, StringRef& reply)
reprap.GetMove().SetZBedProbePoint((size_t)g30ProbePointIndex, z, false, false);
if (g30SValue > -2)
{
- reprap.GetMove().FinishedBedProbing(g30SValue, reply);
+ return reprap.GetMove().FinishedBedProbing(g30SValue, reply);
}
}
else
@@ -2432,10 +2434,10 @@ bool GCodes::ExecuteG30(GCodeBuffer& gb, StringRef& reply)
MessageType GCodes::GetMessageBoxDevice(GCodeBuffer& gb) const
{
MessageType mt = gb.GetResponseMessageType();
- if (mt == GENERIC_MESSAGE)
+ if (mt == GenericMessage)
{
// Command source was the file being printed, or a trigger. Send the message to PanelDue if there is one, else to the web server.
- mt = (lastAuxStatusReportType >= 0) ? AUX_MESSAGE : HTTP_MESSAGE;
+ mt = (lastAuxStatusReportType >= 0) ? LcdMessage : HttpMessage;
}
return mt;
}
@@ -2648,7 +2650,7 @@ bool GCodes::LoadHeightMap(GCodeBuffer& gb, StringRef& reply) const
heightMapFileName.GetRef().copy(DefaultHeightMapFile);
}
- FileStore * const f = platform.GetFileStore(platform.GetSysDir(), heightMapFileName.c_str(), false);
+ FileStore * const f = platform.GetFileStore(platform.GetSysDir(), heightMapFileName.c_str(), OpenMode::read);
if (f == nullptr)
{
reply.printf("Height map file %s not found", heightMapFileName.c_str());
@@ -2684,7 +2686,7 @@ bool GCodes::SaveHeightMap(GCodeBuffer& gb, StringRef& reply) const
heightMapFileName.GetRef().copy(DefaultHeightMapFile);
}
- FileStore * const f = platform.GetFileStore(platform.GetSysDir(), heightMapFileName.c_str(), true);
+ FileStore * const f = platform.GetFileStore(platform.GetSysDir(), heightMapFileName.c_str(), OpenMode::write);
bool err;
if (f == nullptr)
{
@@ -2752,12 +2754,12 @@ void GCodes::GetCurrentCoordinates(StringRef& s) const
bool GCodes::OpenFileToWrite(GCodeBuffer& gb, const char* directory, const char* fileName, const FilePosition size, const bool binaryWrite, const uint32_t fileCRC32)
{
- fileBeingWritten = platform.GetFileStore(directory, fileName, true);
+ fileBeingWritten = platform.GetFileStore(directory, fileName, OpenMode::write);
eofStringCounter = 0;
fileSize = size;
if (fileBeingWritten == nullptr)
{
- platform.MessageF(GENERIC_MESSAGE, "Can't open GCode file \"%s\" for writing.\n", fileName);
+ platform.MessageF(ErrorMessage, "Failed to open GCode file \"%s\" for writing.\n", fileName);
return false;
}
else
@@ -2773,7 +2775,7 @@ void GCodes::WriteHTMLToFile(GCodeBuffer& gb, char b)
{
if (fileBeingWritten == nullptr)
{
- platform.Message(GENERIC_MESSAGE, "Attempt to write to a null file.\n");
+ platform.Message(ErrorMessage, "Attempt to write to a null file.\n");
return;
}
@@ -2826,7 +2828,7 @@ void GCodes::WriteGCodeToFile(GCodeBuffer& gb)
{
if (fileBeingWritten == nullptr)
{
- platform.Message(GENERIC_MESSAGE, "Attempt to write to a null file.\n");
+ platform.Message(ErrorMessage, "Attempt to write to a null file.\n");
return;
}
@@ -2864,9 +2866,10 @@ void GCodes::WriteGCodeToFile(GCodeBuffer& gb)
}
// Set up a file to print, but don't print it yet.
-void GCodes::QueueFileToPrint(const char* fileName)
+// If successful return true, else write an error message to reply and return false
+bool GCodes::QueueFileToPrint(const char* fileName, StringRef& reply)
{
- FileStore * const f = platform.GetFileStore(platform.GetGCodeDir(), fileName, false);
+ FileStore * const f = platform.GetFileStore(platform.GetGCodeDir(), fileName, OpenMode::read);
if (f != nullptr)
{
// Cancel current print if there is any
@@ -2889,11 +2892,11 @@ void GCodes::QueueFileToPrint(const char* fileName)
fileToPrint.Set(f);
fileOffsetToPrint = 0;
+ return true;
}
- else
- {
- platform.MessageF(GENERIC_MESSAGE, "GCode file \"%s\" not found\n", fileName);
- }
+
+ reply.printf("GCode file \"%s\" not found\n", fileName);
+ return false;
}
// Start printing the file already selected
@@ -2903,14 +2906,9 @@ void GCodes::StartPrinting()
fileInput->Reset();
lastFilamentError = FilamentSensorStatus::ok;
reprap.GetPrintMonitor().StartedPrint();
-}
-
-void GCodes::DeleteFile(const char* fileName)
-{
- if (!platform.GetMassStorage()->Delete(platform.GetGCodeDir(), fileName))
- {
- platform.MessageF(GENERIC_MESSAGE, "Could not delete file \"%s\"\n", fileName);
- }
+ platform.MessageF(LogMessage,
+ (simulationMode == 0) ? "Started printing file %s\n" : "Started simulating printing file %s\n",
+ reprap.GetPrintMonitor().GetPrintingFilename());
}
// Function to handle dwell delays. Returns true for dwell finished, false otherwise.
@@ -3256,7 +3254,7 @@ void GCodes::SetMACAddress(GCodeBuffer& gb)
}
else
{
- platform.MessageF(GENERIC_MESSAGE, "Dud MAC address: %s\n", gb.Buffer());
+ platform.MessageF(ErrorMessage, "Dud MAC address: %s\n", gb.Buffer());
}
}
@@ -3309,7 +3307,6 @@ void GCodes::SaveFanSpeeds()
// Handle sending a reply back to the appropriate interface(s).
// Note that 'reply' may be empty. If it isn't, then we need to append newline when sending it.
-// Also, gb may be null if we were executing a trigger macro.
void GCodes::HandleReply(GCodeBuffer& gb, bool error, const char* reply)
{
// Don't report "ok" responses if a (macro) file is being processed
@@ -3319,7 +3316,7 @@ void GCodes::HandleReply(GCodeBuffer& gb, bool error, const char* reply)
return;
}
- // Second UART device, e.g. dc42's PanelDue. Do NOT use emulation for this one!
+ // Second UART device, e.g. PanelDue. Do NOT use emulation for this one!
if (&gb == auxGCode)
{
platform.AppendAuxReply(reply);
@@ -3328,59 +3325,39 @@ void GCodes::HandleReply(GCodeBuffer& gb, bool error, const char* reply)
const Compatibility c = (&gb == serialGCode || &gb == telnetGCode) ? platform.Emulating() : me;
const MessageType type = gb.GetResponseMessageType();
- const char* const response = (gb.Seen('M') && gb.GetIValue() == 998) ? "rs " : "ok";
- const char* emulationType = 0;
+ const char* const response = (gb.GetCommandLetter() == 'M' && gb.GetIValue() == 998) ? "rs " : "ok";
+ const char* emulationType = nullptr;
switch (c)
{
case me:
case reprapFirmware:
- if (error)
- {
- platform.Message(type, "Error: ");
- }
- platform.Message(type, reply);
- platform.Message(type, "\n");
- return;
+ platform.MessageF((error) ? (MessageType)(type | ErrorMessageFlag) : type, "%s\n", reply);
+ break;
case marlin:
// We don't need to handle M20 here because we always allocate an output buffer for that one
if (gb.Seen('M') && gb.GetIValue() == 28)
{
- platform.Message(type, response);
- platform.Message(type, "\n");
- platform.Message(type, reply);
- platform.Message(type, "\n");
- return;
+ platform.MessageF(type, "%s\n%s\n", response, reply);
}
-
- if ((gb.Seen('M') && gb.GetIValue() == 105) || (gb.Seen('M') && gb.GetIValue() == 998))
+ else if ((gb.Seen('M') && gb.GetIValue() == 105) || (gb.Seen('M') && gb.GetIValue() == 998))
{
- platform.Message(type, response);
- platform.Message(type, " ");
- platform.Message(type, reply);
- platform.Message(type, "\n");
- return;
+ platform.MessageF(type, "%s %s\n", response, reply);
}
-
- if (reply[0] != 0 && !gb.IsDoingFileMacro())
+ else if (reply[0] != 0 && !gb.IsDoingFileMacro())
{
- platform.Message(type, reply);
- platform.Message(type, "\n");
- platform.Message(type, response);
- platform.Message(type, "\n");
+ platform.MessageF(type, "%s\n%s\n", reply, response);
}
else if (reply[0] != 0)
{
- platform.Message(type, reply);
- platform.Message(type, "\n");
+ platform.MessageF(type, "%s\n", reply);
}
else
{
- platform.Message(type, response);
- platform.Message(type, "\n");
+ platform.MessageF(type, "%s\n", response);
}
- return;
+ break;
case teacup:
emulationType = "teacup";
@@ -3395,9 +3372,9 @@ void GCodes::HandleReply(GCodeBuffer& gb, bool error, const char* reply)
emulationType = "unknown";
}
- if (emulationType != 0)
+ if (emulationType != nullptr)
{
- platform.MessageF(type, "Emulation of %s is not yet supported.\n", emulationType); // don't send this one to the web as well, it concerns only the USB interface
+ platform.MessageF(type, "Emulation of %s is not yet supported.\n", emulationType);
}
}
@@ -3588,7 +3565,7 @@ void GCodes::SetToolHeaters(Tool *tool, float temperature)
{
if (tool == nullptr)
{
- platform.Message(GENERIC_MESSAGE, "Setting temperature: no tool selected.\n");
+ platform.Message(ErrorMessage, "Setting temperature: no tool selected.\n");
return;
}
@@ -3845,7 +3822,7 @@ void GCodes::CancelPrint(bool printStats, bool deleteResumeFile)
reprap.GetMove().Simulate(simulationMode);
EndSimulation(nullptr);
const uint32_t simMinutes = lrintf((reprap.GetMove().GetSimulationTime() + simulationTime)/60.0);
- platform.MessageF(GENERIC_MESSAGE, "File %s will print in %uh %um plus heating time\n",
+ platform.MessageF(LoggedGenericMessage, "File %s will print in %uh %um plus heating time\n",
printingFilename, simMinutes/60u, simMinutes % 60u);
}
else if (reprap.GetPrintMonitor().IsPrinting())
@@ -3853,12 +3830,12 @@ void GCodes::CancelPrint(bool printStats, bool deleteResumeFile)
if (platform.Emulating() == marlin)
{
// Pronterface expects a "Done printing" message
- platform.Message(HOST_MESSAGE, "Done printing file");
+ platform.Message(UsbMessage, "Done printing file");
}
if (printStats)
{
const uint32_t printMinutes = lrintf(reprap.GetPrintMonitor().GetPrintDuration()/60.0);
- platform.MessageF(GENERIC_MESSAGE, "File %s print time was %uh %um\n",
+ platform.MessageF(LoggedGenericMessage, "Finished printing file %s, print time was %uh %um\n",
printingFilename, printMinutes/60u, printMinutes % 60u);
}
}
@@ -4068,7 +4045,7 @@ void GCodes::ListTriggers(StringRef reply, TriggerInputsBitmap mask)
bool GCodes::StartHash(const char* filename)
{
// Get a FileStore object
- fileBeingHashed = platform.GetFileStore(FS_PREFIX, filename, false);
+ fileBeingHashed = platform.GetFileStore(FS_PREFIX, filename, OpenMode::read);
if (fileBeingHashed == nullptr)
{
return false;
@@ -4127,7 +4104,7 @@ void GCodes::SetAllAxesNotHomed()
// Write the config-override file returning true if an error occurred
bool GCodes::WriteConfigOverrideFile(StringRef& reply, const char *fileName) const
{
- FileStore * const f = platform.GetFileStore(platform.GetSysDir(), fileName, true);
+ FileStore * const f = platform.GetFileStore(platform.GetSysDir(), fileName, OpenMode::write);
if (f == nullptr)
{
reply.printf("Failed to create file %s", fileName);
@@ -4206,7 +4183,7 @@ void GCodes::CheckReportDue(GCodeBuffer& gb, StringRef& reply) const
// In Marlin emulation mode we should return a standard temperature report every second
GenerateTemperatureReport(reply);
reply.cat('\n');
- platform.Message(HOST_MESSAGE, reply.Pointer());
+ platform.Message(UsbMessage, reply.Pointer());
}
if (lastAuxStatusReportType >= 0)
{
diff --git a/src/GCodes/GCodes.h b/src/GCodes/GCodes.h
index b7197bdc..d6ca8e1f 100644
--- a/src/GCodes/GCodes.h
+++ b/src/GCodes/GCodes.h
@@ -102,9 +102,8 @@ public:
void Reset(); // Reset some parameter to defaults
bool ReadMove(RawMove& m); // Called by the Move class to get a movement set by the last G Code
void ClearMove();
- void QueueFileToPrint(const char* fileName); // Open a file of G Codes to run
+ bool QueueFileToPrint(const char* fileName, StringRef& reply); // Open a file of G Codes to run
void StartPrinting(); // Start printing the file already selected
- void DeleteFile(const char* fileName); // Does what it says
void GetCurrentCoordinates(StringRef& s) const; // Write where we are into a string
bool DoingFileMacro() const; // Or still busy processing a macro file?
float FractionOfFilePrinted() const; // Get fraction of file printed
@@ -410,7 +409,7 @@ private:
size_t lastFilamentErrorExtruder;
// Misc
- float longWait; // Timer for things that happen occasionally (seconds)
+ uint32_t longWait; // Timer for things that happen occasionally (seconds)
uint32_t lastWarningMillis; // When we last sent a warning message for things that can happen very often
AxesBitmap axesToSenseLength; // The axes on which we are performing axis length sensing
int8_t lastAuxStatusReportType; // The type of the last status report requested by PanelDue
diff --git a/src/GCodes/GCodes2.cpp b/src/GCodes/GCodes2.cpp
index 9fe7a41f..de79feb7 100644
--- a/src/GCodes/GCodes2.cpp
+++ b/src/GCodes/GCodes2.cpp
@@ -340,10 +340,10 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply)
{
seen = true;
- float idleTimeout = gb.GetFValue();
+ const float idleTimeout = gb.GetFValue();
if (idleTimeout < 0.0)
{
- reply.copy("Idle timeouts cannot be negative!");
+ reply.copy("Idle timeouts cannot be negative");
error = true;
}
else
@@ -464,8 +464,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply)
const char* filename = gb.GetUnprecedentedString();
if (filename != nullptr)
{
- QueueFileToPrint(filename);
- if (fileToPrint.IsLive())
+ if (QueueFileToPrint(filename, reply))
{
reprap.GetPrintMonitor().StartingPrint(filename);
if (platform.Emulating() == marlin && (&gb == serialGCode || &gb == telnetGCode))
@@ -485,7 +484,6 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply)
}
else
{
- reply.printf("Failed to open file %s", filename);
error = true;
}
}
@@ -618,7 +616,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply)
const char *filename = gb.GetUnprecedentedString();
if (filename != nullptr)
{
- DeleteFile(filename);
+ platform.GetMassStorage()->Delete(platform.GetGCodeDir(), filename, false);;
}
}
break;
@@ -699,8 +697,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply)
reprap.GetMove().GetCurrentUserPosition(simulationRestorePoint.moveCoords, 0, reprap.GetCurrentXAxes(), reprap.GetCurrentYAxes());
simulationRestorePoint.feedRate = gb.MachineState().feedrate;
}
- QueueFileToPrint(simFileName.c_str());
- if (fileToPrint.IsLive())
+ if (QueueFileToPrint(simFileName.c_str(), reply))
{
exitSimulationWhenFileComplete = true;
reprap.GetPrintMonitor().StartingPrint(simFileName.c_str());
@@ -711,7 +708,6 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply)
{
simulationMode = 0;
reprap.GetMove().Simulate(0);
- reply.printf("Failed to open file %s", simFileName.c_str());
error = true;
}
}
@@ -1731,7 +1727,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply)
}
else
{
- platform.MessageF(GENERIC_MESSAGE, "Error: Invalid servo index %d in M280 command\n", servoIndex);
+ platform.MessageF(ErrorMessage, "Invalid servo index %d in M280 command\n", servoIndex);
}
}
break;
@@ -1972,7 +1968,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply)
}
else
{
- platform.MessageF(GENERIC_MESSAGE, "Drive %c does not support %dx microstepping%s\n",
+ platform.MessageF(ErrorMessage, "Drive %c does not support %dx microstepping%s\n",
axisLetters[axis], microsteps, (mode) ? " with interpolation" : "");
}
}
@@ -1992,7 +1988,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply)
{
if (!ChangeMicrostepping(numTotalAxes + e, (int)eVals[e], mode))
{
- platform.MessageF(GENERIC_MESSAGE, "Drive E%u does not support %dx microstepping%s\n",
+ platform.MessageF(ErrorMessage, "Drive E%u does not support %dx microstepping%s\n",
e, (int)eVals[e], (mode) ? " with interpolation" : "");
}
}
@@ -2144,7 +2140,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply)
}
// Read the entire file
- FileStore * const f = platform.GetFileStore(platform.GetSysDir(), platform.GetConfigFile(), false);
+ FileStore * const f = platform.GetFileStore(platform.GetSysDir(), platform.GetConfigFile(), OpenMode::read);
if (f == nullptr)
{
error = true;
@@ -2223,6 +2219,26 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply)
case 552: // Enable/Disable network and/or Set/Get IP address
{
bool seen = false;
+
+#ifdef DUET_WIFI
+ if (gb.Seen('S')) // Has the user turned the network on or off?
+ {
+ const int enableValue = gb.GetIValue();
+ seen = true;
+
+ char ssidBuffer[SsidLength + 1];
+ StringRef ssid(ssidBuffer, ARRAY_SIZE(ssidBuffer));
+ if (gb.Seen('P') && !gb.GetQuotedString(ssid))
+ {
+ reply.copy("Bad or missing SSID in M552 command");
+ error = true;
+ }
+ else
+ {
+ reprap.GetNetwork().Enable(enableValue, ssid, reply);
+ }
+ }
+#else
if (gb.Seen('P'))
{
seen = true;
@@ -2245,6 +2261,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply)
seen = true;
reprap.GetNetwork().Enable(gb.GetIValue(), reply);
}
+#endif
if (!seen)
{
@@ -2626,7 +2643,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply)
}
if (badParameter)
{
- platform.Message(GENERIC_MESSAGE, "Error: M569 no longer accepts XYZE parameters; use M584 instead\n");
+ platform.Message(ErrorMessage, "M569 no longer accepts XYZE parameters; use M584 instead\n");
}
else if (!seen)
{
@@ -2699,17 +2716,34 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply)
break;
case 572: // Set/report pressure advance
- if (gb.Seen('D'))
+ if (gb.Seen('S'))
{
- // New usage: specify the extruder drive using the D parameter
- const size_t extruder = gb.GetIValue();
- if (gb.Seen('S'))
+ const float advance = gb.GetFValue();
+ if (gb.Seen('D'))
{
- platform.SetPressureAdvance(extruder, gb.GetFValue());
+ long int eDrive[MaxExtruders];
+ size_t eCount = MaxExtruders;
+ gb.GetLongArray(eDrive, eCount);
+ for (size_t i = 0; i < eCount; i++)
+ {
+ if (eDrive[i] < 0 || (size_t)eDrive[i] >= numExtruders)
+ {
+ reply.printf("Invalid extruder number '%ld'", eDrive[i]);
+ error = true;
+ break;
+ }
+ platform.SetPressureAdvance(eDrive[i], advance);
+ }
}
- else
+ }
+ else
+ {
+ reply.copy("Extruder pressure advance");
+ char c = ':';
+ for (size_t i = 0; i < numExtruders; ++i)
{
- reply.printf("Pressure advance for extruder %u is %.3f seconds", extruder, platform.GetPressureAdvance(extruder));
+ reply.catf("%c %.3f", c, platform.GetPressureAdvance(i));
+ c = ',';
}
}
break;
@@ -2990,7 +3024,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply)
break;
default:
- platform.Message(GENERIC_MESSAGE, "Bad S parameter in M581 command\n");
+ platform.Message(ErrorMessage, "Bad S parameter in M581 command\n");
}
}
if (!seen)
@@ -3486,35 +3520,38 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply)
break;
default:
- platform.MessageF(GENERIC_MESSAGE, "Error: mode %d is not value in M667 command\n", mode);
+ reply.printf("Mode %d is not valid in M667 command\n", mode);
error = true;
- return true;
+ break;
}
seen = true;
}
- if (!changedToCartesian) // don't ask the kinematics to process M667 if we switched to Cartesian mode
+ if (!error)
{
- if (move.GetKinematics().Configure(667, gb, reply, error))
+ if (!changedToCartesian) // don't ask the kinematics to process M667 if we switched to Cartesian mode
{
- seen = true;
+ if (move.GetKinematics().Configure(667, gb, reply, error))
+ {
+ seen = true;
+ }
}
- }
- if (seen)
- {
- // We changed something, so reset the positions and set all axes not homed
- if (move.GetKinematics().GetKinematicsType() != oldK)
- {
- move.GetKinematics().GetAssumedInitialPosition(numVisibleAxes, moveBuffer.coords);
- ToolOffsetInverseTransform(moveBuffer.coords, currentUserPosition);
- }
- if (reprap.GetMove().GetKinematics().LimitPosition(moveBuffer.coords, numVisibleAxes, axesHomed))
+ if (seen)
{
- ToolOffsetInverseTransform(moveBuffer.coords, currentUserPosition); // make sure the limits are reflected in the user position
+ // We changed something, so reset the positions and set all axes not homed
+ if (move.GetKinematics().GetKinematicsType() != oldK)
+ {
+ move.GetKinematics().GetAssumedInitialPosition(numVisibleAxes, moveBuffer.coords);
+ ToolOffsetInverseTransform(moveBuffer.coords, currentUserPosition);
+ }
+ if (reprap.GetMove().GetKinematics().LimitPosition(moveBuffer.coords, numVisibleAxes, axesHomed))
+ {
+ ToolOffsetInverseTransform(moveBuffer.coords, currentUserPosition); // make sure the limits are reflected in the user position
+ }
+ reprap.GetMove().SetNewPosition(moveBuffer.coords, true);
+ SetAllAxesNotHomed();
}
- reprap.GetMove().SetNewPosition(moveBuffer.coords, true);
- SetAllAxesNotHomed();
}
}
break;
@@ -3880,7 +3917,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply)
#ifdef DUET_NG
case 911: // Enable auto save
- platform.ConfigureAutoSave(gb, reply, error);
+ error = platform.ConfigureAutoSave(gb, reply);
break;
#endif
@@ -3924,6 +3961,10 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply)
break;
#endif
+ case 929: // Start/stop event logging
+ error = platform.ConfigureLogging(gb, reply);
+ break;
+
case 997: // Perform firmware update
if (!LockMovementAndWaitForStandstill(gb))
{
@@ -3945,7 +3986,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply)
long t = modulesToUpdate[i];
if (t < 0 || (unsigned long)t >= NumFirmwareUpdateModules)
{
- platform.MessageF(GENERIC_MESSAGE, "Invalid module number '%ld'\n", t);
+ platform.MessageF(ErrorMessage, "Invalid module number '%ld'\n", t);
firmwareUpdateModuleMap = 0;
break;
}
diff --git a/src/Heating/Heat.cpp b/src/Heating/Heat.cpp
index e87fe60b..0a56c82d 100644
--- a/src/Heating/Heat.cpp
+++ b/src/Heating/Heat.cpp
@@ -111,7 +111,7 @@ void Heat::Init()
#endif
lastTime = millis() - platform.HeatSampleInterval(); // flag the PIDS as due for spinning
- longWait = platform.Time();
+ longWait = millis();
coldExtrude = false;
active = true;
}
diff --git a/src/Heating/Heat.h b/src/Heating/Heat.h
index e231c928..3f38c1a4 100644
--- a/src/Heating/Heat.h
+++ b/src/Heating/Heat.h
@@ -147,7 +147,7 @@ private:
TemperatureSensor *virtualHeaterSensors[MaxVirtualHeaters]; // Sensors for virtual heaters
uint32_t lastTime; // The last time our Spin() was called
- float longWait; // Long time for things that happen occasionally
+ uint32_t longWait; // Long time for things that happen occasionally
bool active; // Are we active?
bool coldExtrude; // Is cold extrusion allowed?
diff --git a/src/Heating/Pid.cpp b/src/Heating/Pid.cpp
index b47505bc..74217ee6 100644
--- a/src/Heating/Pid.cpp
+++ b/src/Heating/Pid.cpp
@@ -99,8 +99,8 @@ bool PID::SetModel(float gain, float tc, float td, float maxPwm, bool usePid)
const float noWarnTemp = (temperatureLimit - NormalAmbientTemperature) * 1.5 + 50.0; // allow 50% extra power plus enough for an extra 50C
if (predictedMaxTemp > noWarnTemp)
{
- platform.MessageF(GENERIC_MESSAGE,
- "Warning: Heater %u appears to be over-powered. If left on at full power, its temperature is predicted to reach %dC.\n",
+ platform.MessageF(WarningMessage,
+ "Heater %u appears to be over-powered. If left on at full power, its temperature is predicted to reach %dC.\n",
heater, (int)predictedMaxTemp);
}
}
@@ -133,7 +133,7 @@ void PID::SwitchOn()
{
if (reprap.Debug(Module::moduleHeat))
{
- platform.MessageF(GENERIC_MESSAGE, "Heater %d not switched on due to temperature fault\n", heater);
+ platform.MessageF(WarningMessage, "Heater %d not switched on due to temperature fault\n", heater);
}
}
else if (model.IsEnabled())
@@ -153,7 +153,7 @@ void PID::SwitchOn()
}
if (reprap.Debug(Module::moduleHeat) && oldMode == HeaterMode::off)
{
- platform.MessageF(GENERIC_MESSAGE, "Heater %d switched on\n", heater);
+ platform.MessageF(GenericMessage, "Heater %d switched on\n", heater);
}
}
}
@@ -177,7 +177,7 @@ void PID::SwitchOff()
mode = HeaterMode::off;
if (reprap.Debug(Module::moduleHeat))
{
- platform.MessageF(GENERIC_MESSAGE, "Heater %d switched off\n", heater);
+ platform.MessageF(GenericMessage, "Heater %d switched off\n", heater);
}
}
}
@@ -216,7 +216,7 @@ void PID::Spin()
tuningTempReadings = nullptr;
}
mode = HeaterMode::fault;
- platform.MessageF(GENERIC_MESSAGE, "Error: Temperature reading fault on heater %d: %s\n", heater, TemperatureErrorString(err));
+ platform.MessageF(ErrorMessage, "Temperature reading fault on heater %d: %s\n", heater, TemperatureErrorString(err));
reprap.FlagTemperatureFault(heater);
}
}
@@ -268,8 +268,8 @@ void PID::Spin()
SetHeater(0.0); // do this here just to be sure
mode = HeaterMode::fault;
reprap.GetGCodes().CancelPrint(false, false);
- platform.MessageF(GENERIC_MESSAGE,
- "Error: heating fault on heater %d, temperature rising much more slowly than the expected %.1f" DEGREE_SYMBOL "C/sec\n",
+ platform.MessageF(ErrorMessage,
+ "Heating fault on heater %d, temperature rising much more slowly than the expected %.1f" DEGREE_SYMBOL "C/sec\n",
heater, expectedRate);
reprap.FlagTemperatureFault(heater);
}
@@ -295,7 +295,7 @@ void PID::Spin()
SetHeater(0.0); // do this here just to be sure
mode = HeaterMode::fault;
reprap.GetGCodes().CancelPrint(false, false);
- platform.MessageF(GENERIC_MESSAGE, "Error: heating fault on heater %d, temperature excursion exceeded %.1fC\n",
+ platform.MessageF(ErrorMessage, "Heating fault on heater %d, temperature excursion exceeded %.1fC\n",
heater, maxTempExcursion);
}
}
@@ -399,7 +399,7 @@ void PID::SetActiveTemperature(float t)
{
if (t > temperatureLimit)
{
- platform.MessageF(GENERIC_MESSAGE, "Error: Temperature %.1f too high for heater %d!\n", t, heater);
+ platform.MessageF(ErrorMessage, "Temperature %.1f too high for heater %d\n", t, heater);
}
else
{
@@ -415,7 +415,7 @@ void PID::SetStandbyTemperature(float t)
{
if (t > temperatureLimit)
{
- platform.MessageF(GENERIC_MESSAGE, "Error: Temperature %.1f too high for heater %d!\n", t, heater);
+ platform.MessageF(ErrorMessage, "Temperature %.1f too high for heater %d\n", t, heater);
}
else
{
@@ -615,7 +615,7 @@ void PID::DoTuningStep()
lastPwm = tuningPwm; // turn on heater at specified power
tuningReadingInterval = platform.HeatSampleInterval(); // reset sampling interval
mode = HeaterMode::tuning1;
- platform.Message(GENERIC_MESSAGE, "Auto tune phase 1, heater on\n");
+ platform.Message(GenericMessage, "Auto tune phase 1, heater on\n");
return;
}
if (millis() - tuningPhaseStartTime < 20000)
@@ -623,7 +623,7 @@ void PID::DoTuningStep()
// Allow up to 20 seconds for starting temperature to settle
return;
}
- platform.Message(GENERIC_MESSAGE, "Auto tune cancelled because starting temperature is not stable\n");
+ platform.Message(GenericMessage, "Auto tune cancelled because starting temperature is not stable\n");
break;
case HeaterMode::tuning1:
@@ -634,14 +634,14 @@ void PID::DoTuningStep()
const float extraTimeAllowed = (isBedOrChamberHeater) ? 60.0 : 30.0;
if (heatingTime > (uint32_t)((model.GetDeadTime() + extraTimeAllowed) * SecondsToMillis) && (temperature - tuningStartTemp) < 3.0)
{
- platform.Message(GENERIC_MESSAGE, "Auto tune cancelled because temperature is not increasing\n");
+ platform.Message(GenericMessage, "Auto tune cancelled because temperature is not increasing\n");
break;
}
const uint32_t timeoutMinutes = (isBedOrChamberHeater) ? 20 : 5;
if (heatingTime >= timeoutMinutes * 60 * (uint32_t)SecondsToMillis)
{
- platform.Message(GENERIC_MESSAGE, "Auto tune cancelled because target temperature was not reached\n");
+ platform.Message(GenericMessage, "Auto tune cancelled because target temperature was not reached\n");
break;
}
@@ -657,7 +657,7 @@ void PID::DoTuningStep()
mode = HeaterMode::tuning2;
lastPwm = 0.0;
SetHeater(0.0);
- platform.Message(GENERIC_MESSAGE, "Auto tune phase 2, heater off\n");
+ platform.Message(GenericMessage, "Auto tune phase 2, heater off\n");
}
}
return;
@@ -672,7 +672,7 @@ void PID::DoTuningStep()
{
return; // still waiting for peak temperature
}
- platform.Message(GENERIC_MESSAGE, "Auto tune cancelled because temperature is not falling\n");
+ platform.Message(GenericMessage, "Auto tune cancelled because temperature is not falling\n");
}
else if (peakIndex == 0)
{
@@ -680,7 +680,7 @@ void PID::DoTuningStep()
{
DisplayBuffer("At no peak found");
}
- platform.Message(GENERIC_MESSAGE, "Auto tune cancelled because temperature peak was not identified\n");
+ platform.Message(GenericMessage, "Auto tune cancelled because temperature peak was not identified\n");
}
else
{
@@ -693,7 +693,7 @@ void PID::DoTuningStep()
tuningPhaseStartTime = millis();
tuningReadingInterval = platform.HeatSampleInterval(); // reset sampling interval
mode = HeaterMode::tuning3;
- platform.MessageF(GENERIC_MESSAGE, "Auto tune phase 3, peak temperature was %.1f\n", tuningPeakTemperature);
+ platform.MessageF(GenericMessage, "Auto tune phase 3, peak temperature was %.1f\n", tuningPeakTemperature);
return;
}
}
@@ -831,14 +831,14 @@ void PID::CalculateModel()
tuned = SetModel(gain, tc, td, tuningPwm, true);
if (tuned)
{
- platform.MessageF(GENERIC_MESSAGE,
+ platform.MessageF(LoggedGenericMessage,
"Auto tune heater %d completed in %u sec\n"
"Use M307 H%d to see the result, or M500 to save the result in config-override.g\n",
heater, (millis() - tuningBeginTime)/(uint32_t)SecondsToMillis, heater);
}
else
{
- platform.MessageF(GENERIC_MESSAGE, "Auto tune of heater %u failed due to bad curve fit (G=%.1f, tc=%.1f, td=%.1f)\n", heater, gain, tc, td);
+ platform.MessageF(WarningMessage, "Auto tune of heater %u failed due to bad curve fit (G=%.1f, tc=%.1f, td=%.1f)\n", heater, gain, tc, td);
}
}
@@ -853,7 +853,7 @@ void PID::DisplayBuffer(const char *intro)
buf->catf(" %.1f", tuningTempReadings[i]);
}
buf->cat("\n");
- platform.Message(HOST_MESSAGE, buf);
+ platform.Message(UsbMessage, buf);
}
}
diff --git a/src/Heating/Sensors/CurrentLoopTemperatureSensor.cpp b/src/Heating/Sensors/CurrentLoopTemperatureSensor.cpp
index e6ba8a1c..9d672bc3 100644
--- a/src/Heating/Sensors/CurrentLoopTemperatureSensor.cpp
+++ b/src/Heating/Sensors/CurrentLoopTemperatureSensor.cpp
@@ -44,7 +44,7 @@ void CurrentLoopTemperatureSensor::Init()
if (lastResult != TemperatureError::success)
{
- reprap.GetPlatform().MessageF(GENERIC_MESSAGE, "Error: failed to initialise daughter board ADC: %s\n", TemperatureErrorString(lastResult));
+ reprap.GetPlatform().MessageF(ErrorMessage, "Failed to initialise daughter board ADC: %s\n", TemperatureErrorString(lastResult));
}
}
diff --git a/src/Heating/Sensors/RtdSensor31865.cpp b/src/Heating/Sensors/RtdSensor31865.cpp
index 2cd35cf6..79349d5c 100644
--- a/src/Heating/Sensors/RtdSensor31865.cpp
+++ b/src/Heating/Sensors/RtdSensor31865.cpp
@@ -141,7 +141,7 @@ void RtdSensor31865::Init()
if (rslt != TemperatureError::success)
{
- reprap.GetPlatform().MessageF(GENERIC_MESSAGE, "Error: failed to initialise RTD: %s\n", TemperatureErrorString(rslt));
+ reprap.GetPlatform().MessageF(ErrorMessage, "Failed to initialise RTD: %s\n", TemperatureErrorString(rslt));
}
}
diff --git a/src/Heating/Sensors/ThermocoupleSensor31856.cpp b/src/Heating/Sensors/ThermocoupleSensor31856.cpp
index 2adb19bb..eff6daaf 100644
--- a/src/Heating/Sensors/ThermocoupleSensor31856.cpp
+++ b/src/Heating/Sensors/ThermocoupleSensor31856.cpp
@@ -83,7 +83,7 @@ bool ThermocoupleSensor31856::Configure(unsigned int mCode, unsigned int heater,
if (gb.TryGetQuotedString('T', buf.GetRef(), seen))
{
const char *p;
- if (buf.strlen() == 1 && (p = strchr(TypeLetters, buf.c_str()[0])) != nullptr)
+ if (buf.strlen() == 1 && (p = strchr(TypeLetters, toupper(buf.c_str()[0]))) != nullptr)
{
thermocoupleType = p - TypeLetters;
}
@@ -125,7 +125,7 @@ void ThermocoupleSensor31856::Init()
if (rslt != TemperatureError::success)
{
- reprap.GetPlatform().MessageF(GENERIC_MESSAGE, "Error: failed to initialise thermocouple: %s\n", TemperatureErrorString(rslt));
+ reprap.GetPlatform().MessageF(ErrorMessage, "Failed to initialise thermocouple: %s\n", TemperatureErrorString(rslt));
}
}
diff --git a/src/Libraries/General/IP4String.cpp b/src/Libraries/General/IP4String.cpp
new file mode 100644
index 00000000..5b4091be
--- /dev/null
+++ b/src/Libraries/General/IP4String.cpp
@@ -0,0 +1,22 @@
+/*
+ * IPString.cpp
+ *
+ * Created on: 19 Sep 2017
+ * Author: David
+ */
+
+#include "IP4String.h"
+#include <cstdio>
+
+IP4String::IP4String(const uint8_t ip[4])
+{
+ snprintf(buf, sizeof(buf)/sizeof(buf[0]), "%u.%u.%u.%u", ip[0], ip[1], ip[2], ip[3]);
+}
+
+IP4String::IP4String(uint32_t ip)
+{
+ snprintf(buf, sizeof(buf)/sizeof(buf[0]), "%u.%u.%u.%u",
+ (unsigned int)(ip & 0xFFu), (unsigned int)((ip >> 8) & 0xFFu), (unsigned int)((ip >> 16) & 0xFFu), (unsigned int)((ip >> 24) & 0xFFu));
+}
+
+// End
diff --git a/src/Libraries/General/IP4String.h b/src/Libraries/General/IP4String.h
new file mode 100644
index 00000000..3fa84d9a
--- /dev/null
+++ b/src/Libraries/General/IP4String.h
@@ -0,0 +1,25 @@
+/*
+ * IPString.h
+ *
+ * Created on: 19 Sep 2017
+ * Author: David
+ */
+
+#ifndef SRC_LIBRARIES_GENERAL_IP4STRING_H_
+#define SRC_LIBRARIES_GENERAL_IP4STRING_H_
+
+#include <cstdint>
+
+// Class to convert an IPv4 address to a string representation
+class IP4String
+{
+public:
+ IP4String(const uint8_t ip[4]);
+ IP4String(uint32_t ip);
+ const char *c_str() const { return buf; }
+
+private:
+ char buf[16]; // long enough for e.g. "255.255.255.255" including a null terminator
+};
+
+#endif /* SRC_LIBRARIES_GENERAL_IP4STRING_H_ */
diff --git a/src/Libraries/General/StringRef.cpp b/src/Libraries/General/StringRef.cpp
index 78f5c154..290be8d4 100644
--- a/src/Libraries/General/StringRef.cpp
+++ b/src/Libraries/General/StringRef.cpp
@@ -46,6 +46,16 @@ int StringRef::catf(const char *fmt, ...) const
return 0;
}
+int StringRef::vcatf(const char *fmt, va_list vargs) const
+{
+ size_t n = strlen();
+ if (n + 1 < len) // if room for at least 1 more character and a null
+ {
+ return vsnprintf(p + n, len - n, fmt, vargs) + n;
+ }
+ return 0;
+}
+
// This is quicker than printf for printing constant strings
size_t StringRef::copy(const char* src) const
{
diff --git a/src/Libraries/General/StringRef.h b/src/Libraries/General/StringRef.h
index a8be91ad..d4955774 100644
--- a/src/Libraries/General/StringRef.h
+++ b/src/Libraries/General/StringRef.h
@@ -36,6 +36,7 @@ public:
int printf(const char *fmt, ...) const;
int vprintf(const char *fmt, va_list vargs) const;
int catf(const char *fmt, ...) const;
+ int vcatf(const char *fmt, va_list vargs) const;
size_t copy(const char* src) const;
size_t cat(const char *src) const;
size_t cat(char c) const;
diff --git a/src/Logger.cpp b/src/Logger.cpp
new file mode 100644
index 00000000..c944fe0c
--- /dev/null
+++ b/src/Logger.cpp
@@ -0,0 +1,142 @@
+/*
+ * Logger.cpp
+ *
+ * Created on: 17 Sep 2017
+ * Author: David
+ */
+
+#include "RepRapFirmware.h"
+#include "Logger.h"
+#include "OutputMemory.h"
+#include "RepRap.h"
+#include "Platform.h"
+
+// Simple lock class that sets a variable true when it is created and makes sure it gets set false when it falls out of scope
+class Lock
+{
+public:
+ Lock(bool& pb) : b(pb) { b = true; }
+ ~Lock() { b = false; }
+
+private:
+ bool& b;
+};
+
+Logger::Logger() : logFile(), dirty(false), inLogger(false)
+{
+}
+
+void Logger::Start(time_t time, const StringRef& filename)
+{
+ if (!inLogger)
+ {
+ Lock loggerLock(inLogger);
+ FileStore * const f = reprap.GetPlatform().GetFileStore(SYS_DIR, filename.Pointer(), OpenMode::append);
+ if (f != nullptr)
+ {
+ logFile.Set(f);
+ logFile.Seek(logFile.Length());
+ InternalLogMessage(time, "Event logging started\n");
+ }
+ }
+}
+
+void Logger::Stop(time_t time)
+{
+ if (logFile.IsLive() && !inLogger)
+ {
+ Lock loggerLock(inLogger);
+ InternalLogMessage(time, "Event logging stopped\n");
+ logFile.Close();
+ }
+}
+
+void Logger::LogMessage(time_t time, const char *message)
+{
+ if (logFile.IsLive() && !inLogger)
+ {
+ Lock loggerLock(inLogger);
+ InternalLogMessage(time, message);
+ }
+}
+
+void Logger::LogMessage(time_t time, OutputBuffer *buf)
+{
+ if (logFile.IsLive() && !inLogger)
+ {
+ Lock loggerLock(inLogger);
+ bool ok = WriteDateTime(time);
+ if (ok)
+ {
+ ok = buf->WriteToFile(logFile);
+ }
+
+ if (ok)
+ {
+ dirty = true;
+ }
+ else
+ {
+ logFile.Close();
+ }
+ }
+}
+
+// Version of LogMessage for when we already know we want to proceed and we have already set inLogger
+void Logger::InternalLogMessage(time_t time, const char *message)
+{
+ bool ok = WriteDateTime(time);
+ if (ok)
+ {
+ const size_t len = strlen(message);
+ if (len != 0)
+ {
+ ok = logFile.Write(message, len);
+ }
+ if (ok && (len == 0 || message[len - 1] != '\n'))
+ {
+ ok = logFile.Write('\n');
+ }
+ }
+
+ if (ok)
+ {
+ dirty = true;
+ }
+ else
+ {
+ logFile.Close();
+ }
+}
+
+void Logger::Flush()
+{
+ if (logFile.IsLive() && dirty && !inLogger)
+ {
+ Lock loggerLock(inLogger);
+ logFile.Flush();
+ dirty = false;
+ }
+}
+
+// Write the data and time to the file followed by a space.
+// Caller must already have checked and set inLogger.
+bool Logger::WriteDateTime(time_t time)
+{
+ char bufferSpace[30];
+ StringRef buf(bufferSpace, ARRAY_SIZE(bufferSpace));
+ if (time == 0)
+ {
+ const uint32_t timeSincePowerUp = (uint32_t)(millis64()/1000u);
+ buf.printf("power up + %02u:%02u:%02u ", timeSincePowerUp/3600u, (timeSincePowerUp % 3600u)/60u, timeSincePowerUp % 60u);
+ }
+ else
+ {
+ const struct tm * const timeInfo = gmtime(&time);
+ buf.printf("%04u-%02u-%02u %02u:%02u:%02u ",
+ timeInfo->tm_year + 1900, timeInfo->tm_mon + 1, timeInfo->tm_mday, timeInfo->tm_hour, timeInfo->tm_min, timeInfo->tm_sec);
+ }
+ return logFile.Write(buf.Pointer());
+}
+
+// End
diff --git a/src/Logger.h b/src/Logger.h
new file mode 100644
index 00000000..79b8df19
--- /dev/null
+++ b/src/Logger.h
@@ -0,0 +1,37 @@
+/*
+ * Logger.h
+ *
+ * Created on: 17 Sep 2017
+ * Author: David
+ */
+
+#ifndef SRC_LOGGER_H_
+#define SRC_LOGGER_H_
+
+#include <ctime>
+#include "Storage/FileData.h"
+
+class OutputBuffer;
+
+class Logger
+{
+public:
+ Logger();
+
+ void Start(time_t time, const StringRef& file);
+ void Stop(time_t time);
+ void LogMessage(time_t time, const char *message);
+ void LogMessage(time_t time, OutputBuffer *buf);
+ void Flush();
+ bool IsActive() const { return logFile.IsLive(); }
+
+private:
+ bool WriteDateTime(time_t time);
+ void InternalLogMessage(time_t time, const char *message);
+
+ FileData logFile;
+ bool dirty;
+ bool inLogger;
+};
+
+#endif /* SRC_LOGGER_H_ */
diff --git a/src/MessageType.h b/src/MessageType.h
index 816a0326..d586b74a 100644
--- a/src/MessageType.h
+++ b/src/MessageType.h
@@ -8,18 +8,35 @@
#ifndef MESSAGETYPE_H_
#define MESSAGETYPE_H_
-// Supported message destinations
-enum MessageType
+#include <cstdint>
+
+// Supported message destinations. This is now a bitmap.
+enum MessageType : uint16_t
{
- AUX_MESSAGE, // A message that is to be sent to the panel
- AUX2_MESSAGE, // A message that is to be sent to the second auxiliary device
- HOST_MESSAGE, // A message that is to be sent in non-blocking mode to the host via USB
- DEBUG_MESSAGE, // A debug message to send in blocking mode to USB
- HTTP_MESSAGE, // A message that is to be sent to the web (HTTP)
- TELNET_MESSAGE, // A message that is to be sent to a Telnet client
- GENERIC_MESSAGE, // A message that is to be sent to the web, USB and panel
- FIRMWARE_UPDATE_MESSAGE, // A message that conveys progress of a firmware update
- NETWORK_INFO_MESSAGE // A message that conveys information about the state of the network interface
+ // Destinations
+ UsbMessage = 0x01, // A message that is to be sent in non-blocking mode to the host via USB
+ BlockingUsbMessage = 0x02, // A message to be sent ot USB in blocking mode
+ LcdMessage = 0x04, // A message that is to be sent to the panel
+ ImmediateLcdMessage = 0x08, // A message to be sent to LCD in immediate mode
+ HttpMessage = 0x10, // A message that is to be sent to the web (HTTP)
+ TelnetMessage = 0x20, // A message that is to be sent to a Telnet client
+ AuxMessage = 0x40, // A message that is to be sent to the second auxiliary device
+ LogMessage = 0x80, // A message to be written to the log file
+
+ // Special indicators. These are not processed when calling the version of Platform::Message that takes an OutputBuffer.
+ ErrorMessageFlag = 0x100, // This is an error message
+ WarningMessageFlag = 0x200, // This is a warning message
+
+ // Common combinations
+ DebugMessage = BlockingUsbMessage, // A debug message to send in blocking mode to USB
+ GenericMessage = UsbMessage | LcdMessage | HttpMessage | TelnetMessage | AuxMessage,
+ // A message that is to be sent to the web, Telnet, USB and panel
+ LoggedGenericMessage = GenericMessage | LogMessage, // As GenericMessage that is also logged
+ ErrorMessage = GenericMessage | LogMessage | ErrorMessageFlag, // An error message
+ WarningMessage = GenericMessage | LogMessage | WarningMessageFlag, // A warning message
+ FirmwareUpdateMessage = UsbMessage | ImmediateLcdMessage, // A message that conveys progress of a firmware update
+ FirmwareUpdateErrorMessage = FirmwareUpdateMessage | ErrorMessageFlag, // A message that reports an error during a firmware update
+ NetworkInfoMessage = UsbMessage | LcdMessage | AuxMessage | LogMessage // A message that conveys information about the state of the network interface
};
#endif /* MESSAGETYPE_H_ */
diff --git a/src/Movement/BedProbing/RandomProbePointSet.cpp b/src/Movement/BedProbing/RandomProbePointSet.cpp
index c52c82f5..4dc03e04 100644
--- a/src/Movement/BedProbing/RandomProbePointSet.cpp
+++ b/src/Movement/BedProbing/RandomProbePointSet.cpp
@@ -72,15 +72,16 @@ void RandomProbePointSet::ClearProbeHeights()
}
}
-void RandomProbePointSet::SetProbedBedEquation(size_t numPoints, StringRef& reply)
+bool RandomProbePointSet::SetProbedBedEquation(size_t numPoints, StringRef& reply)
{
if (!GoodProbePointOrdering(numPoints))
{
- reply.printf("Error: probe points P0 to P%u must be in clockwise order starting near X=0 Y=0", min<unsigned int>(numPoints, 4) - 1);
+ reply.printf("Probe points P0 to P%u must be in clockwise order starting near X=0 Y=0", min<unsigned int>(numPoints, 4) - 1);
if (numPoints >= 5)
{
reply.cat(" and P4 must be near the centre");
}
+ return true;
}
else
{
@@ -141,8 +142,8 @@ void RandomProbePointSet::SetProbedBedEquation(size_t numPoints, StringRef& repl
break;
default:
- reprap.GetPlatform().MessageF(GENERIC_MESSAGE, "Bed calibration error: %d points provided but only 3, 4 and 5 supported\n", numPoints);
- return;
+ reply.printf("Bed calibration: %d points provided but only 3, 4 and 5 supported", numPoints);
+ return true;
}
numBedCompensationPoints = numPoints;
@@ -154,7 +155,7 @@ void RandomProbePointSet::SetProbedBedEquation(size_t numPoints, StringRef& repl
reply.catf(" [%.1f, %.1f, %.3f]", xBedProbePoints[point], yBedProbePoints[point], zBedProbePoints[point]);
}
}
- reply.cat("\n");
+ return false;
}
// Compute the interpolated height error at the specified point
@@ -295,7 +296,7 @@ float RandomProbePointSet::TriangleZ(float x, float y) const
return l1 * baryZBedProbePoints[i] + l2 * baryZBedProbePoints[j] + l3 * baryZBedProbePoints[4];
}
}
- reprap.GetPlatform().Message(GENERIC_MESSAGE, "Triangle interpolation: point outside all triangles!\n");
+ reprap.GetPlatform().Message(WarningMessage, "Triangle interpolation: point outside all triangles!\n");
return 0.0;
}
diff --git a/src/Movement/BedProbing/RandomProbePointSet.h b/src/Movement/BedProbing/RandomProbePointSet.h
index 8c09692f..67f0ce97 100644
--- a/src/Movement/BedProbing/RandomProbePointSet.h
+++ b/src/Movement/BedProbing/RandomProbePointSet.h
@@ -35,7 +35,7 @@ public:
void SetZBedProbePoint(size_t index, float z, bool wasXyCorrected, bool wasError); // Record the Z coordinate of a probe point
void ClearProbeHeights(); // Clear out the Z heights so that we don't re-use old points
- void SetProbedBedEquation(size_t numPoints, StringRef& reply); // When we have a full set of probed points, work out the bed's equation
+ bool SetProbedBedEquation(size_t numPoints, StringRef& reply); // When we have a full set of probed points, work out the bed's equation
void SetIdentity() { numBedCompensationPoints = 0; } // Set identity transform
float GetInterpolatedHeightError(float x, float y) const; // Compute the interpolated height error at the specified point
diff --git a/src/Movement/DDA.cpp b/src/Movement/DDA.cpp
index a25b9e9d..319a5341 100644
--- a/src/Movement/DDA.cpp
+++ b/src/Movement/DDA.cpp
@@ -12,7 +12,7 @@
#include "Kinematics/LinearDeltaKinematics.h" // for DELTA_AXES
#ifdef DUET_NG
-# define DDA_MOVE_DEBUG (1)
+# define DDA_MOVE_DEBUG (0)
#else
// On the wired Duets we don't have enough RAM to support this
# define DDA_MOVE_DEBUG (0)
@@ -48,7 +48,7 @@ static size_t savedMovePointer = 0;
for (size_t i = 0; i < NumSavedMoves; ++i)
{
const MoveParameters& m = savedMoves[savedMovePointer];
- reprap.GetPlatform().MessageF(DEBUG_MESSAGE, "%f,%f,%f,%f,%f,%f\n", m.accelDistance, m.steadyDistance, m.decelDistance, m.startSpeed, m.topSpeed, m.endSpeed);
+ reprap.GetPlatform().MessageF(DebugMessage, "%f,%f,%f,%f,%f,%f\n", m.accelDistance, m.steadyDistance, m.decelDistance, m.startSpeed, m.topSpeed, m.endSpeed);
savedMovePointer = (savedMovePointer + 1) % NumSavedMoves;
}
}
diff --git a/src/Movement/Kinematics/Kinematics.cpp b/src/Movement/Kinematics/Kinematics.cpp
index 7de5259b..7b6d0ce8 100644
--- a/src/Movement/Kinematics/Kinematics.cpp
+++ b/src/Movement/Kinematics/Kinematics.cpp
@@ -18,15 +18,9 @@
const char *Kinematics::HomeAllFileName = "homeall.g";
const char * const Kinematics::StandardHomingFileNames[] = AXES_("homex.g", "homey.g", "homez.g", "homeu.g", "homev.g", "homew.g", "homea.g", "homeb.g", "homec.g");
-// Constructor for non-segmented kinematics
-Kinematics::Kinematics(KinematicsType t)
- : useSegmentation(false), useRawG0(true), type(t)
-{
-}
-
-// Constructor for segmented kinematics
+// Constructor. Pass segsPerSecond <= 0.0 to get non-segmented kinematics.
Kinematics::Kinematics(KinematicsType t, float segsPerSecond, float minSegLength, bool doUseRawG0)
- : segmentsPerSecond(segsPerSecond), minSegmentLength(minSegLength), useSegmentation(true), useRawG0(doUseRawG0), type(t)
+ : segmentsPerSecond(segsPerSecond), minSegmentLength(minSegLength), useSegmentation(segsPerSecond > 0.0), useRawG0(doUseRawG0), type(t)
{
}
@@ -47,7 +41,7 @@ bool Kinematics::Configure(unsigned int mCode, GCodeBuffer& gb, StringRef& reply
}
// Return true if the specified XY position is reachable by the print head reference point.
-// This default implementation assumes a rectangular reachable area, so it just uses the bed dimensions give in the M280 command.
+// This default implementation assumes a rectangular reachable area, so it just uses the bed dimensions give in the M208 command.
bool Kinematics::IsReachable(float x, float y) const
{
const Platform& platform = reprap.GetPlatform();
diff --git a/src/Movement/Kinematics/Kinematics.h b/src/Movement/Kinematics/Kinematics.h
index 3ce7c256..91ec36e0 100644
--- a/src/Movement/Kinematics/Kinematics.h
+++ b/src/Movement/Kinematics/Kinematics.h
@@ -85,8 +85,9 @@ public:
virtual bool SupportsAutoCalibration() const { return false; }
// Perform auto calibration. Override this implementation in kinematics that support it. Caller already owns the movement lock.
- virtual void DoAutoCalibration(size_t numFactors, const RandomProbePointSet& probePoints, StringRef& reply)
- pre(SupportsAutoCalibration()) { }
+ // Return true if an error occurred.
+ virtual bool DoAutoCalibration(size_t numFactors, const RandomProbePointSet& probePoints, StringRef& reply)
+ pre(SupportsAutoCalibration()) { return false; }
// Set the default parameters that are changed by auto calibration back to their defaults.
// Do nothing if auto calibration is not supported.
@@ -166,10 +167,7 @@ public:
float GetMinSegmentLength() const pre(UseSegmentation()) { return minSegmentLength; }
protected:
- // This constructor is used by derived classes that implement non-segmented linear motion
- Kinematics(KinematicsType t);
-
- // This constructor is used by derived classes that implement segmented linear motion
+ // Constructor. Pass segsPerSecond <= 0.0 to get non-segmented motion.
Kinematics(KinematicsType t, float segsPerSecond, float minSegLength, bool doUseRawG0);
// Apply the M208 limits to the Cartesian position that the user wants to move to for all axes from the specified one upwards
diff --git a/src/Movement/Kinematics/LinearDeltaKinematics.cpp b/src/Movement/Kinematics/LinearDeltaKinematics.cpp
index 9acc9313..1a700bf6 100644
--- a/src/Movement/Kinematics/LinearDeltaKinematics.cpp
+++ b/src/Movement/Kinematics/LinearDeltaKinematics.cpp
@@ -12,7 +12,7 @@
#include "RepRap.h"
#include "Storage/FileStore.h"
-LinearDeltaKinematics::LinearDeltaKinematics() : Kinematics(KinematicsType::linearDelta)
+LinearDeltaKinematics::LinearDeltaKinematics() : Kinematics(KinematicsType::linearDelta, -1.0, 0.0, true)
{
Init();
}
@@ -224,15 +224,15 @@ void LinearDeltaKinematics::GetAssumedInitialPosition(size_t numAxes, float posi
}
// Auto calibrate from a set of probe points
-void LinearDeltaKinematics::DoAutoCalibration(size_t numFactors, const RandomProbePointSet& probePoints, StringRef& reply)
+bool LinearDeltaKinematics::DoAutoCalibration(size_t numFactors, const RandomProbePointSet& probePoints, StringRef& reply)
{
const size_t NumDeltaFactors = 9; // maximum number of delta machine factors we can adjust
const size_t numPoints = probePoints.NumberOfProbePoints();
if (numFactors < 3 || numFactors > NumDeltaFactors || numFactors == 5)
{
- reply.printf("Error: Delta calibration with %d factors requested but only 3, 4, 6, 7, 8 and 9 supported", numFactors);
- return;
+ reply.printf("Delta calibration with %d factors requested but only 3, 4, 6, 7, 8 and 9 supported", numFactors);
+ return true;
}
if (reprap.Debug(moduleMove))
@@ -396,8 +396,10 @@ void LinearDeltaKinematics::DoAutoCalibration(size_t numFactors, const RandomPro
reply.printf("Calibrated %d factors using %d points, deviation before %.3f after %.3f",
numFactors, numPoints, sqrt(initialSumOfSquares/numPoints), expectedRmsError);
+ reprap.GetPlatform().MessageF(LogMessage, "%s\n", reply.Pointer());
doneAutoCalibration = true;
+ return false;
}
// Return the type of motion computation needed by an axis
diff --git a/src/Movement/Kinematics/LinearDeltaKinematics.h b/src/Movement/Kinematics/LinearDeltaKinematics.h
index 4d54e486..df10a1b1 100644
--- a/src/Movement/Kinematics/LinearDeltaKinematics.h
+++ b/src/Movement/Kinematics/LinearDeltaKinematics.h
@@ -29,7 +29,7 @@ public:
bool CartesianToMotorSteps(const float machinePos[], const float stepsPerMm[], size_t numVisibleAxes, size_t numTotalAxes, int32_t motorPos[]) const override;
void MotorStepsToCartesian(const int32_t motorPos[], const float stepsPerMm[], size_t numVisibleAxes, size_t numTotalAxes, float machinePos[]) const override;
bool SupportsAutoCalibration() const override { return true; }
- void DoAutoCalibration(size_t numFactors, const RandomProbePointSet& probePoints, StringRef& reply) override;
+ bool DoAutoCalibration(size_t numFactors, const RandomProbePointSet& probePoints, StringRef& reply) override;
void SetCalibrationDefaults() override { Init(); }
bool WriteCalibrationParameters(FileStore *f) const override;
float GetTiltCorrection(size_t axis) const override;
diff --git a/src/Movement/Kinematics/ScaraKinematics.cpp b/src/Movement/Kinematics/ScaraKinematics.cpp
index 8fd1cad2..18674867 100644
--- a/src/Movement/Kinematics/ScaraKinematics.cpp
+++ b/src/Movement/Kinematics/ScaraKinematics.cpp
@@ -13,7 +13,7 @@
#include "Movement/DDA.h"
ScaraKinematics::ScaraKinematics()
- : Kinematics(KinematicsType::scara, DefaultSegmentsPerSecond, DefaultMinSegmentSize, true),
+ : ZLeadscrewKinematics(KinematicsType::scara, DefaultSegmentsPerSecond, DefaultMinSegmentSize, true),
proximalArmLength(DefaultProximalArmLength), distalArmLength(DefaultDistalArmLength), xOffset(0.0), yOffset(0.0)
{
thetaLimits[0] = DefaultMinTheta;
@@ -163,7 +163,7 @@ bool ScaraKinematics::Configure(unsigned int mCode, GCodeBuffer& gb, StringRef&
}
else
{
- return Kinematics::Configure(mCode, gb, reply, error);
+ return ZLeadscrewKinematics::Configure(mCode, gb, reply, error);
}
}
@@ -172,8 +172,8 @@ bool ScaraKinematics::Configure(unsigned int mCode, GCodeBuffer& gb, StringRef&
bool ScaraKinematics::IsReachable(float x, float y) const
{
// TODO The following isn't quite right, in particular it doesn't take account of the maximum arm travel
- const float r = sqrtf(fsquare(x) + fsquare(y));
- return r >= minRadius && r <= maxRadius && x > 0.0;
+ const float r = sqrtf(fsquare(x + xOffset) + fsquare(y + yOffset));
+ return r >= minRadius && r <= maxRadius && (x + xOffset) > 0.0;
}
// Limit the Cartesian position that the user wants to move to
diff --git a/src/Movement/Kinematics/ScaraKinematics.h b/src/Movement/Kinematics/ScaraKinematics.h
index 058ababf..248d9008 100644
--- a/src/Movement/Kinematics/ScaraKinematics.h
+++ b/src/Movement/Kinematics/ScaraKinematics.h
@@ -8,7 +8,7 @@
#ifndef SRC_MOVEMENT_KINEMATICS_SCARAKINEMATICS_H_
#define SRC_MOVEMENT_KINEMATICS_SCARAKINEMATICS_H_
-#include "Kinematics.h"
+#include "ZLeadscrewKinematics.h"
// Standard setup for SCARA machines assumed by this firmware
// The X motor output drives the proximal arm joint, unless remapped using M584
@@ -19,7 +19,7 @@
// Phi is the angle of the distal arm relative to the Cartesian X axis. Therefore the angle of the distal arm joint is (phi - theta).
// The M92 steps/mm settings for X and Y are interpreted as steps per degree of theta and phi respectively.
-class ScaraKinematics : public Kinematics
+class ScaraKinematics : public ZLeadscrewKinematics
{
public:
// Constructors
@@ -30,7 +30,6 @@ public:
bool Configure(unsigned int mCode, GCodeBuffer& gb, StringRef& reply, bool& error) override;
bool CartesianToMotorSteps(const float machinePos[], const float stepsPerMm[], size_t numVisibleAxes, size_t numTotalAxes, int32_t motorPos[]) const override;
void MotorStepsToCartesian(const int32_t motorPos[], const float stepsPerMm[], size_t numVisibleAxes, size_t numTotalAxes, float machinePos[]) const override;
- bool SupportsAutoCalibration() const override { return false; }
bool IsReachable(float x, float y) const override;
bool LimitPosition(float position[], size_t numAxes, AxesBitmap axesHomed) const override;
void GetAssumedInitialPosition(size_t numAxes, float positions[]) const override;
diff --git a/src/Movement/Kinematics/ZLeadscrewKinematics.cpp b/src/Movement/Kinematics/ZLeadscrewKinematics.cpp
index 00432ca2..7d3e6c93 100644
--- a/src/Movement/Kinematics/ZLeadscrewKinematics.cpp
+++ b/src/Movement/Kinematics/ZLeadscrewKinematics.cpp
@@ -12,7 +12,13 @@
const float M3ScrewPitch = 0.5;
-ZLeadscrewKinematics::ZLeadscrewKinematics(KinematicsType k) : Kinematics(k), numLeadscrews(0), maxCorrection(1.0), screwPitch(M3ScrewPitch)
+ZLeadscrewKinematics::ZLeadscrewKinematics(KinematicsType k)
+ : Kinematics(k, -1.0, 0.0, true), numLeadscrews(0), maxCorrection(1.0), screwPitch(M3ScrewPitch)
+{
+}
+
+ZLeadscrewKinematics::ZLeadscrewKinematics(KinematicsType k, float segsPerSecond, float minSegLength, bool doUseRawG0)
+ : Kinematics(k, segsPerSecond, minSegLength, doUseRawG0), numLeadscrews(0), maxCorrection(1.0), screwPitch(M3ScrewPitch)
{
}
@@ -84,16 +90,17 @@ bool ZLeadscrewKinematics::SupportsAutoCalibration() const
}
// Perform auto calibration. Override this implementation in kinematics that support it. Caller already owns the GCode movement lock.
-void ZLeadscrewKinematics::DoAutoCalibration(size_t numFactors, const RandomProbePointSet& probePoints, StringRef& reply)
+bool ZLeadscrewKinematics::DoAutoCalibration(size_t numFactors, const RandomProbePointSet& probePoints, StringRef& reply)
{
if (!SupportsAutoCalibration()) // should be checked by caller, but check it here too
{
- return;
+ return false;
}
if (numFactors != numLeadscrews)
{
- reply.printf("Error: Number of calibration factors (%u) not equal to number of leadscrews (%u)", numFactors, numLeadscrews);
+ reply.printf("Number of calibration factors (%u) not equal to number of leadscrews (%u)", numFactors, numLeadscrews);
+ return true;
}
const size_t numPoints = probePoints.NumberOfProbePoints();
@@ -262,44 +269,43 @@ void ZLeadscrewKinematics::DoAutoCalibration(size_t numFactors, const RandomProb
if (haveNaN)
{
- reply.printf("Error: calibration failed, computed corrections:");
- AppendCorrections(solution, reply);
- }
- else if (haveLargeCorrection)
- {
- reply.printf("Error: some computed corrections exceed configured limit of %.02fmm:", maxCorrection);
+ reply.printf("Calibration failed, computed corrections:");
AppendCorrections(solution, reply);
+ return true;
}
else
{
const size_t numZDrivers = reprap.GetPlatform().GetAxisDriversConfig(Z_AXIS).numDrivers;
if (numZDrivers == numLeadscrews)
{
- reprap.GetMove().AdjustLeadscrews(solution);
- reply.printf("Leadscrew adjustments made:");
- AppendCorrections(solution, reply);
- reply.catf(", points used %d, deviation before %.3f after %.3f",
- numPoints, sqrt(initialSumOfSquares/numPoints), sqrtf(sumOfSquares/numPoints));
+ if (haveLargeCorrection)
+ {
+ reply.printf("Some computed corrections exceed configured limit of %.02fmm:", maxCorrection);
+ AppendCorrections(solution, reply);
+ return true;
+ }
+ else
+ {
+ reprap.GetMove().AdjustLeadscrews(solution);
+ reply.printf("Leadscrew adjustments made:");
+ AppendCorrections(solution, reply);
+ reply.catf(", points used %d, deviation before %.3f after %.3f",
+ numPoints, sqrt(initialSumOfSquares/numPoints), sqrtf(sumOfSquares/numPoints));
+ reprap.GetPlatform().MessageF(LogMessage, "%s\n", reply.Pointer());
+ }
}
else
{
// User wants manual corrections for bed levelling screws.
- // Pick the one with the smallest adjustment to leave alone.
- float smallestCorrection = solution[0];
- for (size_t i = 1; i < numLeadscrews; ++i)
- {
- if (fabs(solution[i]) < fabs(smallestCorrection))
- {
- smallestCorrection = solution[i];
- }
- }
+ // Leave the first one alone.
reply.printf("Manual corrections required:");
for (size_t i = 0; i < numLeadscrews; ++i)
{
- const float netAdjustment = solution[i] - smallestCorrection;
+ const float netAdjustment = solution[i] - solution[0];
reply.catf(" %.2f turn %s (%.2fmm)", fabs(netAdjustment)/screwPitch, (netAdjustment > 0) ? "down" : "up", netAdjustment);
}
}
+ return false;
}
}
diff --git a/src/Movement/Kinematics/ZLeadscrewKinematics.h b/src/Movement/Kinematics/ZLeadscrewKinematics.h
index b7a00596..a6caa4a5 100644
--- a/src/Movement/Kinematics/ZLeadscrewKinematics.h
+++ b/src/Movement/Kinematics/ZLeadscrewKinematics.h
@@ -10,13 +10,17 @@
#include "Kinematics.h"
+// This is used as the base class for any kinematic that supports auto or manual bed levelling (as distinct from bed compensation)
+// using leadscrews or bed adjusting screws.
class ZLeadscrewKinematics : public Kinematics
{
public:
ZLeadscrewKinematics(KinematicsType k);
+ ZLeadscrewKinematics(KinematicsType t, float segsPerSecond, float minSegLength, bool doUseRawG0);
+
bool Configure(unsigned int mCode, GCodeBuffer& gb, StringRef& reply, bool& error) override;
bool SupportsAutoCalibration() const override;
- void DoAutoCalibration(size_t numFactors, const RandomProbePointSet& probePoints, StringRef& reply) override;
+ bool DoAutoCalibration(size_t numFactors, const RandomProbePointSet& probePoints, StringRef& reply) override;
#ifdef DUET_NG
bool WriteResumeSettings(FileStore *f) const override;
diff --git a/src/Movement/Move.cpp b/src/Movement/Move.cpp
index 7bfee5ee..29166bb6 100644
--- a/src/Movement/Move.cpp
+++ b/src/Movement/Move.cpp
@@ -72,8 +72,8 @@ void Move::Init()
usingMesh = false;
useTaper = false;
- longWait = reprap.GetPlatform().Time();
- idleTimeout = DEFAULT_IDLE_TIMEOUT;
+ longWait = millis();
+ idleTimeout = DefaultIdleTimeout;
iState = IdleState::idle;
idleCount = 0;
@@ -256,7 +256,7 @@ void Move::Spin()
}
else
{
- Platform::DisableStepInterrupt(); // should be disabled already because we weren't executing a move, but make sure
+ Platform::DisableStepInterrupt(); // should be disabled already because we weren't executing a move, but make sure
if (StartNextMove(Platform::GetInterruptClocks())) // start the next move
{
Interrupt();
@@ -264,15 +264,18 @@ void Move::Spin()
}
iState = IdleState::busy;
}
- else if (!simulationMode != 0 && iState == IdleState::busy && !reprap.GetGCodes().IsPaused() && idleTimeout > 0.0)
+ else if (simulationMode != 0)
{
- lastMoveTime = reprap.GetPlatform().Time(); // record when we first noticed that the machine was idle
- iState = IdleState::timing;
- }
- else if (!simulationMode != 0 && iState == IdleState::timing && reprap.GetPlatform().Time() - lastMoveTime >= idleTimeout)
- {
- reprap.GetPlatform().SetDriversIdle(); // put all drives in idle hold
- iState = IdleState::idle;
+ if (iState == IdleState::busy && !reprap.GetGCodes().IsPaused())
+ {
+ lastMoveTime = millis(); // record when we first noticed that the machine was idle
+ iState = IdleState::timing;
+ }
+ else if (iState == IdleState::timing && millis() - lastMoveTime >= idleTimeout)
+ {
+ reprap.GetPlatform().SetDriversIdle(); // put all drives in idle hold
+ iState = IdleState::idle;
+ }
}
}
}
@@ -534,7 +537,7 @@ void Move::Diagnostics(MessageType mtype)
// For debugging
if (sqCount != 0)
{
- p.AppendMessage(GENERIC_MESSAGE, "Average sqrt times %.2f, %.2f, count %u, errors %u, last %" PRIu64 " %u %u\n",
+ p.AppendMessage(GenericMessage, "Average sqrt times %.2f, %.2f, count %u, errors %u, last %" PRIu64 " %u %u\n",
(float)sqSum1/sqCount, (float)sqSum2/sqCount, sqCount, sqErrors, lastNum, lastRes1, lastRes2);
sqSum1 = sqSum2 = sqCount = sqErrors = 0;
}
@@ -560,7 +563,7 @@ void Move::SetPositions(const float move[DRIVES])
}
else
{
- reprap.GetPlatform().Message(GENERIC_MESSAGE, "SetPositions called when DDA ring not empty\n");
+ reprap.GetPlatform().Message(ErrorMessage, "SetPositions called when DDA ring not empty\n");
}
}
@@ -809,11 +812,12 @@ void Move::SetAxisCompensation(unsigned int axis, float tangent)
}
}
-// Calibrate or set the bed equation after probing.
+// Calibrate or set the bed equation after probing, returning true if an error occurred
// sParam is the value of the S parameter in the G30 command that provoked this call.
// Caller already owns the GCode movement lock.
-void Move::FinishedBedProbing(int sParam, StringRef& reply)
+bool Move::FinishedBedProbing(int sParam, StringRef& reply)
{
+ bool error = false;
const size_t numPoints = probePoints.NumberOfProbePoints();
if (sParam < 0)
@@ -823,7 +827,8 @@ void Move::FinishedBedProbing(int sParam, StringRef& reply)
}
else if (numPoints < (size_t)sParam)
{
- reprap.GetPlatform().MessageF(GENERIC_MESSAGE, "Bed calibration error: %d factor calibration requested but only %d points provided\n", sParam, numPoints);
+ reply.printf("Bed calibration : %d factor calibration requested but only %d points provided\n", sParam, numPoints);
+ error = true;
}
else
{
@@ -839,21 +844,23 @@ void Move::FinishedBedProbing(int sParam, StringRef& reply)
if (!probePoints.GoodProbePoints(numPoints))
{
- reply.cat("Compensation or calibration cancelled due to probing errors");
+ reply.copy("Compensation or calibration cancelled due to probing errors");
+ error = true;
}
else if (kinematics->SupportsAutoCalibration())
{
- kinematics->DoAutoCalibration(sParam, probePoints, reply);
+ error = kinematics->DoAutoCalibration(sParam, probePoints, reply);
}
else
{
- probePoints.SetProbedBedEquation(sParam, reply);
+ error = probePoints.SetProbedBedEquation(sParam, reply);
}
}
// Clear out the Z heights so that we don't re-use old points.
// This allows us to use different numbers of probe point on different occasions.
probePoints.ClearProbeHeights();
+ return error;
}
// Perform motor endpoint adjustment
@@ -1031,7 +1038,7 @@ void Move::SetXYBedProbePoint(size_t index, float x, float y)
{
if (index >= MaxProbePoints)
{
- reprap.GetPlatform().Message(GENERIC_MESSAGE, "Z probe point index out of range.\n");
+ reprap.GetPlatform().Message(ErrorMessage, "Z probe point index out of range.\n");
}
else
{
@@ -1043,7 +1050,7 @@ void Move::SetZBedProbePoint(size_t index, float z, bool wasXyCorrected, bool wa
{
if (index >= MaxProbePoints)
{
- reprap.GetPlatform().Message(GENERIC_MESSAGE, "Z probe point Z index out of range.\n");
+ reprap.GetPlatform().Message(ErrorMessage, "Z probe point Z index out of range.\n");
}
else
{
@@ -1093,6 +1100,18 @@ void Move::AdjustLeadscrews(const floatc_t corrections[])
specialMoveAvailable = true;
}
+// Return the idle timeout in seconds
+float Move::IdleTimeout() const
+{
+ return (float)idleTimeout * 0.001;
+}
+
+// Set the idle timeout in seconds
+void Move::SetIdleTimeout(float timeout)
+{
+ idleTimeout = (uint32_t)lrintf(timeout * 1000.0);
+}
+
#ifdef DUET_NG
// Write settings for resuming the print
diff --git a/src/Movement/Move.h b/src/Movement/Move.h
index 7e65c8bd..68273194 100644
--- a/src/Movement/Move.h
+++ b/src/Movement/Move.h
@@ -56,7 +56,7 @@ public:
void SetXYBedProbePoint(size_t index, float x, float y); // Record the X and Y coordinates of a probe point
void SetZBedProbePoint(size_t index, float z, bool wasXyCorrected, bool wasError); // Record the Z coordinate of a probe point
float GetProbeCoordinates(int count, float& x, float& y, bool wantNozzlePosition) const; // Get pre-recorded probe coordinates
- void FinishedBedProbing(int sParam, StringRef& reply); // Calibrate or set the bed equation after probing
+ bool FinishedBedProbing(int sParam, StringRef& reply); // Calibrate or set the bed equation after probing
void SetAxisCompensation(unsigned int axis, float tangent); // Set an axis-pair compensation angle
float AxisCompensation(unsigned int axis) const; // The tangent value
void SetIdentityTransform(); // Cancel the bed equation; does not reset axis angle compensation
@@ -92,8 +92,8 @@ public:
void CurrentMoveCompleted(); // Signal that the current move has just been completed
bool TryStartNextMove(uint32_t startTime); // Try to start another move, returning true if Step() needs to be called immediately
- float IdleTimeout() const { return idleTimeout; } // Returns the idle timeout in seconds
- void SetIdleTimeout(float timeout) { idleTimeout = timeout; } // Set the idle timeout in seconds
+ float IdleTimeout() const; // Returns the idle timeout in seconds
+ void SetIdleTimeout(float timeout); // Set the idle timeout in seconds
void Simulate(uint8_t simMode); // Enter or leave simulation mode
float GetSimulationTime() const { return simulationTime; } // Get the accumulated simulation time
@@ -171,9 +171,9 @@ private:
bool usingMesh; // true if we are using the height map, false if we are using the random probe point set
float taperHeight; // Height over which we taper
- float idleTimeout; // How long we wait with no activity before we reduce motor currents to idle
- float lastMoveTime; // The approximate time at which the last move was completed, or 0
- float longWait; // A long time for things that need to be done occasionally
+ uint32_t idleTimeout; // How long we wait with no activity before we reduce motor currents to idle, in milliseconds
+ uint32_t lastMoveTime; // The approximate time at which the last move was completed
+ uint32_t longWait; // A long time for things that need to be done occasionally
IdleState iState; // whether the idle timer is active
Kinematics *kinematics; // What kinematics we are using
diff --git a/src/OutputMemory.cpp b/src/OutputMemory.cpp
index 1dade00a..26d23f45 100644
--- a/src/OutputMemory.cpp
+++ b/src/OutputMemory.cpp
@@ -45,7 +45,7 @@ void OutputBuffer::IncreaseReferences(size_t refs)
size_t OutputBuffer::Length() const
{
size_t totalLength = 0;
- for(const OutputBuffer *current = this; current != nullptr; current = current->Next())
+ for (const OutputBuffer *current = this; current != nullptr; current = current->Next())
{
totalLength += current->DataLength();
}
@@ -301,11 +301,37 @@ size_t OutputBuffer::EncodeReply(OutputBuffer *src, bool allowControlChars)
return bytesWritten;
}
+// Write all the data to file, but don't release the buffers
+// Returns true if successful
+bool OutputBuffer::WriteToFile(FileData& f) const
+{
+ bool endedInNewline = false;
+ const OutputBuffer *current = this;
+ do
+ {
+ if (current->dataLength != 0)
+ {
+ if (!f.Write(current->data, current->dataLength))
+ {
+ return false;
+ }
+ endedInNewline = current->data[current->dataLength - 1] == '\n';
+ }
+ current = current->Next();
+ } while (current != nullptr);
+
+ if (!endedInNewline)
+ {
+ return f.Write('\n');
+ }
+ return true;
+}
+
// Initialise the output buffers manager
/*static*/ void OutputBuffer::Init()
{
freeOutputBuffers = nullptr;
- for(size_t i = 0; i < OUTPUT_BUFFER_COUNT; i++)
+ for (size_t i = 0; i < OUTPUT_BUFFER_COUNT; i++)
{
freeOutputBuffers = new OutputBuffer(freeOutputBuffers);
}
diff --git a/src/OutputMemory.h b/src/OutputMemory.h
index c90542ad..0dee215a 100644
--- a/src/OutputMemory.h
+++ b/src/OutputMemory.h
@@ -10,6 +10,7 @@
#include "RepRapFirmware.h"
#include "MessageType.h"
+#include "Storage/FileData.h"
const size_t OUTPUT_STACK_DEPTH = 4; // Number of OutputBuffer chains that can be pushed onto one stack instance
@@ -57,6 +58,9 @@ class OutputBuffer
uint32_t GetAge() const;
+ // Write the buffer to file returning true if successful
+ bool WriteToFile(FileData& f) const;
+
// Initialise the output buffers manager
static void Init();
diff --git a/src/Platform.cpp b/src/Platform.cpp
index 90126cd1..7e761302 100644
--- a/src/Platform.cpp
+++ b/src/Platform.cpp
@@ -251,7 +251,7 @@ bool ZProbeParameters::WriteParameters(FileStore *f, unsigned int probeType) con
// Platform class
Platform::Platform() :
- board(DEFAULT_BOARD_TYPE), active(false), errorCodeBits(0), lastFanCheckTime(0),
+ logger(nullptr), lastLogFlushTime(0), board(DEFAULT_BOARD_TYPE), active(false), errorCodeBits(0), lastFanCheckTime(0),
auxGCodeReply(nullptr), fileStructureInitialised(false), tickState(0), debugCode(0)
#ifdef DUET_NG
, lastWarningMillis(0), nextDriveToPoll(0),
@@ -266,7 +266,6 @@ Platform::Platform() :
usbOutput = new OutputStack();
// Files
-
massStorage = new MassStorage(this);
for (size_t i = 0; i < MAX_FILES; i++)
@@ -345,16 +344,6 @@ void Platform::Init()
ARRAY_INIT(macAddress, DefaultMacAddress);
#endif
- zProbeType = 0; // Default is to use no Z probe switch
- zProbeAxes = Z_PROBE_AXES;
- SetZProbeDefaults();
-
- // We need to initialise at least some of the time stuff before we call MassStorage::Init()
- addToTime = 0.0;
- lastTimeCall = 0;
- lastTime = Time();
- longWait = lastTime;
-
// File management
massStorage->Init();
@@ -408,15 +397,18 @@ void Platform::Init()
#endif
// Z PROBE
+ zProbeType = 0; // default is to use no Z probe
+ zProbeAxes = Z_PROBE_AXES;
zProbePin = Z_PROBE_PIN;
zProbeAdcChannel = PinToAdcChannel(zProbePin);
- InitZProbe(); // this also sets up zProbeModulationPin
+ SetZProbeDefaults();
+ InitZProbe(); // this also sets up zProbeModulationPin
// AXES
ARRAY_INIT(axisMaxima, AXIS_MAXIMA);
ARRAY_INIT(axisMinima, AXIS_MINIMA);
- idleCurrentFactor = DEFAULT_IDLE_CURRENT_FACTOR;
+ idleCurrentFactor = DefaultIdleCurrentFactor;
// SD card interfaces
for (size_t i = 0; i < NumSdCards; ++i)
@@ -434,6 +426,9 @@ void Platform::Init()
PIOB->PIO_OWDR = 0xFFFFFFFF;
PIOC->PIO_OWDR = 0xFFFFFFFF;
PIOD->PIO_OWDR = 0xFFFFFFFF;
+#ifdef PIOE
+ PIOE->PIO_OWDR = 0xFFFFFFFF;
+#endif
for (size_t drive = 0; drive < DRIVES; drive++)
{
@@ -469,6 +464,20 @@ void Platform::Init()
motorCurrents[drive] = 0.0;
motorCurrentFraction[drive] = 1.0;
driverState[drive] = DriverStatus::disabled;
+
+ // Enable pullup resistors on endstop inputs here if necessary.
+#if defined(DUET_NG)
+ // The Duets have hardware pullup resistors/LEDs except for the two on the CONN_LCD connector.
+ // They have RC filtering on the main endstop inputs, so best not to enable the pullup resistors on these.
+ if (drive >= 10)
+ {
+ setPullup(endStopPins[drive], true); // enable pullup on CONN_LCD endstop input
+ }
+#endif
+#if defined(__RADDS__) || defined(__ALLIGATOR__)
+ // I don't know whether RADDS and Alligator have hardware pullup resistors or not. I'll assume they might not.
+ setPullup(endStopPins[drive], true);
+#endif
}
slowDriverStepPulseClocks = 0; // no extended driver timing configured yet
@@ -624,8 +633,7 @@ void Platform::Init()
memset(logicalPinModes, PIN_MODE_NOT_CONFIGURED, sizeof(logicalPinModes)); // set all pins to "not configured"
// Kick everything off
- lastTime = Time();
- longWait = lastTime;
+ longWait = millis();
InitialiseInterrupts(); // also sets 'active' to true
}
@@ -702,12 +710,6 @@ void Platform::InitZProbe()
pinMode(endStopPins[E0_AXIS + 1], INPUT);
pinMode(zProbeModulationPin, OUTPUT_LOW); // we now set the modulation output high during probing only when using probe types 4 and higher
break;
-
- case 7:
- AnalogInEnableChannel(zProbeAdcChannel, false);
- pinMode(zProbePin, INPUT_PULLUP);
- pinMode(zProbeModulationPin, OUTPUT_LOW); // we now set the modulation output high during probing only when using probe types 4 and higher
- break; //TODO (DeltaProbe)
}
}
@@ -734,10 +736,6 @@ int Platform::GetZProbeReading() const
zProbeVal = (int) (((int32_t) zProbeOnFilter.GetSum() - (int32_t) zProbeOffFilter.GetSum()) / (int)(4 * Z_PROBE_AVERAGE_READINGS));
break;
- case 7: // Delta humming probe
- zProbeVal = (int) ((zProbeOnFilter.GetSum() + zProbeOffFilter.GetSum()) / (8 * Z_PROBE_AVERAGE_READINGS)); //TODO this is temporary
- break;
-
default:
return 0;
}
@@ -829,7 +827,6 @@ const ZProbeParameters& Platform::GetZProbeParameters(int32_t probeType) const
case 5:
return irZProbeParameters;
case 3:
- case 7:
return alternateZProbeParameters;
case 4:
case 6:
@@ -849,7 +846,6 @@ void Platform::SetZProbeParameters(int32_t probeType, const ZProbeParameters& pa
break;
case 3:
- case 7:
alternateZProbeParameters = params;
break;
@@ -902,10 +898,10 @@ bool Platform::HomingZWithProbe() const
// Check the prerequisites for updating the main firmware. Return True if satisfied, else print as message and return false.
bool Platform::CheckFirmwareUpdatePrerequisites()
{
- FileStore * const firmwareFile = GetFileStore(GetSysDir(), IAP_FIRMWARE_FILE, false);
+ FileStore * const firmwareFile = GetFileStore(GetSysDir(), IAP_FIRMWARE_FILE, OpenMode::read);
if (firmwareFile == nullptr)
{
- MessageF(GENERIC_MESSAGE, "Error: Firmware binary \"%s\" not found\n", IAP_FIRMWARE_FILE);
+ MessageF(ErrorMessage, "Firmware binary \"%s\" not found\n", IAP_FIRMWARE_FILE);
return false;
}
@@ -920,13 +916,13 @@ bool Platform::CheckFirmwareUpdatePrerequisites()
#endif
)
{
- MessageF(GENERIC_MESSAGE, "Error: Firmware binary \"%s\" is not valid for this electronics\n", IAP_FIRMWARE_FILE);
+ MessageF(ErrorMessage, "Firmware binary \"%s\" is not valid for this electronics\n", IAP_FIRMWARE_FILE);
return false;
}
if (!GetMassStorage()->FileExists(GetSysDir(), IAP_UPDATE_FILE))
{
- MessageF(GENERIC_MESSAGE, "Error: In-application programming binary \"%s\" not found\n", IAP_UPDATE_FILE);
+ MessageF(ErrorMessage, "In-application programming binary \"%s\" not found\n", IAP_UPDATE_FILE);
return false;
}
@@ -936,10 +932,10 @@ bool Platform::CheckFirmwareUpdatePrerequisites()
// Update the firmware. Prerequisites should be checked before calling this.
void Platform::UpdateFirmware()
{
- FileStore * const iapFile = GetFileStore(GetSysDir(), IAP_UPDATE_FILE, false);
+ FileStore * const iapFile = GetFileStore(GetSysDir(), IAP_UPDATE_FILE, OpenMode::read);
if (iapFile == nullptr)
{
- MessageF(FIRMWARE_UPDATE_MESSAGE, "IAP not found\n");
+ MessageF(FirmwareUpdateMessage, "IAP not found\n");
return;
}
@@ -982,13 +978,13 @@ void Platform::UpdateFirmware()
if (rc != FLASH_RC_OK)
{
- MessageF(FIRMWARE_UPDATE_MESSAGE, "Error: Flash write failed, code=%u, address=0x%08x\n", rc, flashAddr);
+ MessageF(FirmwareUpdateErrorMessage, "flash write failed, code=%u, address=0x%08x\n", rc, flashAddr);
return;
}
// Verify written data
if (memcmp(reinterpret_cast<void *>(flashAddr), data, bytesRead) != 0)
{
- MessageF(FIRMWARE_UPDATE_MESSAGE, "Error: Verify during flash write failed, address=0x%08x\n", flashAddr);
+ MessageF(FirmwareUpdateErrorMessage, "verify during flash write failed, address=0x%08x\n", flashAddr);
return;
}
}
@@ -1039,13 +1035,13 @@ void Platform::UpdateFirmware()
if (rc != FLASH_RC_OK)
{
- MessageF(FIRMWARE_UPDATE_MESSAGE, "Error: Flash %s failed, code=%u, address=0x%08x\n", op, rc, flashAddr);
+ MessageF(FirmwareUpdateErrorMessage, "flash %s failed, code=%u, address=0x%08x\n", op, rc, flashAddr);
return;
}
// Verify written data
if (memcmp(reinterpret_cast<void *>(flashAddr), data, bytesRead) != 0)
{
- MessageF(FIRMWARE_UPDATE_MESSAGE, "Error: Verify during flash write failed, address=0x%08x\n", flashAddr);
+ MessageF(FirmwareUpdateErrorMessage, "verify during flash write failed, address=0x%08x\n", flashAddr);
return;
}
}
@@ -1063,7 +1059,9 @@ void Platform::UpdateFirmware()
#endif
iapFile->Close();
- Message(FIRMWARE_UPDATE_MESSAGE, "Updating main firmware\n");
+
+ Message(LcdMessage, "Updating main firmware\n");
+ Message(UsbMessage, "Shutting down USB interface to update main firmware. Try reconnecting after 30 seconds.\n");
// Allow time for the firmware update message to be sent
const uint32_t now = millis();
@@ -1132,7 +1130,7 @@ void Platform::UpdateFirmware()
// Send the beep command to the aux channel. There is no flow control on this port, so it can't block for long.
void Platform::Beep(int freq, int ms)
{
- MessageF(AUX_MESSAGE, "{\"beep_freq\":%d,\"beep_length\":%d}\n", freq, ms);
+ MessageF(LcdMessage, "{\"beep_freq\":%d,\"beep_length\":%d}\n", freq, ms);
}
// Send a short message to the aux channel. There is no flow control on this port, so it can't block for long.
@@ -1144,27 +1142,14 @@ void Platform::SendAuxMessage(const char* msg)
buf->copy("{\"message\":");
buf->EncodeString(msg, strlen(msg), false, true);
buf->cat("}\n");
- Message(AUX_MESSAGE, buf);
- }
-}
-
-// Note: the use of floating point time will cause the resolution to degrade over time.
-// For example, 1ms time resolution will only be available for about half an hour from startup.
-// Personally, I (dc42) would rather just maintain and provide the time in milliseconds in a uint32_t.
-// This would wrap round after about 49 days, but that isn't difficult to handle.
-float Platform::Time()
-{
- unsigned long now = micros();
- if (now < lastTimeCall) // Has timer overflowed?
- {
- addToTime += ((float) ULONG_MAX) * TIME_FROM_REPRAP;
+ Message(LcdMessage, buf);
}
- lastTimeCall = now;
- return addToTime + TIME_FROM_REPRAP * (float) now;
}
void Platform::Exit()
{
+ StopLogging();
+
// Close all files
for (FileStore*& f : files)
{
@@ -1201,14 +1186,16 @@ void Platform::SetEmulating(Compatibility c)
{
if (c != me && c != reprapFirmware && c != marlin)
{
- Message(GENERIC_MESSAGE, "Attempt to emulate unsupported firmware.\n");
- return;
+ Message(ErrorMessage, "Attempt to emulate unsupported firmware.\n");
}
- if (c == reprapFirmware)
+ else
{
- c = me;
+ if (c == reprapFirmware)
+ {
+ c = me;
+ }
+ compatibility = c;
}
- compatibility = c;
}
void Platform::UpdateNetworkAddress(byte dst[4], const byte src[4])
@@ -1415,8 +1402,19 @@ void Platform::Spin()
TMC2660::SetDriversPowered(driversPowered);
#endif
- // Thermostatically-controlled fans (do this after getting TMC driver status)
const uint32_t now = millis();
+
+ // Update the time
+ if (realTime != 0)
+ {
+ if (now - timeLastUpdatedMillis >= 1000)
+ {
+ ++realTime; // this assumes that time_t is a seconds-since-epoch counter, which is not guaranteed by the C standard
+ timeLastUpdatedMillis += 1000;
+ }
+ }
+
+ // Thermostatically-controlled fans (do this after getting TMC driver status)
if (now - lastFanCheckTime >= FanCheckInterval)
{
lastFanCheckTime = now;
@@ -1452,7 +1450,7 @@ void Platform::Spin()
// Check for a VSSA fault
if (vssaSenseWorking && digitalRead(VssaSensePin))
{
- Message(GENERIC_MESSAGE, "Error: VSSA fault, check thermistor wiring\n");
+ Message(ErrorMessage, "VSSA fault, check thermistor wiring\n");
reported = true;
}
@@ -1464,16 +1462,6 @@ void Platform::Spin()
#endif
}
- // Update the time
- if (realTime != 0)
- {
- if (millis() - timeLastUpdatedMillis >= 1000)
- {
- ++realTime; // this assumes that time_t is a seconds-since-epoch counter, which is not guaranteed by the C standard
- timeLastUpdatedMillis += 1000;
- }
- }
-
#ifdef DUET_NG
// Check for auto-pause, shutdown or resume
if (autoSaveEnabled)
@@ -1530,6 +1518,16 @@ void Platform::Spin()
}
#endif
+ // Flush the log file it it is time. This may take some time, so do it last.
+ if (logger != nullptr)
+ {
+ if (now - lastLogFlushTime >= LogFlushInterval)
+ {
+ logger->Flush();
+ lastLogFlushTime = now;
+ }
+ }
+
ClassReport(longWait);
}
@@ -1550,21 +1548,22 @@ void Platform::ReportDrivers(uint16_t whichDrivers, const char* text, bool& repo
}
whichDrivers >>= 1;
}
- MessageF(GENERIC_MESSAGE, "%s\n", scratchString);
+ MessageF(GenericMessage, "%s\n", scratchString);
reported = true;
}
}
// Configure auto save on power fail
-void Platform::ConfigureAutoSave(GCodeBuffer& gb, StringRef& reply, bool& error)
+bool Platform::ConfigureAutoSave(GCodeBuffer& gb, StringRef& reply)
{
bool seen = false;
float autoSaveVoltages[3];
if (gb.TryGetFloatArray('S', 3, autoSaveVoltages, reply, seen))
{
- error = true;
+ return true;
}
- else if (seen)
+
+ if (seen)
{
autoSaveEnabled = (autoSaveVoltages[0] >= 5.0 && autoSaveVoltages[1] > autoSaveVoltages[0] && autoSaveVoltages[2] > autoSaveVoltages[1]);
if (autoSaveEnabled)
@@ -1583,6 +1582,7 @@ void Platform::ConfigureAutoSave(GCodeBuffer& gb, StringRef& reply, bool& error)
reply.printf(" Auto shutdown at %.1fV, save/pause at %.1fV, resume at %.1fV",
AdcReadingToPowerVoltage(autoShutdownReading), AdcReadingToPowerVoltage(autoPauseReading), AdcReadingToPowerVoltage(autoResumeReading));
}
+ return false;
}
// Save some resume information
@@ -1903,7 +1903,7 @@ void Platform::Diagnostics(MessageType mtype)
MessageF(mtype, "Never used ram: %u\n", neverUsed);
// Show the up time and reason for the last reset
- const uint32_t now = (uint32_t)Time(); // get up time in seconds
+ const uint32_t now = (uint32_t)(millis64()/1000u); // get up time in seconds
const char* resetReasons[8] = { "power up", "backup", "watchdog", "software",
#ifdef DUET_NG
// On the SAM4E a watchdog reset may be reported as a user reset because of the capacitor on the NRST pin
@@ -2122,7 +2122,7 @@ void Platform::DiagnosticTest(int d)
const uint32_t now2 = Platform::GetInterruptClocks();
const uint32_t num2a = isqrt64((uint64_t)num2 * num2);
const uint32_t tim2 = Platform::GetInterruptClocks() - now2;
- MessageF(GENERIC_MESSAGE, "Square roots: 64-bit %.1fus %s, 32-bit %.1fus %s\n",
+ MessageF(GenericMessage, "Square roots: 64-bit %.1fus %s, 32-bit %.1fus %s\n",
(float)(tim1 * 1000000)/DDA::stepClockRate, (num1a == num1) ? "ok" : "ERROR",
(float)(tim2 * 1000000)/DDA::stepClockRate, (num2a == num2) ? "ok" : "ERROR");
}
@@ -2130,7 +2130,7 @@ void Platform::DiagnosticTest(int d)
#ifdef DUET_NG
case (int)DiagnosticTestType::PrintExpanderStatus:
- MessageF(GENERIC_MESSAGE, "Expander status %04X\n", DuetExpansion::DiagnosticRead());
+ MessageF(GenericMessage, "Expander status %04X\n", DuetExpansion::DiagnosticRead());
break;
#endif
@@ -2157,15 +2157,16 @@ void Platform::GetStackUsage(uint32_t* currentStack, uint32_t* maxStack, uint32_
if (neverUsed != nullptr) { *neverUsed = stack_lwm - heapend; }
}
-void Platform::ClassReport(float &lastTime)
+void Platform::ClassReport(uint32_t &lastTime)
{
const Module spinningModule = reprap.GetSpinningModule();
if (reprap.Debug(spinningModule))
{
- if (Time() - lastTime >= LONG_TIME)
+ const uint32_t now = millis();
+ if (now - lastTime >= LongTime)
{
- lastTime = Time();
- MessageF(HOST_MESSAGE, "Class %s spinning.\n", moduleName[spinningModule]);
+ lastTime = now;
+ MessageF(UsbMessage, "Class %s spinning\n", moduleName[spinningModule]);
}
}
}
@@ -2398,6 +2399,16 @@ void Platform::DisableDrive(size_t drive)
}
}
+// Disable all drives
+void Platform::DisableAllDrives()
+{
+ for (size_t drive = 0; drive < DRIVES; drive++)
+ {
+ SetDriverCurrent(drive, 0.0, false);
+ DisableDriver(drive);
+ }
+}
+
// Set drives to idle hold if they are enabled. If a drive is disabled, leave it alone.
// Must not be called from an ISR, or with interrupts disabled.
void Platform::SetDriversIdle()
@@ -2781,7 +2792,7 @@ void Platform::SetMACAddress(uint8_t mac[])
//-----------------------------------------------------------------------------------------------------
-FileStore* Platform::GetFileStore(const char* directory, const char* fileName, bool write)
+FileStore* Platform::GetFileStore(const char* directory, const char* fileName, OpenMode mode)
{
if (!fileStructureInitialised)
{
@@ -2792,7 +2803,7 @@ FileStore* Platform::GetFileStore(const char* directory, const char* fileName, b
{
if (!files[i]->inUse)
{
- if (files[i]->Open(directory, fileName, write))
+ if (files[i]->Open(directory, fileName, mode))
{
files[i]->inUse = true;
return files[i];
@@ -2803,7 +2814,7 @@ FileStore* Platform::GetFileStore(const char* directory, const char* fileName, b
}
}
}
- Message(HOST_MESSAGE, "Max open file count exceeded.\n");
+ Message(UsbMessage, "Max open file count exceeded.\n");
return nullptr;
}
@@ -2862,15 +2873,37 @@ void Platform::AppendAuxReply(OutputBuffer *reply)
}
}
-void Platform::Message(MessageType type, const char *message)
+// Send the specified message to the specified destinations. The Error and Warning flags have already been handled.
+void Platform::RawMessage(MessageType type, const char *message)
{
- switch (type)
+ // Deal with logging
+ if ((type & LogMessage) != 0 && logger != nullptr)
+ {
+ logger->LogMessage(realTime, message);
+ }
+
+ // Send the nessage to the destinations
+ if ((type & ImmediateLcdMessage) != 0)
+ {
+ SendAuxMessage(message);
+ }
+ else if ((type & LcdMessage) != 0)
{
- case AUX_MESSAGE:
AppendAuxReply(message);
- break;
+ }
- case AUX2_MESSAGE:
+ if ((type & HttpMessage) != 0)
+ {
+ reprap.GetNetwork().HandleHttpGCodeReply(message);
+ }
+
+ if ((type & TelnetMessage) != 0)
+ {
+ reprap.GetNetwork().HandleTelnetGCodeReply(message);
+ }
+
+ if ((type & AuxMessage) != 0)
+ {
#ifdef SERIAL_AUX2_DEVICE
// Message that is to be sent to the second auxiliary device (blocking)
if (!aux2Output->IsEmpty())
@@ -2885,15 +2918,16 @@ void Platform::Message(MessageType type, const char *message)
SERIAL_AUX2_DEVICE.flush();
}
#endif
- break;
+ }
- case DEBUG_MESSAGE:
+ if ((type & BlockingUsbMessage) != 0)
+ {
// Debug messages in blocking mode - potentially DANGEROUS, use with care!
SERIAL_MAIN_DEVICE.write(message);
SERIAL_MAIN_DEVICE.flush();
- break;
-
- case HOST_MESSAGE:
+ }
+ else if ((type & UsbMessage) != 0)
+ {
// Message that is to be sent via the USB line (non-blocking)
#if SUPPORT_SCANNER
if (!reprap.GetScanner().IsRegistered() || reprap.GetScanner().DoingGCodes())
@@ -2914,101 +2948,94 @@ void Platform::Message(MessageType type, const char *message)
// Append the message string
usbOutputBuffer->cat(message);
}
- break;
-
- case HTTP_MESSAGE:
- reprap.GetNetwork().HandleHttpGCodeReply(message);
- break;
-
- case TELNET_MESSAGE:
- reprap.GetNetwork().HandleTelnetGCodeReply(message);
- break;
-
- case FIRMWARE_UPDATE_MESSAGE:
- Message(HOST_MESSAGE, message); // send message to USB
- SendAuxMessage(message); // send message to aux
- break;
-
- case GENERIC_MESSAGE:
- // Message that is to be sent to the web & host. Make this the default one, too.
- default:
- Message(HTTP_MESSAGE, message);
- Message(TELNET_MESSAGE, message);
- // no break
- case NETWORK_INFO_MESSAGE:
- Message(HOST_MESSAGE, message);
- Message(AUX_MESSAGE, message);
- break;
}
}
+// Note: this overload of Platform::Message does not process the special action flags in the MessageType.
+// Also it treats calls to send a blocking USB message the same as ordinary USB messages,
+// and calls to send an immediate LCD message the same as ordinary LCD messages
void Platform::Message(const MessageType type, OutputBuffer *buffer)
{
- switch (type)
+ // First deal with logging because it doesn't hand on to the buffer
+ if ((type & LogMessage) != 0 && logger != nullptr)
{
- case AUX_MESSAGE:
- AppendAuxReply(buffer);
- break;
+ logger->LogMessage(realTime, buffer);
+ }
+
+ // Now send the message to all the destinations
+ size_t numDestinations = 0;
+ if ((type & (LcdMessage | ImmediateLcdMessage)) != 0)
+ {
+ ++numDestinations;
+ }
+ if ((type & (UsbMessage | BlockingUsbMessage)) != 0)
+ {
+ ++numDestinations;
+ }
+ if ((type & HttpMessage) != 0)
+ {
+ ++numDestinations;
+ }
+ if ((type & TelnetMessage) != 0)
+ {
+ ++numDestinations;
+ }
- case AUX2_MESSAGE:
#ifdef SERIAL_AUX2_DEVICE
- // Send this message to the second UART device
- aux2Output->Push(buffer);
-#else
- OutputBuffer::ReleaseAll(buffer);
+ if ((type & AuxMessage) != 0)
+ {
+ ++numDestinations;
+ }
#endif
- break;
- case DEBUG_MESSAGE:
- // Probably rarely used, but supported.
- while (buffer != nullptr)
- {
- SERIAL_MAIN_DEVICE.write(buffer->Data(), buffer->DataLength());
- SERIAL_MAIN_DEVICE.flush();
+ if (numDestinations == 0)
+ {
+ OutputBuffer::ReleaseAll(buffer);
+ }
+ else
+ {
+ buffer->IncreaseReferences(numDestinations - 1);
- buffer = OutputBuffer::Release(buffer);
+ if ((type & (LcdMessage | ImmediateLcdMessage)) != 0)
+ {
+ AppendAuxReply(buffer);
}
- break;
- case HOST_MESSAGE:
- if ( !SERIAL_MAIN_DEVICE
-#if SUPPORT_SCANNER
- || (reprap.GetScanner().IsRegistered() && !reprap.GetScanner().DoingGCodes())
-#endif
- )
+ if ((type & HttpMessage) != 0)
{
- // If the serial USB line is not open, discard the message right away
- OutputBuffer::ReleaseAll(buffer);
+ reprap.GetNetwork().HandleHttpGCodeReply(buffer);
}
- else
+
+ if ((type & TelnetMessage) != 0)
{
- // Else append incoming data to the stack
- usbOutput->Push(buffer);
+ reprap.GetNetwork().HandleTelnetGCodeReply(buffer);
}
- break;
-
- case HTTP_MESSAGE:
- reprap.GetNetwork().HandleHttpGCodeReply(buffer);
- break;
- case TELNET_MESSAGE:
- reprap.GetNetwork().HandleTelnetGCodeReply(buffer);
- break;
-
- case GENERIC_MESSAGE:
- // Message that is to be sent to the web & host.
- buffer->IncreaseReferences(3); // This one is handled by three additional destinations
- Message(HTTP_MESSAGE, buffer);
- Message(TELNET_MESSAGE, buffer);
- Message(HOST_MESSAGE, buffer);
- Message(AUX_MESSAGE, buffer);
- break;
+#ifdef SERIAL_AUX2_DEVICE
+ if ((type & AuxMessage) != 0)
+ {
+ // Send this message to the second UART device
+ aux2Output->Push(buffer);
+ }
+#endif
- default:
- // Everything else is unsupported (and probably not used)
- OutputBuffer::ReleaseAll(buffer);
- MessageF(HOST_MESSAGE, "Error: Unsupported Message call for type %u!\n", type);
- break;
+ if ((type & (UsbMessage | BlockingUsbMessage)) != 0)
+ {
+ if ( !SERIAL_MAIN_DEVICE
+#if SUPPORT_SCANNER
+ || (reprap.GetScanner().IsRegistered() && !reprap.GetScanner().DoingGCodes())
+#endif
+ )
+ {
+ // If the serial USB line is not open, discard the message right away
+ OutputBuffer::ReleaseAll(buffer);
+ }
+ else
+ {
+ // Else append incoming data to the stack
+ usbOutput->Push(buffer);
+ }
+ }
}
}
@@ -3016,22 +3043,46 @@ void Platform::MessageF(MessageType type, const char *fmt, va_list vargs)
{
char formatBuffer[FORMAT_STRING_LENGTH];
StringRef formatString(formatBuffer, ARRAY_SIZE(formatBuffer));
- formatString.vprintf(fmt, vargs);
+ if ((type & ErrorMessageFlag) != 0)
+ {
+ formatString.copy("Error: ");
+ formatString.vcatf(fmt, vargs);
+ }
+ else if ((type & WarningMessageFlag) != 0)
+ {
+ formatString.copy("Warning: ");
+ formatString.vcatf(fmt, vargs);
+ }
+ else
+ {
+ formatString.vprintf(fmt, vargs);
+ }
- Message(type, formatBuffer);
+ RawMessage((MessageType)(type & ~(ErrorMessageFlag | WarningMessageFlag)), formatBuffer);
}
void Platform::MessageF(MessageType type, const char *fmt, ...)
{
- char formatBuffer[FORMAT_STRING_LENGTH];
- StringRef formatString(formatBuffer, ARRAY_SIZE(formatBuffer));
-
va_list vargs;
va_start(vargs, fmt);
- formatString.vprintf(fmt, vargs);
+ MessageF(type, fmt, vargs);
va_end(vargs);
+}
- Message(type, formatBuffer);
+void Platform::Message(MessageType type, const char *message)
+{
+ if ((type & (ErrorMessageFlag | WarningMessageFlag)) == 0)
+ {
+ RawMessage(type, message);
+ }
+ else
+ {
+ char formatBuffer[FORMAT_STRING_LENGTH];
+ StringRef formatString(formatBuffer, ARRAY_SIZE(formatBuffer));
+ formatString.copy(((type & ErrorMessageFlag) != 0) ? "Error: " : "Warning: ");
+ formatString.cat(message);
+ RawMessage((MessageType)(type & ~(ErrorMessageFlag | WarningMessageFlag)), formatBuffer);
+ }
}
// Send a message box, which may require an acknowledgement
@@ -3043,9 +3094,9 @@ void Platform::SendAlert(MessageType mt, const char *message, const char *title,
{
switch (mt)
{
- case HTTP_MESSAGE:
- case AUX_MESSAGE:
- case GENERIC_MESSAGE:
+ case HttpMessage:
+ case LcdMessage:
+ case GenericMessage:
// Make the RepRap class cache this message until it's picked up by the HTTP clients and/or PanelDue
reprap.SetAlert(message, title, sParam, tParam, controls);
break;
@@ -3068,6 +3119,57 @@ void Platform::SendAlert(MessageType mt, const char *message, const char *title,
}
}
+// Configure logging according to the M929 command received, returning true if error
+bool Platform::ConfigureLogging(GCodeBuffer& gb, StringRef& reply)
+{
+ if (gb.Seen('S'))
+ {
+ StopLogging();
+ if (gb.GetIValue() > 0)
+ {
+ // Start logging
+ if (logger == nullptr)
+ {
+ logger = new Logger();
+ }
+ else
+ {
+ StopLogging();
+ }
+
+ char buf[FILENAME_LENGTH + 1];
+ StringRef filename(buf, ARRAY_SIZE(buf));
+ if (gb.Seen('P'))
+ {
+ if (!gb.GetQuotedString(filename))
+ {
+ reply.copy("Missing filename in M929 command");
+ return true;
+ }
+ }
+ else
+ {
+ filename.copy(DEFAULT_LOG_FILE);
+ }
+ logger->Start(realTime, filename);
+ }
+ }
+ else
+ {
+ reply.printf("Event logging is %s", (logger != nullptr && logger->IsActive()) ? "enabled" : "disabled");
+ }
+ return false;
+}
+
+// This is called form EmergencyStop. It closes the log file and stops logging.
+void Platform::StopLogging()
+{
+ if (logger != nullptr)
+ {
+ logger->Stop(realTime);
+ }
+}
+
bool Platform::AtxPower() const
{
return ReadPin(ATX_POWER_PIN);
diff --git a/src/Platform.h b/src/Platform.h
index d1fa886d..6a027d95 100644
--- a/src/Platform.h
+++ b/src/Platform.h
@@ -48,6 +48,7 @@ Licence: GPL
#include "Storage/MassStorage.h" // must be after Pins.h because it needs NumSdCards defined
#include "MessageType.h"
#include "ZProbeProgrammer.h"
+#include "Logger.h"
#if defined(DUET_NG)
# include "DueXn.h"
@@ -318,7 +319,7 @@ public:
void SetEmulating(Compatibility c);
void Diagnostics(MessageType mtype);
void DiagnosticTest(int d);
- void ClassReport(float &lastTime); // Called on Spin() return to check everything's live.
+ void ClassReport(uint32_t &lastTime); // Called on Spin() return to check everything's live.
void LogError(ErrorCode e) { errorCodeBits |= (uint32_t)e; }
void SoftwareReset(uint16_t reason, const uint32_t *stk = nullptr);
@@ -330,7 +331,6 @@ public:
// Timing
- float Time(); // Returns elapsed seconds since some arbitrary time - DEPRECATED
static uint32_t GetInterruptClocks(); // Get the interrupt clock count
static bool ScheduleStepInterrupt(uint32_t tim); // Schedule an interrupt at the specified clock count, or return true if it has passed already
static void DisableStepInterrupt(); // Make sure we get no step interrupts
@@ -376,7 +376,7 @@ public:
friend class FileStore;
MassStorage* GetMassStorage() const;
- FileStore* GetFileStore(const char* directory, const char* fileName, bool write);
+ FileStore* GetFileStore(const char* directory, const char* fileName, OpenMode mode);
const char* GetWebDir() const; // Where the html etc files are
const char* GetGCodeDir() const; // Where the gcodes are
const char* GetSysDir() const; // Where the system files are
@@ -388,12 +388,13 @@ public:
// Message output (see MessageType for further details)
- void Message(const MessageType type, const char *message);
- void Message(const MessageType type, OutputBuffer *buffer);
- void MessageF(const MessageType type, const char *fmt, ...);
- void MessageF(const MessageType type, const char *fmt, va_list vargs);
+ void Message(MessageType type, const char *message);
+ void Message(MessageType type, OutputBuffer *buffer);
+ void MessageF(MessageType type, const char *fmt, ...);
+ void MessageF(MessageType type, const char *fmt, va_list vargs);
bool FlushMessages(); // Flush messages to USB and aux, returning true if there is more to send
void SendAlert(MessageType mt, const char *message, const char *title, int sParam, float tParam, AxesBitmap controls);
+ void StopLogging();
// Movement
@@ -407,6 +408,7 @@ public:
void DisableDriver(size_t driver);
void EnableDrive(size_t drive);
void DisableDrive(size_t drive);
+ void DisableAllDrives();
void SetDriversIdle();
void SetMotorCurrent(size_t drive, float current, bool isPercent);
float GetMotorCurrent(size_t drive, bool isPercent) const;
@@ -568,7 +570,7 @@ public:
void GetPowerVoltages(float& minV, float& currV, float& maxV) const;
float GetTmcDriversTemperature(unsigned int board) const;
void DriverCoolingFansOn(uint32_t driverChannelsMonitored);
- void ConfigureAutoSave(GCodeBuffer& gb, StringRef& reply, bool& error);
+ bool ConfigureAutoSave(GCodeBuffer& gb, StringRef& reply);
bool WriteFanSettings(FileStore *f) const; // Save some resume information
#endif
@@ -578,11 +580,16 @@ public:
// For filament sensor support
Pin GetEndstopPin(int endstop) const; // Get the firmware pin number for an endstop
+ // Logging support
+ bool ConfigureLogging(GCodeBuffer& gb, StringRef& reply);
+
//-------------------------------------------------------------------------------------------------------
private:
Platform(const Platform&); // private copy constructor to make sure we don't try to copy a Platform
+ void RawMessage(MessageType type, const char *message); // called by Message after handling error/warning flags
+
void ResetChannel(size_t chan); // re-initialise a serial channel
float AdcReadingToCpuTemperature(uint32_t reading) const;
@@ -640,11 +647,17 @@ private:
static_assert(SoftwareResetData::numberOfSlots * sizeof(SoftwareResetData) <= FLASH_DATA_LENGTH, "NVData too large");
#endif
+ // Logging
+ Logger *logger;
+ uint32_t lastLogFlushTime;
+
+ // Z probes
ZProbeParameters switchZProbeParameters; // Z probe values for the switch Z-probe
ZProbeParameters irZProbeParameters; // Z probe values for the IR sensor
ZProbeParameters alternateZProbeParameters; // Z probe values for the alternate sensor
int zProbeType; // the type of Z probe we are currently using
AxesBitmap zProbeAxes; // Z probe is used for these axes (bitmap)
+
byte ipAddress[4];
byte netMask[4];
byte gateWay[4];
@@ -656,10 +669,7 @@ private:
ExpansionBoardType expansionBoard;
#endif
- float lastTime;
- float longWait;
- float addToTime;
- unsigned long lastTimeCall;
+ uint32_t longWait;
bool active;
uint32_t errorCodeBits;
diff --git a/src/PrintMonitor.cpp b/src/PrintMonitor.cpp
index 4f5c6fae..da50109b 100644
--- a/src/PrintMonitor.cpp
+++ b/src/PrintMonitor.cpp
@@ -26,7 +26,7 @@ Licence: GPL
#include "RepRap.h"
PrintMonitor::PrintMonitor(Platform& p, GCodes& gc) : platform(p), gCodes(gc), isPrinting(false),
- printStartTime(0), pauseStartTime(0.0), totalPauseTime(0.0), heatingUp(false), currentLayer(0), warmUpDuration(0.0),
+ printStartTime(0), pauseStartTime(0), totalPauseTime(0), heatingUp(false), currentLayer(0), warmUpDuration(0.0),
firstLayerDuration(0.0), firstLayerFilament(0.0), firstLayerProgress(0.0), lastLayerChangeTime(0.0),
lastLayerFilament(0.0), lastLayerZ(0.0), numLayerSamples(0), layerEstimatedTimeLeft(0.0), parseState(notParsing),
fileBeingParsed(nullptr), fileOverlapLength(0), printingFileParsed(false), accumulatedParseTime(0),
@@ -37,8 +37,7 @@ PrintMonitor::PrintMonitor(Platform& p, GCodes& gc) : platform(p), gCodes(gc), i
void PrintMonitor::Init()
{
- longWait = platform.Time();
- lastUpdateTime = millis();
+ longWait = lastUpdateTime = millis();
}
void PrintMonitor::Spin()
@@ -57,9 +56,9 @@ void PrintMonitor::Spin()
// Don't do any updates if the print has been paused
if (!gCodes.IsRunning())
{
- if (pauseStartTime == 0.0)
+ if (pauseStartTime == 0)
{
- pauseStartTime = platform.Time();
+ pauseStartTime = millis64();
}
platform.ClassReport(longWait);
return;
@@ -74,10 +73,10 @@ void PrintMonitor::Spin()
&& now - lastUpdateTime > PRINTMONITOR_UPDATE_INTERVAL)
{
// Adjust the actual print time if the print was paused before
- if (pauseStartTime != 0.0)
+ if (pauseStartTime != 0)
{
- totalPauseTime += platform.Time() - pauseStartTime;
- pauseStartTime = 0.0;
+ totalPauseTime += millis64() - pauseStartTime;
+ pauseStartTime = 0;
}
// Have we just started a print? See if we're heating up
@@ -174,7 +173,7 @@ void PrintMonitor::StartingPrint(const char* filename)
void PrintMonitor::StartedPrint()
{
isPrinting = true;
- printStartTime = platform.Time();
+ printStartTime = millis64();
}
// This is called as soon as the heaters are at temperature and the actual print has started
@@ -268,7 +267,7 @@ void PrintMonitor::StoppedPrint()
{
isPrinting = heatingUp = printingFileParsed = false;
currentLayer = numLayerSamples = 0;
- pauseStartTime = totalPauseTime = 0.0;
+ pauseStartTime = totalPauseTime = 0;
firstLayerDuration = firstLayerFilament = firstLayerProgress = 0.0;
layerEstimatedTimeLeft = printStartTime = warmUpDuration = 0.0;
lastLayerChangeTime = lastLayerFilament = lastLayerZ = 0.0;
@@ -286,7 +285,7 @@ bool PrintMonitor::GetFileInfo(const char *directory, const char *fileName, GCod
return true;
}
- fileBeingParsed = platform.GetFileStore(directory, fileName, false);
+ fileBeingParsed = platform.GetFileStore(directory, fileName, OpenMode::read);
if (fileBeingParsed == nullptr)
{
// Something went wrong - we cannot open it
@@ -316,7 +315,7 @@ bool PrintMonitor::GetFileInfo(const char *directory, const char *fileName, GCod
if (reprap.Debug(modulePrintMonitor))
{
accumulatedReadTime = accumulatedParseTime = 0;
- platform.MessageF(HOST_MESSAGE, "-- Parsing file %s --\n", fileName);
+ platform.MessageF(UsbMessage, "-- Parsing file %s --\n", fileName);
}
// If the file is empty or not a G-Code file, we don't need to parse anything
@@ -363,7 +362,7 @@ bool PrintMonitor::GetFileInfo(const char *directory, const char *fileName, GCod
const int nbytes = fileBeingParsed->Read(&buf[fileOverlapLength], sizeToRead);
if (nbytes != (int)sizeToRead)
{
- platform.MessageF(HOST_MESSAGE, "Error: Failed to read header of G-Code file \"%s\"\n", fileName);
+ platform.MessageF(ErrorMessage, "Failed to read header of G-Code file \"%s\"\n", fileName);
parseState = notParsing;
fileBeingParsed->Close();
info = parsedFileInfo;
@@ -460,7 +459,7 @@ bool PrintMonitor::GetFileInfo(const char *directory, const char *fileName, GCod
// Yes - see if we need to output some debug info
if (reprap.Debug(modulePrintMonitor))
{
- platform.MessageF(HOST_MESSAGE, "Header complete, processed %lu bytes, read time %.3fs, parse time %.3fs\n",
+ platform.MessageF(UsbMessage, "Header complete, processed %lu bytes, read time %.3fs, parse time %.3fs\n",
fileBeingParsed->Position(), (float)accumulatedReadTime/1000.0, (float)accumulatedParseTime/1000.0);
}
@@ -501,7 +500,7 @@ bool PrintMonitor::GetFileInfo(const char *directory, const char *fileName, GCod
int nbytes = fileBeingParsed->Read(buf, sizeToRead);
if (nbytes != (int)sizeToRead)
{
- platform.MessageF(HOST_MESSAGE, "Error: Failed to read footer from G-Code file \"%s\"\n", fileName);
+ platform.MessageF(ErrorMessage, "Failed to read footer from G-Code file \"%s\"\n", fileName);
parseState = notParsing;
fileBeingParsed->Close();
info = parsedFileInfo;
@@ -552,7 +551,7 @@ bool PrintMonitor::GetFileInfo(const char *directory, const char *fileName, GCod
{
if (reprap.Debug(modulePrintMonitor))
{
- platform.MessageF(HOST_MESSAGE, "Footer complete, processed %lu bytes, read time %.3fs, parse time %.3fs, seek time %.3fs\n",
+ platform.MessageF(UsbMessage, "Footer complete, processed %lu bytes, read time %.3fs, parse time %.3fs, seek time %.3fs\n",
fileBeingParsed->Length() - fileBeingParsed->Position() + GCODE_READ_SIZE,
(float)accumulatedReadTime/1000.0, (float)accumulatedParseTime/1000.0, (float)accumulatedSeekTime/1000.0);
}
@@ -567,7 +566,7 @@ bool PrintMonitor::GetFileInfo(const char *directory, const char *fileName, GCod
size_t seekOffset = (size_t)min<FilePosition>(pos, GCODE_READ_SIZE);
if (!fileBeingParsed->Seek(pos - seekOffset))
{
- platform.Message(HOST_MESSAGE, "Error: Could not seek from end of file!\n");
+ platform.Message(ErrorMessage, "Could not seek from end of file!\n");
parseState = notParsing;
fileBeingParsed->Close();
info = parsedFileInfo;
@@ -1151,13 +1150,8 @@ float PrintMonitor::GetPrintDuration() const
return 0.0;
}
- float printDuration = platform.Time() - printStartTime - totalPauseTime;
- if (pauseStartTime != 0.0)
- {
- // Take into account how long the machine has been paused
- printDuration -= platform.Time() - pauseStartTime;
- }
- return printDuration;
+ const uint64_t printDuration = ((pauseStartTime != 0) ? pauseStartTime : millis64()) - printStartTime - totalPauseTime;
+ return (float)printDuration * 0.001;
}
// vim: ts=4:sw=4
diff --git a/src/PrintMonitor.h b/src/PrintMonitor.h
index f469be19..7cc6783e 100644
--- a/src/PrintMonitor.h
+++ b/src/PrintMonitor.h
@@ -104,7 +104,7 @@ class PrintMonitor
private:
Platform& platform;
GCodes& gCodes;
- float longWait;
+ uint32_t longWait;
uint32_t lastUpdateTime;
// Information/Events concerning the file being printed
@@ -113,8 +113,8 @@ class PrintMonitor
void LayerComplete();
bool isPrinting;
- float printStartTime;
- float pauseStartTime, totalPauseTime;
+ uint64_t printStartTime;
+ uint64_t pauseStartTime, totalPauseTime;
bool heatingUp;
unsigned int currentLayer;
diff --git a/src/RepRap.cpp b/src/RepRap.cpp
index 8a0d56ad..d77e0f2e 100644
--- a/src/RepRap.cpp
+++ b/src/RepRap.cpp
@@ -104,18 +104,18 @@ void RepRap::Init()
printMonitor->Init();
active = true; // must do this before we start the network, else the watchdog may time out
- platform->MessageF(HOST_MESSAGE, "%s Version %s dated %s\n", FIRMWARE_NAME, VERSION, DATE);
+ platform->MessageF(UsbMessage, "%s Version %s dated %s\n", FIRMWARE_NAME, VERSION, DATE);
// Run the configuration file
const char *configFile = platform->GetConfigFile();
- platform->Message(HOST_MESSAGE, "\nExecuting ");
+ platform->Message(UsbMessage, "\nExecuting ");
if (platform->GetMassStorage()->FileExists(platform->GetSysDir(), configFile))
{
- platform->MessageF(HOST_MESSAGE, "%s...", platform->GetConfigFile());
+ platform->MessageF(UsbMessage, "%s...", platform->GetConfigFile());
}
else
{
- platform->MessageF(HOST_MESSAGE, "%s (no configuration file found)...", platform->GetDefaultFile());
+ platform->MessageF(UsbMessage, "%s (no configuration file found)...", platform->GetDefaultFile());
configFile = platform->GetDefaultFile();
}
@@ -126,11 +126,11 @@ void RepRap::Init()
// GCodes::Spin will read the macro and ensure IsDaemonBusy returns false when it's done
Spin();
}
- platform->Message(HOST_MESSAGE, "Done!\n");
+ platform->Message(UsbMessage, "Done!\n");
}
else
{
- platform->Message(HOST_MESSAGE, "Error, not found\n");
+ platform->Message(UsbMessage, "Error, not found\n");
}
processingConfig = false;
@@ -140,10 +140,10 @@ void RepRap::Init()
#if !defined(__RADDS__) && !defined(__ALLIGATOR__)
hsmci_set_idle_func(hsmciIdle);
#endif
- platform->MessageF(HOST_MESSAGE, "%s is up and running.\n", FIRMWARE_NAME);
- fastLoop = FLT_MAX;
- slowLoop = 0.0;
- lastTime = platform->Time();
+ platform->MessageF(UsbMessage, "%s is up and running.\n", FIRMWARE_NAME);
+ fastLoop = UINT32_MAX;
+ slowLoop = 0;
+ lastTime = micros();
}
void RepRap::Exit()
@@ -236,15 +236,15 @@ void RepRap::Spin()
{
if (t->DisplayColdExtrudeWarning())
{
- platform->MessageF(GENERIC_MESSAGE, "Warning: Tool %d was not driven because its heater temperatures were not high enough or it has a heater fault\n", t->myNumber);
+ platform->MessageF(WarningMessage, "Tool %d was not driven because its heater temperatures were not high enough or it has a heater fault\n", t->myNumber);
lastWarningMillis = now;
}
}
}
// Keep track of the loop time
- const float t = platform->Time();
- const float dt = t - lastTime;
+ const uint32_t t = micros();
+ const uint32_t dt = t - lastTime;
if (dt < fastLoop)
{
fastLoop = dt;
@@ -258,9 +258,9 @@ void RepRap::Spin()
void RepRap::Timing(MessageType mtype)
{
- platform->MessageF(mtype, "Slowest main loop (seconds): %f; fastest: %f\n", slowLoop, fastLoop);
- fastLoop = FLT_MAX;
- slowLoop = 0.0;
+ platform->MessageF(mtype, "Slowest main loop (seconds): %f; fastest: %f\n", (float)slowLoop * 0.000001, (float)fastLoop * 0.000001);
+ fastLoop = UINT32_MAX;
+ slowLoop = 0;
}
void RepRap::Diagnostics(MessageType mtype)
@@ -291,7 +291,7 @@ void RepRap::EmergencyStop()
}
heat->Exit();
- for(size_t heater = 0; heater < Heaters; heater++)
+ for (size_t heater = 0; heater < Heaters; heater++)
{
platform->SetHeater(heater, 0.0);
}
@@ -300,12 +300,10 @@ void RepRap::EmergencyStop()
for (int i = 0; i < 2; i++)
{
move->Exit();
- for (size_t drive = 0; drive < DRIVES; drive++)
- {
- platform->SetMotorCurrent(drive, 0.0, false);
- platform->DisableDrive(drive);
- }
+ platform->DisableAllDrives();
}
+
+ platform->StopLogging();
}
void RepRap::SetDebug(Module m, bool enable)
@@ -330,27 +328,27 @@ void RepRap::PrintDebug()
{
if (debug != 0)
{
- platform->Message(GENERIC_MESSAGE, "Debugging enabled for modules:");
+ platform->Message(GenericMessage, "Debugging enabled for modules:");
for (size_t i = 0; i < numModules; i++)
{
if ((debug & (1 << i)) != 0)
{
- platform->MessageF(GENERIC_MESSAGE, " %s(%u)", moduleName[i], i);
+ platform->MessageF(GenericMessage, " %s(%u)", moduleName[i], i);
}
}
- platform->Message(GENERIC_MESSAGE, "\nDebugging disabled for modules:");
+ platform->Message(GenericMessage, "\nDebugging disabled for modules:");
for (size_t i = 0; i < numModules; i++)
{
if ((debug & (1 << i)) == 0)
{
- platform->MessageF(GENERIC_MESSAGE, " %s(%u)", moduleName[i], i);
+ platform->MessageF(GenericMessage, " %s(%u)", moduleName[i], i);
}
}
- platform->Message(GENERIC_MESSAGE, "\n");
+ platform->Message(GenericMessage, "\n");
}
else
{
- platform->Message(GENERIC_MESSAGE, "Debugging disabled\n");
+ platform->Message(GenericMessage, "Debugging disabled\n");
}
}
@@ -464,7 +462,7 @@ void RepRap::StandbyTool(int toolNumber)
}
else
{
- platform->MessageF(GENERIC_MESSAGE, "Error: Attempt to standby a non-existent tool: %d.\n", toolNumber);
+ platform->MessageF(ErrorMessage, "Attempt to standby a non-existent tool: %d.\n", toolNumber);
}
}
@@ -499,7 +497,7 @@ void RepRap::SetToolVariables(int toolNumber, const float* standbyTemperatures,
}
else
{
- platform->MessageF(GENERIC_MESSAGE, "Error: Attempt to set variables for a non-existent tool: %d.\n", toolNumber);
+ platform->MessageF(ErrorMessage, "Attempt to set variables for a non-existent tool: %d.\n", toolNumber);
}
}
@@ -872,7 +870,7 @@ OutputBuffer *RepRap::GetStatusResponse(uint8_t type, ResponseSource source)
bool first = true;
for (size_t heater = FirstVirtualHeater; heater < FirstVirtualHeater + MaxVirtualHeaters; ++heater)
{
- const char *nm = heat->GetHeaterName(heater);
+ const char * const nm = heat->GetHeaterName(heater);
if (nm != nullptr)
{
if (!first)
@@ -892,7 +890,7 @@ OutputBuffer *RepRap::GetStatusResponse(uint8_t type, ResponseSource source)
}
// Time since last reset
- response->catf(",\"time\":%.1f", platform->Time());
+ response->catf(",\"time\":%.1f", (float)millis64() * 0.001);
#if SUPPORT_SCANNER
// Scanner
@@ -914,16 +912,16 @@ OutputBuffer *RepRap::GetStatusResponse(uint8_t type, ResponseSource source)
response->catf(",\"tempLimit\":%1.f", heat->GetHighestTemperatureLimit());
// Endstops
- uint16_t endstops = 0;
+ uint32_t endstops = 0;
for(size_t drive = 0; drive < DRIVES; drive++)
{
EndStopHit stopped = platform->Stopped(drive);
if (stopped == EndStopHit::highHit || stopped == EndStopHit::lowHit)
{
- endstops |= (1 << drive);
+ endstops |= (1u << drive);
}
}
- response->catf(",\"endstops\":%d", endstops);
+ response->catf(",\"endstops\":%u", endstops);
// Firmware name, machine geometry and number of axes
response->catf(",\"firmwareName\":\"%s\",\"geometry\":\"%s\",\"axes\":%u", FIRMWARE_NAME, move->GetGeometryString(), numAxes);
@@ -1195,7 +1193,7 @@ OutputBuffer *RepRap::GetConfigResponse()
// Motor idle parameters
response->catf(",\"idleCurrentFactor\":%.1f", platform->GetIdleCurrentFactor() * 100.0);
- response->catf(",\"idleTimeout\":%.1f", move->IdleTimeout());
+ response->catf(",\"idleTimeout\":%u", move->IdleTimeout());
// Minimum feedrates
response->cat(",\"minFeedrates\":");
diff --git a/src/RepRap.h b/src/RepRap.h
index d89f7c2d..5293ebaa 100644
--- a/src/RepRap.h
+++ b/src/RepRap.h
@@ -138,8 +138,8 @@ private:
uint16_t ticksInSpinState;
Module spinningModule;
- float fastLoop, slowLoop;
- float lastTime;
+ uint32_t fastLoop, slowLoop;
+ uint32_t lastTime;
uint16_t debug;
bool stopped;
diff --git a/src/RepRapFirmware.cpp b/src/RepRapFirmware.cpp
index c484e0f1..904cb598 100644
--- a/src/RepRapFirmware.cpp
+++ b/src/RepRapFirmware.cpp
@@ -201,7 +201,7 @@ void debugPrintf(const char* fmt, ...)
{
va_list vargs;
va_start(vargs, fmt);
- reprap.GetPlatform().MessageF(DEBUG_MESSAGE, fmt, vargs);
+ reprap.GetPlatform().MessageF(DebugMessage, fmt, vargs);
va_end(vargs);
}
diff --git a/src/Scanner.cpp b/src/Scanner.cpp
index 0a76d894..dc2d1821 100644
--- a/src/Scanner.cpp
+++ b/src/Scanner.cpp
@@ -23,7 +23,7 @@ const char* CALIBRATE_POST_G = "calibrate_post.g";
void Scanner::Init()
{
- longWait = platform.Time();
+ longWait = millis();
enabled = false;
SetState(ScannerState::Disconnected);
@@ -78,7 +78,7 @@ void Scanner::Spin()
if (state == ScannerState::ScanningPre || state == ScannerState::Scanning || state == ScannerState::ScanningPost ||
state == ScannerState::Uploading)
{
- platform.Message(GENERIC_MESSAGE, "Warning: Scanner disconnected while a 3D scan or upload was in progress");
+ platform.Message(WarningMessage, "Scanner disconnected while a 3D scan or upload was in progress");
}
// Delete any pending uploads
@@ -179,7 +179,7 @@ void Scanner::Spin()
{
if (reprap.Debug(moduleScanner))
{
- platform.MessageF(HTTP_MESSAGE, "Finished uploading %u bytes of scan data\n", uploadSize);
+ platform.MessageF(HttpMessage, "Finished uploading %u bytes of scan data\n", uploadSize);
}
fileBeingUploaded->Close();
@@ -195,7 +195,7 @@ void Scanner::Spin()
fileBeingUploaded = nullptr;
platform.GetMassStorage()->Delete(SCANS_DIRECTORY, uploadFilename);
- platform.Message(GENERIC_MESSAGE, "Error: Could not write scan file\n");
+ platform.Message(ErrorMessage, "Failed to write scan file\n");
SetState(ScannerState::Idle);
break;
}
@@ -219,7 +219,7 @@ void Scanner::Spin()
buffer[bufferPointer++] = b;
if (bufferPointer >= ScanBufferSize)
{
- platform.Message(GENERIC_MESSAGE, "Error: Scan buffer overflow\n");
+ platform.Message(ErrorMessage, "Scan buffer overflow\n");
bufferPointer = 0;
}
}
@@ -236,7 +236,7 @@ void Scanner::ProcessCommand()
// Output some info if debugging is enabled
if (reprap.Debug(moduleScanner))
{
- platform.MessageF(HTTP_MESSAGE, "Scanner request: '%s'\n", buffer);
+ platform.MessageF(HttpMessage, "Scanner request: '%s'\n", buffer);
}
// Register request: M751
@@ -285,19 +285,19 @@ void Scanner::ProcessCommand()
if (uploadFilename != nullptr)
{
uploadBytesLeft = uploadSize;
- fileBeingUploaded = platform.GetFileStore(SCANS_DIRECTORY, uploadFilename, true);
+ fileBeingUploaded = platform.GetFileStore(SCANS_DIRECTORY, uploadFilename, OpenMode::write);
if (fileBeingUploaded != nullptr)
{
SetState(ScannerState::Uploading);
if (reprap.Debug(moduleScanner))
{
- platform.MessageF(HTTP_MESSAGE, "Starting scan upload for file %s (%u bytes total)\n", uploadFilename, uploadSize);
+ platform.MessageF(HttpMessage, "Starting scan upload for file %s (%u bytes total)\n", uploadFilename, uploadSize);
}
}
}
else
{
- platform.Message(GENERIC_MESSAGE, "Error: Malformed scanner upload request\n");
+ platform.Message(ErrorMessage, "Malformed scanner upload request\n");
}
}
@@ -329,7 +329,7 @@ void Scanner::ProcessCommand()
// if this command contains a message, report it
if (bufferPointer > 6)
{
- platform.MessageF(GENERIC_MESSAGE, "Error: %s\n", &buffer[6]);
+ platform.MessageF(ErrorMessage, "%s\n", &buffer[6]);
}
// reset the state
diff --git a/src/Scanner.h b/src/Scanner.h
index 49606dc8..0e67a0da 100644
--- a/src/Scanner.h
+++ b/src/Scanner.h
@@ -74,7 +74,7 @@ private:
void DoFileMacro(const char *filename);
Platform& platform;
- float longWait;
+ uint32_t longWait;
bool enabled;
diff --git a/src/Storage/FileData.h b/src/Storage/FileData.h
index 2dea0214..683b4165 100644
--- a/src/Storage/FileData.h
+++ b/src/Storage/FileData.h
@@ -56,6 +56,11 @@ public:
return f->Write(b);
}
+ bool Write(const char *s)
+ {
+ return f->Write(s, strlen(s));
+ }
+
bool Write(const char *s, size_t len)
{
return f->Write(s, len);
diff --git a/src/Storage/FileStore.cpp b/src/Storage/FileStore.cpp
index c5642732..084fb873 100644
--- a/src/Storage/FileStore.cpp
+++ b/src/Storage/FileStore.cpp
@@ -38,12 +38,12 @@ bool FileStore::IsOpenOn(const FATFS *fs) const
// Open a local file (for example on an SD card).
// This is protected - only Platform can access it.
-bool FileStore::Open(const char* directory, const char* fileName, bool write)
+bool FileStore::Open(const char* directory, const char* fileName, OpenMode mode)
{
const char* const location = (directory != nullptr)
? platform->GetMassStorage()->CombineName(directory, fileName)
: fileName;
- writing = write;
+ writing = (mode == OpenMode::write || mode == OpenMode::append);
if (writing)
{
@@ -53,7 +53,7 @@ bool FileStore::Open(const char* directory, const char* fileName, bool write)
filePath.copy(location);
bool isVolume = isdigit(filePath[0]);
- for(size_t i = 1; i < filePath.strlen(); i++)
+ for (size_t i = 1; i < filePath.strlen(); i++)
{
if (filePath[i] == '/')
{
@@ -66,7 +66,7 @@ bool FileStore::Open(const char* directory, const char* fileName, bool write)
filePath[i] = 0;
if (!platform->GetMassStorage()->DirectoryExists(filePath.Pointer()) && !platform->GetMassStorage()->MakeDirectory(filePath.Pointer()))
{
- platform->MessageF(GENERIC_MESSAGE, "Failed to create directory %s while trying to open file %s\n",
+ platform->MessageF(ErrorMessage, "Failed to create directory %s while trying to open file %s\n",
filePath.Pointer(), location);
return false;
}
@@ -78,14 +78,17 @@ bool FileStore::Open(const char* directory, const char* fileName, bool write)
writeBuffer = platform->GetMassStorage()->AllocateWriteBuffer();
}
- FRESULT openReturn = f_open(&file, location, (writing) ? FA_CREATE_ALWAYS | FA_WRITE : FA_OPEN_EXISTING | FA_READ);
+ const FRESULT openReturn = f_open(&file, location,
+ (mode == OpenMode::write) ? FA_CREATE_ALWAYS | FA_WRITE
+ : (mode == OpenMode::append) ? FA_WRITE | FA_OPEN_ALWAYS
+ : FA_OPEN_EXISTING | FA_READ);
if (openReturn != FR_OK)
{
// We no longer report an error if opening a file in read mode fails unless debugging is enabled, because sometimes that is quite normal.
// It is up to the caller to report an error if necessary.
if (reprap.Debug(modulePlatform))
{
- platform->MessageF(GENERIC_MESSAGE, "Can't open %s to %s, error code %d\n", location, (writing) ? "write" : "read", openReturn);
+ platform->MessageF(ErrorMessage, "Can't open %s to %s, error code %d\n", location, (writing) ? "write" : "read", openReturn);
}
return false;
}
@@ -99,7 +102,7 @@ void FileStore::Duplicate()
{
if (!inUse)
{
- platform->Message(GENERIC_MESSAGE, "Error: Attempt to dup a non-open file.\n");
+ platform->Message(ErrorMessage, "Attempt to dup a non-open file.\n");
return;
}
irqflags_t flags = cpu_irq_save();
@@ -132,7 +135,7 @@ bool FileStore::Close()
if (!inUse)
{
- platform->Message(GENERIC_MESSAGE, "Error: Attempt to close a non-open file.\n");
+ platform->Message(ErrorMessage, "Attempt to close a non-open file.\n");
return false;
}
@@ -169,7 +172,7 @@ bool FileStore::Seek(FilePosition pos)
{
if (!inUse)
{
- platform->Message(GENERIC_MESSAGE, "Error: Attempt to seek on a non-open file.\n");
+ platform->Message(ErrorMessage, "Attempt to seek on a non-open file.\n");
return false;
}
FRESULT fr = f_lseek(&file, pos);
@@ -192,7 +195,7 @@ FilePosition FileStore::Length() const
{
if (!inUse)
{
- platform->Message(GENERIC_MESSAGE, "Error: Attempt to size non-open file.\n");
+ platform->Message(ErrorMessage, "Attempt to size non-open file.\n");
return 0;
}
@@ -210,7 +213,7 @@ int FileStore::Read(char* extBuf, size_t nBytes)
{
if (!inUse)
{
- platform->Message(GENERIC_MESSAGE, "Error: Attempt to read from a non-open file.\n");
+ platform->Message(ErrorMessage, "Attempt to read from a non-open file.\n");
return -1;
}
@@ -218,7 +221,7 @@ int FileStore::Read(char* extBuf, size_t nBytes)
FRESULT readStatus = f_read(&file, extBuf, nBytes, &bytes_read);
if (readStatus != FR_OK)
{
- platform->Message(GENERIC_MESSAGE, "Error: Cannot read file.\n");
+ platform->Message(ErrorMessage, "Cannot read file.\n");
return -1;
}
return (int)bytes_read;
@@ -285,7 +288,7 @@ bool FileStore::Write(const char *s, size_t len)
{
if (!inUse)
{
- platform->Message(GENERIC_MESSAGE, "Error: Attempt to write block to a non-open file.\n");
+ platform->Message(ErrorMessage, "Attempt to write block to a non-open file.\n");
return false;
}
@@ -302,7 +305,8 @@ bool FileStore::Write(const char *s, size_t len)
size_t bytesStored = writeBuffer->Store(s + totalBytesWritten, len - totalBytesWritten);
if (writeBuffer->BytesLeft() == 0)
{
- size_t bytesToWrite = writeBuffer->BytesStored(), bytesWritten;
+ const size_t bytesToWrite = writeBuffer->BytesStored();
+ size_t bytesWritten;
writeStatus = Store(writeBuffer->Data(), bytesToWrite, &bytesWritten);
writeBuffer->DataTaken();
@@ -319,7 +323,7 @@ bool FileStore::Write(const char *s, size_t len)
if ((writeStatus != FR_OK) || (totalBytesWritten != len))
{
- platform->Message(GENERIC_MESSAGE, "Error: Cannot write to file. Drive may be full.\n");
+ platform->Message(ErrorMessage, "Failed to write to file. Drive may be full.\n");
return false;
}
return true;
@@ -329,20 +333,24 @@ bool FileStore::Flush()
{
if (!inUse)
{
- platform->Message(GENERIC_MESSAGE, "Error: Attempt to flush a non-open file.\n");
+ platform->Message(ErrorMessage, "Attempt to flush a non-open file.\n");
return false;
}
if (writeBuffer != nullptr)
{
- size_t bytesToWrite = writeBuffer->BytesStored(), bytesWritten;
- FRESULT writeStatus = Store(writeBuffer->Data(), bytesToWrite, &bytesWritten);
- writeBuffer->DataTaken();
-
- if ((writeStatus != FR_OK) || (bytesToWrite != bytesWritten))
+ const size_t bytesToWrite = writeBuffer->BytesStored();
+ if (bytesToWrite != 0)
{
- platform->Message(GENERIC_MESSAGE, "Error: Cannot write to file. Drive may be full.\n");
- return false;
+ size_t bytesWritten;
+ const FRESULT writeStatus = Store(writeBuffer->Data(), bytesToWrite, &bytesWritten);
+ writeBuffer->DataTaken();
+
+ if ((writeStatus != FR_OK) || (bytesToWrite != bytesWritten))
+ {
+ platform->Message(ErrorMessage, "Failed to write to file. Drive may be full.\n");
+ return false;
+ }
}
}
@@ -364,7 +372,7 @@ bool FileStore::SetClusterMap(uint32_t tbl[])
{
if (!inUse)
{
- platform->Message(GENERIC_MESSAGE, "Error: Attempt to set cluster map for a non-open file.\n");
+ platform->Message(ErrorMessage, "attempt to set cluster map for a non-open file.\n");
return false;
}
diff --git a/src/Storage/FileStore.h b/src/Storage/FileStore.h
index dfc8cd16..0bf65af3 100644
--- a/src/Storage/FileStore.h
+++ b/src/Storage/FileStore.h
@@ -10,6 +10,13 @@
class Platform;
class FileWriteBuffer;
+enum class OpenMode : uint8_t
+{
+ read, // open an existing file for reading
+ write, // write a file, replacing any existing file of the same name
+ append // append to an existing file, or create a new file if it is not found
+};
+
class FileStore
{
public:
@@ -44,7 +51,7 @@ protected:
FileStore(Platform* p);
void Init();
- bool Open(const char* directory, const char* fileName, bool write);
+ bool Open(const char* directory, const char* fileName, OpenMode mode);
FRESULT Store(const char *s, size_t len, size_t *bytesWritten); // Write data to the non-volatile storage
private:
diff --git a/src/Storage/MassStorage.cpp b/src/Storage/MassStorage.cpp
index 17741acd..5a601d7b 100644
--- a/src/Storage/MassStorage.cpp
+++ b/src/Storage/MassStorage.cpp
@@ -75,7 +75,7 @@ void MassStorage::Init()
if (reply.strlen() != 0)
{
delay(3000); // Wait a few seconds so users have a chance to see this
- platform->Message(HOST_MESSAGE, reply.Pointer());
+ platform->Message(UsbMessage, reply.Pointer());
}
}
@@ -113,7 +113,7 @@ const char* MassStorage::CombineName(const char* directory, const char* fileName
outIndex++;
if (outIndex >= ARRAY_SIZE(combinedName))
{
- platform->MessageF(GENERIC_MESSAGE, "CombineName() buffer overflow.");
+ platform->MessageF(ErrorMessage, "CombineName() buffer overflow");
outIndex = 0;
}
}
@@ -133,7 +133,7 @@ const char* MassStorage::CombineName(const char* directory, const char* fileName
outIndex++;
if (outIndex >= ARRAY_SIZE(combinedName))
{
- platform->Message(GENERIC_MESSAGE, "CombineName() buffer overflow.");
+ platform->Message(ErrorMessage, "CombineName() buffer overflow");
outIndex = 0;
}
}
@@ -231,7 +231,7 @@ bool MassStorage::Delete(const char* directory, const char* fileName, bool silen
{
if (!silent)
{
- platform->MessageF(GENERIC_MESSAGE, "Can't delete file %s\n", location);
+ platform->MessageF(ErrorMessage, "Failed to delete file %s\n", location);
}
return false;
}
@@ -244,7 +244,7 @@ bool MassStorage::MakeDirectory(const char *parentDir, const char *dirName)
const char* location = platform->GetMassStorage()->CombineName(parentDir, dirName);
if (f_mkdir(location) != FR_OK)
{
- platform->MessageF(GENERIC_MESSAGE, "Can't create directory %s\n", location);
+ platform->MessageF(ErrorMessage, "Failed to create directory %s\n", location);
return false;
}
return true;
@@ -254,7 +254,7 @@ bool MassStorage::MakeDirectory(const char *directory)
{
if (f_mkdir(directory) != FR_OK)
{
- platform->MessageF(GENERIC_MESSAGE, "Can't create directory %s\n", directory);
+ platform->MessageF(ErrorMessage, "Failed to create directory %s\n", directory);
return false;
}
return true;
@@ -272,7 +272,7 @@ bool MassStorage::Rename(const char *oldFilename, const char *newFilename)
}
if (f_rename(oldFilename, newFilename) != FR_OK)
{
- platform->MessageF(GENERIC_MESSAGE, "Can't rename file or directory %s to %s\n", oldFilename, newFilename);
+ platform->MessageF(ErrorMessage, "Failed to rename file or directory %s to %s\n", oldFilename, newFilename);
return false;
}
return true;
@@ -334,7 +334,7 @@ bool MassStorage::SetLastModifiedTime(const char* directory, const char *fileNam
const bool ok = (f_utime(location, &fno) == FR_OK);
if (!ok)
{
- reprap.GetPlatform().MessageF(HTTP_MESSAGE, "SetLastModifiedTime didn't work for file '%s'\n", location);
+ reprap.GetPlatform().MessageF(ErrorMessage, "Failed to set last modified time for file '%s'\n", location);
}
return ok;
}
@@ -389,7 +389,7 @@ bool MassStorage::Mount(size_t card, StringRef& reply, bool reportSuccess)
FRESULT mounted = f_mount(card, &fileSystems[card]);
if (mounted != FR_OK)
{
- reply.printf("Can't mount SD card %u: code %d", card, mounted);
+ reply.printf("Cannot mount SD card %u: code %d", card, mounted);
}
else
{
diff --git a/src/Tools/Filament.cpp b/src/Tools/Filament.cpp
index c21b38eb..fb42414d 100644
--- a/src/Tools/Filament.cpp
+++ b/src/Tools/Filament.cpp
@@ -41,7 +41,7 @@ void Filament::Unload()
void Filament::LoadAssignment()
{
- FileStore *file = reprap.GetPlatform().GetFileStore(SYS_DIR, FilamentAssignmentFile, false);
+ FileStore *file = reprap.GetPlatform().GetFileStore(SYS_DIR, FilamentAssignmentFile, OpenMode::read);
if (file == nullptr)
{
// May happen, but not critical
@@ -78,7 +78,7 @@ void Filament::LoadAssignment()
/*static*/ void Filament::SaveAssignments()
{
- FileStore *file = reprap.GetPlatform().GetFileStore(SYS_DIR, FilamentAssignmentFile, true);
+ FileStore *file = reprap.GetPlatform().GetFileStore(SYS_DIR, FilamentAssignmentFile, OpenMode::write);
if (file == nullptr)
{
// Should never happen
diff --git a/src/Tools/Tool.cpp b/src/Tools/Tool.cpp
index b65bc706..4e5358c2 100644
--- a/src/Tools/Tool.cpp
+++ b/src/Tools/Tool.cpp
@@ -202,7 +202,7 @@ float Tool::MaxFeedrate() const
{
if (driveCount <= 0)
{
- reprap.GetPlatform().Message(GENERIC_MESSAGE, "Error: Attempt to get maximum feedrate for a tool with no drives.\n");
+ reprap.GetPlatform().Message(ErrorMessage, "Attempt to get maximum feedrate for a tool with no drives.\n");
return 1.0;
}
float result = 0.0;
@@ -222,7 +222,7 @@ float Tool::InstantDv() const
{
if (driveCount <= 0)
{
- reprap.GetPlatform().Message(GENERIC_MESSAGE, "Error: Attempt to get InstantDv for a tool with no drives.\n");
+ reprap.GetPlatform().Message(ErrorMessage, "Attempt to get InstantDv for a tool with no drives.\n");
return 1.0;
}
float result = FLT_MAX;
diff --git a/src/Version.h b/src/Version.h
index 86f7cd6f..7822eac6 100644
--- a/src/Version.h
+++ b/src/Version.h
@@ -9,11 +9,11 @@
#define SRC_VERSION_H_
#ifndef VERSION
-# define VERSION "1.19.2"
+# define VERSION "1.20alpha2"
#endif
#ifndef DATE
-# define DATE "2017-09-01"
+# define DATE "2017-09-21"
#endif
#define AUTHORS "reprappro, dc42, chrishamm, t3p3, dnewman"