Version 0.78i
Changed compiler optimization option to -O2 (was accidentally reset to -Os in previous release) Set the number of decimal places reported in the responses to various M commands Integrated zpl's changes to returning lists of files, returning info for file being printed, and some network layer changes
This commit is contained in:
parent
2a818bcfc0
commit
83d2732fd9
9 changed files with 482 additions and 379 deletions
|
@ -24,7 +24,7 @@ Licence: GPL
|
|||
#define CONFIGURATION_H
|
||||
|
||||
#define NAME "RepRapFirmware"
|
||||
#define VERSION "0.78h-dc42"
|
||||
#define VERSION "0.78i-dc42"
|
||||
#define DATE "2014-08-01"
|
||||
#define AUTHORS "reprappro, dc42. zpl"
|
||||
|
||||
|
|
79
GCodes.cpp
79
GCodes.cpp
|
@ -25,6 +25,8 @@
|
|||
|
||||
#include "RepRapFirmware.h"
|
||||
|
||||
const float secondsToMinutes = 1.0/60.0;
|
||||
|
||||
GCodes::GCodes(Platform* p, Webserver* w)
|
||||
{
|
||||
active = false;
|
||||
|
@ -992,10 +994,10 @@ const char* GCodes::GetCurrentCoordinates() const
|
|||
float liveCoordinates[DRIVES + 1];
|
||||
reprap.GetMove()->LiveCoordinates(liveCoordinates);
|
||||
|
||||
snprintf(scratchString, STRING_LENGTH, "X:%f Y:%f Z:%f ", liveCoordinates[X_AXIS], liveCoordinates[Y_AXIS], liveCoordinates[Z_AXIS]);
|
||||
snprintf(scratchString, STRING_LENGTH, "X:%.2f Y:%.2f Z:%.2f ", liveCoordinates[X_AXIS], liveCoordinates[Y_AXIS], liveCoordinates[Z_AXIS]);
|
||||
for(int i = AXES; i< DRIVES; i++)
|
||||
{
|
||||
sncatf(scratchString, STRING_LENGTH, "E%d:%f ", i-AXES, liveCoordinates[i]);
|
||||
sncatf(scratchString, STRING_LENGTH, "E%d:%.1f ", i-AXES, liveCoordinates[i]);
|
||||
}
|
||||
return scratchString;
|
||||
}
|
||||
|
@ -1836,18 +1838,45 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
|||
break;
|
||||
|
||||
case 20: // Deprecated...
|
||||
if (platform->Emulating() == me || platform->Emulating() == reprapFirmware)
|
||||
{
|
||||
snprintf(reply, STRING_LENGTH, "GCode files:\n%s",
|
||||
platform->GetMassStorage()->FileList(platform->GetGCodeDir(), gb == serialGCode));
|
||||
}
|
||||
else
|
||||
{
|
||||
snprintf(reply, STRING_LENGTH, "%s",
|
||||
platform->GetMassStorage()->FileList(platform->GetGCodeDir(), gb == serialGCode));
|
||||
bool encapsulate_list;
|
||||
if (platform->Emulating() == me || platform->Emulating() == reprapFirmware)
|
||||
{
|
||||
strcpy(reply, "GCode files:\n");
|
||||
encapsulate_list = false;
|
||||
}
|
||||
else
|
||||
{
|
||||
strcpy(reply, "");
|
||||
encapsulate_list = true;
|
||||
}
|
||||
|
||||
FileInfo file_info;
|
||||
if (platform->GetMassStorage()->FindFirst(platform->GetGCodeDir(), file_info))
|
||||
{
|
||||
// iterate through all entries and append each file name
|
||||
do {
|
||||
if (encapsulate_list)
|
||||
{
|
||||
sncatf(reply, STRING_LENGTH -1, "%c%s%c%c", FILE_LIST_BRACKET, file_info.fileName, FILE_LIST_BRACKET, FILE_LIST_SEPARATOR);
|
||||
}
|
||||
else
|
||||
{
|
||||
sncatf(reply, STRING_LENGTH -1, "%s\n", file_info.fileName);
|
||||
}
|
||||
} while (platform->GetMassStorage()->FindNext(file_info));
|
||||
|
||||
// remove the last character
|
||||
reply[strlen(reply) - 1] = 0;
|
||||
}
|
||||
else
|
||||
{
|
||||
strcat(reply, "NONE");
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
|
||||
case 21: // Initialise SD - ignore
|
||||
break;
|
||||
|
||||
|
@ -2308,12 +2337,12 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
|||
|
||||
if(!seen)
|
||||
{
|
||||
snprintf(reply, STRING_LENGTH, "Accelerations: X: %f, Y: %f, Z: %f, E: ",
|
||||
snprintf(reply, STRING_LENGTH, "Accelerations: X: %.1f, Y: %.1f, Z: %.1f, E: ",
|
||||
platform->Acceleration(X_AXIS)/distanceScale, platform->Acceleration(Y_AXIS)/distanceScale,
|
||||
platform->Acceleration(Z_AXIS)/distanceScale);
|
||||
for(int8_t drive = AXES; drive < DRIVES; drive++)
|
||||
{
|
||||
sncatf(reply, STRING_LENGTH, "%f", platform->Acceleration(drive)/distanceScale);
|
||||
sncatf(reply, STRING_LENGTH, "%.1f", platform->Acceleration(drive)/distanceScale);
|
||||
if(drive < DRIVES-1)
|
||||
{
|
||||
sncatf(reply, STRING_LENGTH, ":");
|
||||
|
@ -2330,7 +2359,7 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
|||
{
|
||||
if(gb->Seen(axisLetters[axis]))
|
||||
{
|
||||
platform->SetMaxFeedrate(axis, gb->GetFValue()*distanceScale*0.016666667); // G Code feedrates are in mm/minute; we need mm/sec
|
||||
platform->SetMaxFeedrate(axis, gb->GetFValue() * distanceScale * secondsToMinutes); // G Code feedrates are in mm/minute; we need mm/sec
|
||||
seen = true;
|
||||
}
|
||||
}
|
||||
|
@ -2350,19 +2379,19 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
|||
{
|
||||
for(int8_t e = 0; e < eCount; e++)
|
||||
{
|
||||
platform->SetMaxFeedrate(AXES + e, eVals[e]*distanceScale*0.016666667);
|
||||
platform->SetMaxFeedrate(AXES + e, eVals[e] * distanceScale * secondsToMinutes);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
if(!seen)
|
||||
{
|
||||
snprintf(reply, STRING_LENGTH, "Maximum feedrates: X: %f, Y: %f, Z: %f, E: ",
|
||||
platform->MaxFeedrate(X_AXIS)/(distanceScale*0.016666667), platform->MaxFeedrate(Y_AXIS)/(distanceScale*0.016666667),
|
||||
platform->MaxFeedrate(Z_AXIS)/(distanceScale*0.016666667));
|
||||
snprintf(reply, STRING_LENGTH, "Maximum feedrates: X: %.1f, Y: %.1f, Z: %.1f, E: ",
|
||||
platform->MaxFeedrate(X_AXIS)/(distanceScale * secondsToMinutes), platform->MaxFeedrate(Y_AXIS)/(distanceScale * secondsToMinutes),
|
||||
platform->MaxFeedrate(Z_AXIS)/(distanceScale * secondsToMinutes));
|
||||
for(int8_t drive = AXES; drive < DRIVES; drive++)
|
||||
{
|
||||
sncatf(reply, STRING_LENGTH, "%f", platform->MaxFeedrate(drive)/(distanceScale*0.016666667));
|
||||
sncatf(reply, STRING_LENGTH, "%.1f", platform->MaxFeedrate(drive)/(distanceScale * secondsToMinutes));
|
||||
if(drive < DRIVES-1)
|
||||
{
|
||||
sncatf(reply, STRING_LENGTH, ":");
|
||||
|
@ -2425,7 +2454,7 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
|||
{
|
||||
if (gb->Seen(axisLetters[axis]))
|
||||
{
|
||||
float value = gb->GetFValue() * distanceScale * 0.016666667;
|
||||
float value = gb->GetFValue() * distanceScale * secondsToMinutes;
|
||||
platform->SetHomeFeedRate(axis, value);
|
||||
seen = true;
|
||||
}
|
||||
|
@ -2780,7 +2809,7 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
|||
{
|
||||
if(gb->Seen(axisLetters[axis]))
|
||||
{
|
||||
platform->SetInstantDv(axis, gb->GetFValue()*distanceScale*0.016666667); // G Code feedrates are in mm/minute; we need mm/sec
|
||||
platform->SetInstantDv(axis, gb->GetFValue()*distanceScale * secondsToMinutes); // G Code feedrates are in mm/minute; we need mm/sec
|
||||
seen = true;
|
||||
}
|
||||
}
|
||||
|
@ -2799,18 +2828,18 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
|
|||
{
|
||||
for(int8_t e = 0; e < eCount; e++)
|
||||
{
|
||||
platform->SetInstantDv(AXES + e, eVals[e]*distanceScale*0.016666667);
|
||||
platform->SetInstantDv(AXES + e, eVals[e] * distanceScale * secondsToMinutes);
|
||||
}
|
||||
}
|
||||
}
|
||||
else if(!seen)
|
||||
{
|
||||
snprintf(reply, STRING_LENGTH, "Minimum feedrates: X: %f, Y: %f, Z: %f, E: ",
|
||||
platform->InstantDv(X_AXIS)/(distanceScale*0.016666667), platform->InstantDv(Y_AXIS)/(distanceScale*0.016666667),
|
||||
platform->InstantDv(Z_AXIS)/(distanceScale*0.016666667));
|
||||
snprintf(reply, STRING_LENGTH, "Minimum feedrates: X: %.1f, Y: %.1f, Z: %.1f, E: ",
|
||||
platform->InstantDv(X_AXIS)/(distanceScale * secondsToMinutes), platform->InstantDv(Y_AXIS)/(distanceScale * secondsToMinutes),
|
||||
platform->InstantDv(Z_AXIS)/(distanceScale * secondsToMinutes));
|
||||
for(int8_t drive = AXES; drive < DRIVES; drive++)
|
||||
{
|
||||
sncatf(reply, STRING_LENGTH, "%f", platform->InstantDv(drive)/(distanceScale*0.016666667));
|
||||
sncatf(reply, STRING_LENGTH, "%.1f", platform->InstantDv(drive)/(distanceScale * secondsToMinutes));
|
||||
if(drive < DRIVES-1)
|
||||
{
|
||||
sncatf(reply, STRING_LENGTH, ":");
|
||||
|
|
283
Network.cpp
283
Network.cpp
|
@ -50,7 +50,6 @@ extern "C"
|
|||
#include "lwip/src/include/lwip/tcp.h"
|
||||
|
||||
void RepRapNetworkSetMACAddress(const u8_t macAddress[]);
|
||||
|
||||
}
|
||||
|
||||
const unsigned int requestStateSize = MEMP_NUM_TCP_PCB * 2; // number of RequestStates that can be used for network IO
|
||||
|
@ -63,6 +62,7 @@ static tcp_pcb *telnet_pcb = NULL;
|
|||
|
||||
static bool closingDataPort = false;
|
||||
|
||||
static uint8_t volatile inLwip = 0;
|
||||
|
||||
// Called to put out a message via the RepRap firmware.
|
||||
// Can be called from C as well as C++
|
||||
|
@ -112,7 +112,7 @@ static void SendData(tcp_pcb *pcb, ConnectionState *cs)
|
|||
}
|
||||
else
|
||||
{
|
||||
debugPrintf("send_data: error %d\n", err);
|
||||
// debugPrintf("send_data: error %d\n", err);
|
||||
tcp_abort(cs->pcb);
|
||||
cs->pcb = NULL;
|
||||
}
|
||||
|
@ -365,7 +365,7 @@ SendBuffer::SendBuffer(SendBuffer *n) : next(n)
|
|||
// Network/Ethernet class
|
||||
|
||||
Network::Network()
|
||||
: state(NetworkInactive), inLwip(0),
|
||||
: state(NetworkInactive), readingData(false),
|
||||
freeTransactions(NULL), readyTransactions(NULL), writingTransactions(NULL),
|
||||
dataCs(NULL), ftpCs(NULL), telnetCs(NULL),
|
||||
sendBuffer(NULL)
|
||||
|
@ -385,22 +385,22 @@ Network::Network()
|
|||
|
||||
void Network::AppendTransaction(RequestState* volatile* list, RequestState *r)
|
||||
{
|
||||
irqflags_t flags = cpu_irq_save();
|
||||
++inLwip;
|
||||
r->next = NULL;
|
||||
while (*list != NULL)
|
||||
{
|
||||
list = &((*list)->next);
|
||||
}
|
||||
*list = r;
|
||||
cpu_irq_restore(flags);
|
||||
--inLwip;
|
||||
}
|
||||
|
||||
void Network::PrependTransaction(RequestState* volatile* list, RequestState *r)
|
||||
{
|
||||
irqflags_t flags = cpu_irq_save();
|
||||
++inLwip;
|
||||
r->next = *list;
|
||||
*list = r;
|
||||
cpu_irq_restore(flags);
|
||||
--inLwip;
|
||||
}
|
||||
|
||||
void Network::Init()
|
||||
|
@ -422,13 +422,11 @@ void Network::Spin()
|
|||
--inLwip;
|
||||
|
||||
// See if we can send anything
|
||||
++inLwip;
|
||||
RequestState* r = writingTransactions;
|
||||
if (r != NULL)
|
||||
{
|
||||
bool finished = r->Send();
|
||||
|
||||
// Disable interrupts while we mess around with the lists in case we get a callback from a network ISR
|
||||
irqflags_t flags = cpu_irq_save();
|
||||
writingTransactions = r->next;
|
||||
|
||||
if (finished)
|
||||
|
@ -454,8 +452,8 @@ void Network::Spin()
|
|||
{
|
||||
AppendTransaction(&writingTransactions, r);
|
||||
}
|
||||
cpu_irq_restore(flags);
|
||||
}
|
||||
--inLwip;
|
||||
}
|
||||
else if (state == NetworkInitializing)
|
||||
{
|
||||
|
@ -470,13 +468,23 @@ void Network::Spin()
|
|||
}
|
||||
}
|
||||
|
||||
bool Network::InLwip() const
|
||||
{
|
||||
return (inLwip);
|
||||
}
|
||||
|
||||
void Network::ReadPacket()
|
||||
{
|
||||
readingData = true;
|
||||
}
|
||||
|
||||
bool Network::AllocateSendBuffer(SendBuffer *&buffer)
|
||||
{
|
||||
// Grab another send buffer
|
||||
buffer = sendBuffer;
|
||||
if (buffer == NULL)
|
||||
{
|
||||
debugPrintf("Network: Could not allocate send buffer!\n");
|
||||
// debugPrintf("Network: Could not allocate send buffer!\n");
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -522,17 +530,14 @@ void Network::SentPacketAcknowledged(ConnectionState *cs, unsigned int len)
|
|||
// It must set the state of any RequestState that refers to it to connection accepted.
|
||||
void Network::ConnectionAccepted(ConnectionState *cs)
|
||||
{
|
||||
irqflags_t flags = cpu_irq_save();
|
||||
RequestState* r = freeTransactions;
|
||||
if (r == NULL)
|
||||
{
|
||||
cpu_irq_restore(flags);
|
||||
reprap.GetPlatform()->Message(HOST_MESSAGE, "Network::ConnectionAccepted() - no free transactions!\n");
|
||||
return;
|
||||
}
|
||||
|
||||
freeTransactions = r->next;
|
||||
cpu_irq_restore(flags);
|
||||
|
||||
r->Set(NULL, cs, connected);
|
||||
AppendTransaction(&readyTransactions, r);
|
||||
|
@ -585,34 +590,28 @@ void Network::ConnectionClosed(ConnectionState* cs)
|
|||
|
||||
void Network::ConnectionClosedGracefully(ConnectionState *cs)
|
||||
{
|
||||
irqflags_t flags = cpu_irq_save();
|
||||
RequestState* r = freeTransactions;
|
||||
if (r == NULL)
|
||||
{
|
||||
cpu_irq_restore(flags);
|
||||
reprap.GetPlatform()->Message(HOST_MESSAGE, "Network::ConnectionClosedGracefully() - no free transactions!\n");
|
||||
return;
|
||||
}
|
||||
freeTransactions = r->next;
|
||||
r->Set(NULL, cs, disconnected);
|
||||
cpu_irq_restore(flags);
|
||||
|
||||
AppendTransaction(&readyTransactions, r);
|
||||
}
|
||||
|
||||
void Network::ReceiveInput(pbuf *pb, ConnectionState* cs)
|
||||
{
|
||||
irqflags_t flags = cpu_irq_save();
|
||||
RequestState* r = freeTransactions;
|
||||
if (r == NULL)
|
||||
{
|
||||
cpu_irq_restore(flags);
|
||||
reprap.GetPlatform()->Message(HOST_MESSAGE, "Network::ReceiveInput() - no free transactions!\n");
|
||||
return;
|
||||
}
|
||||
|
||||
freeTransactions = r->next;
|
||||
cpu_irq_restore(flags);
|
||||
|
||||
r->Set(pb, cs, dataReceiving);
|
||||
AppendTransaction(&readyTransactions, r);
|
||||
|
@ -626,48 +625,52 @@ void Network::ReceiveInput(pbuf *pb, ConnectionState* cs)
|
|||
// will return the same one.
|
||||
RequestState *Network::GetRequest(const ConnectionState *cs)
|
||||
{
|
||||
++inLwip;
|
||||
RequestState *rs = readyTransactions;
|
||||
if (rs == NULL || cs == NULL || rs->cs == cs)
|
||||
{
|
||||
--inLwip;
|
||||
return rs;
|
||||
}
|
||||
|
||||
// There is at least one ready transaction, but it's not on the connection we are looking for
|
||||
for (;;)
|
||||
for (RequestState *rsNext = rs->next; rsNext != NULL; rsNext = rs->next)
|
||||
{
|
||||
RequestState *rsNext = rs->next;
|
||||
if (rsNext == NULL)
|
||||
{
|
||||
return rsNext;
|
||||
}
|
||||
if (rsNext->cs == cs)
|
||||
{
|
||||
irqflags_t flags = cpu_irq_save();
|
||||
rs->next = rsNext->next; // remove rsNext from the list
|
||||
rsNext->next = readyTransactions;
|
||||
readyTransactions = rsNext;
|
||||
cpu_irq_restore(flags);
|
||||
--inLwip;
|
||||
return rsNext;
|
||||
}
|
||||
rs = rsNext;
|
||||
}
|
||||
return NULL; // to keep Eclipse happy
|
||||
--inLwip;
|
||||
return NULL;
|
||||
}
|
||||
|
||||
// Send the output data we already have, optionally with a file appended, then close the connection unless keepConnectionOpen is true.
|
||||
// The file may be too large for our buffer, so we may have to send it in multiple transactions.
|
||||
void Network::SendAndClose(FileStore *f, bool keepConnectionOpen)
|
||||
{
|
||||
irqflags_t flags = cpu_irq_save();
|
||||
++inLwip;
|
||||
RequestState *r = readyTransactions;
|
||||
if (r == NULL)
|
||||
{
|
||||
cpu_irq_restore(flags);
|
||||
--inLwip;
|
||||
}
|
||||
else if (r->status == dataSending)
|
||||
{
|
||||
// This transaction is already in use for sending (e.g. a Telnet request),
|
||||
// so all we have to do is to remove it from readyTransactions.
|
||||
readyTransactions = r->next;
|
||||
--inLwip;
|
||||
}
|
||||
else
|
||||
{
|
||||
readyTransactions = r->next;
|
||||
cpu_irq_restore(flags);
|
||||
--inLwip;
|
||||
r->FreePbuf();
|
||||
if (r->LostConnection())
|
||||
{
|
||||
|
@ -679,6 +682,7 @@ void Network::SendAndClose(FileStore *f, bool keepConnectionOpen)
|
|||
if (buf != NULL)
|
||||
{
|
||||
FreeSendBuffer(buf);
|
||||
buf = NULL;
|
||||
}
|
||||
AppendTransaction(&freeTransactions, r);
|
||||
// debugPrintf("Conn lost before send\n");
|
||||
|
@ -688,6 +692,7 @@ void Network::SendAndClose(FileStore *f, bool keepConnectionOpen)
|
|||
r->persistConnection = keepConnectionOpen;
|
||||
r->nextWrite = NULL;
|
||||
r->fileBeingSent = f;
|
||||
r->status = dataSending;
|
||||
if (f != NULL && r->sendBuffer == NULL)
|
||||
{
|
||||
SendBuffer *buf;
|
||||
|
@ -696,12 +701,11 @@ void Network::SendAndClose(FileStore *f, bool keepConnectionOpen)
|
|||
r->sendBuffer = buf;
|
||||
r->outputBuffer = r->sendBuffer->tcpOutputBuffer;
|
||||
r->fileBeingSent = f;
|
||||
r->status = dataSending;
|
||||
}
|
||||
else
|
||||
{
|
||||
r->fileBeingSent = NULL;
|
||||
debugPrintf("Could not allocate send buffer for file transfer!\n");
|
||||
// debugPrintf("Could not allocate send buffer for file transfer!\n");
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -731,26 +735,13 @@ void Network::SendAndClose(FileStore *f, bool keepConnectionOpen)
|
|||
// That way we can speed up freeing the current RequestState.
|
||||
void Network::CloseRequest()
|
||||
{
|
||||
// Safety check
|
||||
irqflags_t flags = cpu_irq_save();
|
||||
// Free the current RequestState's data (if any)
|
||||
++inLwip;
|
||||
RequestState *r = readyTransactions;
|
||||
RequestStatus status = r->GetStatus();
|
||||
if (status == dataSending)
|
||||
{
|
||||
cpu_irq_restore(flags);
|
||||
RepRapNetworkMessage("Network: Cannot close sending request!\n");
|
||||
return;
|
||||
}
|
||||
|
||||
// Free the current transaction
|
||||
readyTransactions = r->next;
|
||||
cpu_irq_restore(flags);
|
||||
AppendTransaction(&freeTransactions, r);
|
||||
|
||||
// Free the current RequestState's data
|
||||
r->FreePbuf();
|
||||
|
||||
// Terminate this connection if this RequestState indicates a graceful disconnect
|
||||
RequestStatus status = r->status;
|
||||
if (!r->LostConnection() && status == disconnected)
|
||||
{
|
||||
ConnectionState *locCs = r->cs; // take a copy because our cs field is about to get cleared
|
||||
|
@ -764,34 +755,45 @@ void Network::CloseRequest()
|
|||
mem_free(locCs);
|
||||
tcp_close(pcb);
|
||||
}
|
||||
|
||||
// Remove the current item from readyTransactions
|
||||
readyTransactions = r->next;
|
||||
--inLwip;
|
||||
|
||||
// Append it to freeTransactions again unless it's already on another list
|
||||
if (status != dataSending)
|
||||
{
|
||||
AppendTransaction(&freeTransactions, r);
|
||||
}
|
||||
}
|
||||
|
||||
// The current RequestState must be processed again, e.g. because we're still waiting for another
|
||||
// data connection.
|
||||
void Network::RepeatRequest()
|
||||
{
|
||||
irqflags_t flags = cpu_irq_save();
|
||||
++inLwip;
|
||||
RequestState *r = readyTransactions;
|
||||
r->inputPointer = 0; // behave as if this request hasn't been processed yet
|
||||
if (r->next != NULL)
|
||||
{
|
||||
readyTransactions = r->next;
|
||||
cpu_irq_restore(flags);
|
||||
|
||||
--inLwip;
|
||||
AppendTransaction(&readyTransactions, r);
|
||||
}
|
||||
else
|
||||
{
|
||||
cpu_irq_restore(flags);
|
||||
--inLwip;
|
||||
}
|
||||
}
|
||||
|
||||
void Network::OpenDataPort(uint16_t port)
|
||||
{
|
||||
++inLwip;
|
||||
tcp_pcb* pcb = tcp_new();
|
||||
tcp_bind(pcb, IP_ADDR_ANY, port);
|
||||
ftp_pasv_pcb = tcp_listen(pcb);
|
||||
tcp_accept(ftp_pasv_pcb, conn_accept);
|
||||
--inLwip;
|
||||
}
|
||||
|
||||
// Close the data port and return true on success
|
||||
|
@ -820,6 +822,7 @@ bool Network::CloseDataPort()
|
|||
ConnectionState *loc_cs = dataCs;
|
||||
// debugPrintf("CloseDataPort is closing connection dataCS=%08x\n", (unsigned int)loc_cs);
|
||||
ConnectionClosed(loc_cs);
|
||||
++inLwip;
|
||||
tcp_pcb *pcb = loc_cs->pcb;
|
||||
tcp_arg(pcb, NULL);
|
||||
tcp_sent(pcb, NULL);
|
||||
|
@ -827,112 +830,118 @@ bool Network::CloseDataPort()
|
|||
tcp_poll(pcb, NULL, 4);
|
||||
mem_free(loc_cs);
|
||||
tcp_close(pcb);
|
||||
--inLwip;
|
||||
}
|
||||
}
|
||||
|
||||
// close listening data port
|
||||
if (ftp_pasv_pcb != NULL)
|
||||
{
|
||||
++inLwip;
|
||||
tcp_accept(ftp_pasv_pcb, NULL);
|
||||
tcp_close(ftp_pasv_pcb);
|
||||
ftp_pasv_pcb = NULL;
|
||||
--inLwip;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
// These methods keep track of our connections in case we need to send to one of them
|
||||
void Network::SaveDataConnection()
|
||||
{
|
||||
// store our data connection so we can identify it again later
|
||||
++inLwip;
|
||||
dataCs = readyTransactions->cs;
|
||||
--inLwip;
|
||||
}
|
||||
|
||||
void Network::SaveFTPConnection()
|
||||
{
|
||||
++inLwip;
|
||||
ftpCs = readyTransactions->cs;
|
||||
--inLwip;
|
||||
}
|
||||
|
||||
void Network::SaveTelnetConnection()
|
||||
{
|
||||
++inLwip;
|
||||
telnetCs = readyTransactions->cs;
|
||||
--inLwip;
|
||||
}
|
||||
|
||||
// Check if there are enough resources left to allocate another RequestState for sending
|
||||
bool Network::CanMakeRequest()
|
||||
{
|
||||
++inLwip;
|
||||
if (freeTransactions == NULL)
|
||||
{
|
||||
--inLwip;
|
||||
return false;
|
||||
}
|
||||
--inLwip;
|
||||
|
||||
return (sendBuffer != NULL);
|
||||
}
|
||||
|
||||
// Stored connections can be be restored by calling one of the following functions
|
||||
bool Network::MakeDataRequest()
|
||||
{
|
||||
// Make sure we have a connection
|
||||
if (dataCs == NULL)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
|
||||
// Get a free transaction
|
||||
irqflags_t flags = cpu_irq_save();
|
||||
RequestState *r = freeTransactions;
|
||||
if (r == NULL)
|
||||
{
|
||||
cpu_irq_restore(flags);
|
||||
reprap.GetPlatform()->Message(HOST_MESSAGE, "Network::MakeDataRequest() - no free transactions!\n");
|
||||
return false;
|
||||
}
|
||||
freeTransactions = r->next;
|
||||
|
||||
// Set up the RequestState and replace the first entry of readyTransactions
|
||||
r->Set(NULL, dataCs, dataSending);
|
||||
cpu_irq_restore(flags);
|
||||
PrependTransaction(&readyTransactions, r);
|
||||
|
||||
return true;
|
||||
return MakeRequest(0, dataCs);
|
||||
}
|
||||
|
||||
bool Network::MakeFTPRequest()
|
||||
{
|
||||
// Make sure we have a connection
|
||||
if (ftpCs == NULL)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
|
||||
// Get a free transaction
|
||||
irqflags_t flags = cpu_irq_save();
|
||||
RequestState *r = freeTransactions;
|
||||
if (r == NULL)
|
||||
{
|
||||
cpu_irq_restore(flags);
|
||||
reprap.GetPlatform()->Message(HOST_MESSAGE, "Network::MakeFTPRequest() - no free transactions!\n");
|
||||
return false;
|
||||
}
|
||||
freeTransactions = r->next;
|
||||
|
||||
// Set up the RequestState and replace the first entry of readyTransactions
|
||||
r->Set(NULL, ftpCs, dataSending);
|
||||
cpu_irq_restore(flags);
|
||||
PrependTransaction(&readyTransactions, r);
|
||||
|
||||
return true;
|
||||
return MakeRequest(0, ftpCs);
|
||||
}
|
||||
|
||||
bool Network::MakeTelnetRequest()
|
||||
bool Network::MakeTelnetRequest(unsigned int dataLength)
|
||||
{
|
||||
// Make sure we have a connection
|
||||
if (telnetCs == NULL)
|
||||
return MakeRequest(dataLength, telnetCs);
|
||||
}
|
||||
|
||||
// Retrieves the sending connection to which dataLength bytes can be appended or
|
||||
// returns a free transaction if dataLength is 0.
|
||||
bool Network::MakeRequest(unsigned int dataLength, ConnectionState *cs)
|
||||
{
|
||||
// Make sure we have a connection and that we have another SendBuffer left
|
||||
if (cs == NULL || sendBuffer == NULL)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
|
||||
// Get a free transaction
|
||||
irqflags_t flags = cpu_irq_save();
|
||||
RequestState *r = freeTransactions;
|
||||
if (r == NULL)
|
||||
// See if we are already writing data on this connection
|
||||
RequestState *r = (dataLength > 0) ? writingTransactions : NULL;
|
||||
++inLwip;
|
||||
while (r != NULL)
|
||||
{
|
||||
cpu_irq_restore(flags);
|
||||
reprap.GetPlatform()->Message(HOST_MESSAGE, "Network::MakeTelnetRequest() - no free transactions!\n");
|
||||
return false;
|
||||
if (r->cs == cs)
|
||||
{
|
||||
while (r->nextWrite != NULL)
|
||||
{
|
||||
r = r->nextWrite;
|
||||
}
|
||||
break;
|
||||
}
|
||||
r = r->next;
|
||||
}
|
||||
freeTransactions = r->next;
|
||||
|
||||
// Set up the RequestState and replace the first entry of readyTransactions
|
||||
r->Set(NULL, telnetCs, dataSending);
|
||||
cpu_irq_restore(flags);
|
||||
// If we are sending and there isn't enough space to append a message, we must get a free transaction
|
||||
if (r == NULL || r->fileBeingSent != NULL || r->outputPointer + dataLength > tcpOutputBufferSize)
|
||||
{
|
||||
r = freeTransactions;
|
||||
if (r == NULL)
|
||||
{
|
||||
--inLwip;
|
||||
reprap.GetPlatform()->Message(HOST_MESSAGE, "Network::MakeRequest() - no free transactions!\n");
|
||||
return false;
|
||||
}
|
||||
freeTransactions = r->next;
|
||||
r->Set(NULL, cs, dataReceiving);
|
||||
}
|
||||
--inLwip;
|
||||
|
||||
// Replace the first entry of readyTransactions with our new transaction,
|
||||
// so it can be removed again by SendAndClose().
|
||||
PrependTransaction(&readyTransactions, r);
|
||||
|
||||
return true;
|
||||
|
@ -1042,7 +1051,6 @@ void RequestState::Write(char b)
|
|||
Network *net = reprap.GetNetwork();
|
||||
if (net->AllocateSendBuffer(sendBuffer))
|
||||
{
|
||||
status = dataSending;
|
||||
outputBuffer = sendBuffer->tcpOutputBuffer;
|
||||
}
|
||||
else
|
||||
|
@ -1063,17 +1071,33 @@ void RequestState::Write(char b)
|
|||
outputPointer++;
|
||||
}
|
||||
|
||||
// This is not called for data, only for internally-
|
||||
// generated short strings at the start of a transmission,
|
||||
// so it should never overflow the buffer (which is checked
|
||||
// anyway).
|
||||
|
||||
void RequestState::Write(const char* s)
|
||||
// This functions attempts to append a string to the send buffer. If the string is too big,
|
||||
// this function will return false, so another RequestState must be used for sending.
|
||||
bool RequestState::Write(const char* s)
|
||||
{
|
||||
while (*s)
|
||||
unsigned int len = strlen(s);
|
||||
if (outputPointer + len >= tcpOutputBufferSize)
|
||||
{
|
||||
Write(*s++);
|
||||
return false;
|
||||
}
|
||||
|
||||
if (sendBuffer == NULL)
|
||||
{
|
||||
Network *net = reprap.GetNetwork();
|
||||
if (net->AllocateSendBuffer(sendBuffer))
|
||||
{
|
||||
outputBuffer = sendBuffer->tcpOutputBuffer;
|
||||
}
|
||||
else
|
||||
{
|
||||
// We cannot write because there are no more send buffers available.
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
memcpy(outputBuffer + outputPointer, s, len);
|
||||
outputPointer += len;
|
||||
return true;
|
||||
}
|
||||
|
||||
// Write formatted data to the output buffer
|
||||
|
@ -1086,7 +1110,6 @@ void RequestState::Printf(const char* fmt, ...)
|
|||
Network *net = reprap.GetNetwork();
|
||||
if (net->AllocateSendBuffer(sendBuffer))
|
||||
{
|
||||
status = dataSending;
|
||||
outputBuffer = sendBuffer->tcpOutputBuffer;
|
||||
}
|
||||
else
|
||||
|
@ -1172,7 +1195,7 @@ bool RequestState::Send()
|
|||
float timeNow = reprap.GetPlatform()->Time();
|
||||
if (timeNow - lastWriteTime > writeTimeout)
|
||||
{
|
||||
debugPrintf("Network: Timing out connection cs=%08x\n", (unsigned int)cs);
|
||||
// debugPrintf("Network: Timing out connection cs=%08x\n", (unsigned int)cs);
|
||||
Close();
|
||||
return false; // this RS will be freed next time round
|
||||
}
|
||||
|
@ -1266,10 +1289,12 @@ uint16_t RequestState::GetLocalPort() const
|
|||
|
||||
void RequestState::Close()
|
||||
{
|
||||
++inLwip;
|
||||
tcp_pcb *pcb = cs->pcb;
|
||||
tcp_poll(pcb, NULL, 4);
|
||||
tcp_recv(pcb, NULL);
|
||||
closeRequested = true;
|
||||
--inLwip;
|
||||
}
|
||||
|
||||
void RequestState::FreePbuf()
|
||||
|
@ -1277,11 +1302,13 @@ void RequestState::FreePbuf()
|
|||
// Tell LWIP that we have processed data
|
||||
if (cs != NULL && bufferLength > 0 && cs->pcb != NULL)
|
||||
{
|
||||
++inLwip;
|
||||
tcp_recved(cs->pcb, bufferLength);
|
||||
bufferLength = 0;
|
||||
--inLwip;
|
||||
}
|
||||
|
||||
// Free pbuf
|
||||
// Free pbuf (pbufs are thread-safe)
|
||||
if (pb != NULL)
|
||||
{
|
||||
pbuf_free(pb);
|
||||
|
|
16
Network.h
16
Network.h
|
@ -27,7 +27,7 @@ Separated out from Platform.h by dc42
|
|||
// Currently we set the MSS (in file network/lwipopts.h) to 1432 which matches the value used by most versions of Windows
|
||||
// and therefore avoids additional memory use and fragmentation.
|
||||
|
||||
const unsigned int tcpOutputBufferCount = MEMP_NUM_TCP_PCB; // number of send buffers
|
||||
const unsigned int tcpOutputBufferCount = MEMP_NUM_TCP_PCB - 1; // number of send buffers
|
||||
const unsigned int tcpOutputBufferSize = 2 * 1432; // size of each send buffer
|
||||
|
||||
#define IP_ADDRESS {192, 168, 1, 10} // Need some sort of default...
|
||||
|
@ -78,7 +78,7 @@ public:
|
|||
bool ReadBuffer(char *&buffer, unsigned int &len);
|
||||
void SentPacketAcknowledged(unsigned int len);
|
||||
void Write(char b);
|
||||
void Write(const char* s);
|
||||
bool Write(const char* s);
|
||||
void Printf(const char *fmt, ...);
|
||||
bool Send();
|
||||
|
||||
|
@ -150,15 +150,19 @@ public:
|
|||
void SaveDataConnection();
|
||||
void SaveFTPConnection();
|
||||
void SaveTelnetConnection();
|
||||
|
||||
bool CanMakeRequest();
|
||||
|
||||
bool MakeDataRequest();
|
||||
bool MakeFTPRequest();
|
||||
bool MakeTelnetRequest();
|
||||
bool MakeTelnetRequest(unsigned int dataLength);
|
||||
|
||||
Network();
|
||||
void Init();
|
||||
void Spin();
|
||||
|
||||
bool InLwip() const { return inLwip; }
|
||||
bool InLwip() const;
|
||||
void ReadPacket();
|
||||
|
||||
private:
|
||||
|
||||
|
@ -168,12 +172,14 @@ private:
|
|||
bool AllocateSendBuffer(SendBuffer *&buffer);
|
||||
void FreeSendBuffer(SendBuffer *buffer);
|
||||
|
||||
bool MakeRequest(unsigned int requiredSpace, ConnectionState *cs);
|
||||
|
||||
RequestState * volatile freeTransactions;
|
||||
RequestState * volatile readyTransactions;
|
||||
RequestState * volatile writingTransactions;
|
||||
|
||||
enum { NetworkInactive, NetworkInitializing, NetworkActive } state;
|
||||
uint8_t inLwip;
|
||||
bool volatile readingData;
|
||||
|
||||
ConnectionState *dataCs;
|
||||
ConnectionState *ftpCs;
|
||||
|
|
179
Platform.cpp
179
Platform.cpp
|
@ -1380,107 +1380,8 @@ const char* MassStorage::CombineName(const char* directory, const char* fileName
|
|||
return scratchString;
|
||||
}
|
||||
|
||||
// List the flat files in a directory. No sub-directories or recursion.
|
||||
|
||||
const char* MassStorage::FileList(const char* directory, bool fromLine)
|
||||
{
|
||||
char fileListBracket = FILE_LIST_BRACKET;
|
||||
char fileListSeparator = FILE_LIST_SEPARATOR;
|
||||
|
||||
if (fromLine)
|
||||
{
|
||||
if (platform->Emulating() == marlin)
|
||||
{
|
||||
fileListBracket = 0;
|
||||
fileListSeparator = '\n';
|
||||
}
|
||||
}
|
||||
|
||||
TCHAR loc[64];
|
||||
|
||||
// Remove the trailing '/' from the directory name
|
||||
size_t len = strnlen(directory, ARRAY_SIZE(loc));
|
||||
if (len == 0)
|
||||
{
|
||||
loc[0] = 0;
|
||||
}
|
||||
else
|
||||
{
|
||||
strncpy(loc, directory, len - 1);
|
||||
loc[len - 1] = 0;
|
||||
}
|
||||
|
||||
// if(reprap.Debug()) {
|
||||
// platform->Message(HOST_MESSAGE, "Opening: ");
|
||||
// platform->Message(HOST_MESSAGE, loc);
|
||||
// platform->Message(HOST_MESSAGE, "\n");
|
||||
// }
|
||||
|
||||
DIR dir;
|
||||
FRESULT res = f_opendir(&dir, loc);
|
||||
if (res == FR_OK)
|
||||
{
|
||||
|
||||
// if(reprap.Debug()) {
|
||||
// platform->Message(HOST_MESSAGE, "Directory open\n");
|
||||
// }
|
||||
|
||||
size_t p = 0;
|
||||
unsigned int foundFiles = 0;
|
||||
|
||||
f_readdir(&dir, 0);
|
||||
|
||||
FILINFO entry;
|
||||
TCHAR loclfname[255]; // this buffer is used to hold the directory name, and later to hold the long filename
|
||||
entry.lfname = loclfname;
|
||||
entry.lfsize = ARRAY_SIZE(loclfname);
|
||||
|
||||
// When we reach, the end of the directory, the function we are about to call suppresses the "end of directory" error code and goes on returning FR_OK.
|
||||
// So we need to check the sector number before the call. What idiot wrote that function???
|
||||
while (dir.sect != 0 && f_readdir(&dir, &entry) == FR_OK)
|
||||
{
|
||||
const TCHAR *fp = (loclfname[0] == 0) ? entry.fname : loclfname;
|
||||
if (*fp != 0)
|
||||
{
|
||||
size_t lastFileStart = p;
|
||||
if (fileListBracket)
|
||||
{
|
||||
fileList[p++] = fileListBracket;
|
||||
}
|
||||
while (*fp != 0 && p <= ARRAY_SIZE(fileList) - 4) // leave space for this character, bracket, separator, bracket
|
||||
{
|
||||
fileList[p++] = *fp++;
|
||||
}
|
||||
if (*fp != 0)
|
||||
{
|
||||
// Not enough space to store this filename
|
||||
p = lastFileStart;
|
||||
break;
|
||||
}
|
||||
foundFiles++;
|
||||
if (fileListBracket)
|
||||
{
|
||||
fileList[p++] = fileListBracket;
|
||||
}
|
||||
fileList[p++] = fileListSeparator;
|
||||
}
|
||||
}
|
||||
|
||||
if (foundFiles == 0)
|
||||
return "NONE";
|
||||
|
||||
fileList[--p] = 0; // Get rid of the last separator
|
||||
return fileList;
|
||||
}
|
||||
|
||||
return "";
|
||||
}
|
||||
|
||||
// Month names. The first entry is used for invalid month numbers.
|
||||
static const char *monthNames[13] = { "???", "Jan", "Feb", "Mar", "Apr", "May", "Jun", "Jul", "Aug", "Sep", "Oct", "Nov", "Dec" };
|
||||
|
||||
// Get a UNIX-compatible file list for the specified directory
|
||||
const char *MassStorage::UnixFileList(const char* directory)
|
||||
// Open a directory to read a file list. Returns true if it contains any files, false otherwise.
|
||||
bool MassStorage::FindFirst(const char *directory, FileInfo &file_info)
|
||||
{
|
||||
TCHAR loc[64 + 1];
|
||||
|
||||
|
@ -1501,45 +1402,81 @@ const char *MassStorage::UnixFileList(const char* directory)
|
|||
loc[len] = 0;
|
||||
}
|
||||
|
||||
DIR dir;
|
||||
FRESULT res = f_opendir(&dir, loc);
|
||||
FRESULT res = f_opendir(&findDir, loc);
|
||||
if (res == FR_OK)
|
||||
{
|
||||
FILINFO entry;
|
||||
char longFilename[255];
|
||||
|
||||
fileList[0] = 0;
|
||||
entry.lfname = longFilename;
|
||||
entry.lfsize = ARRAY_SIZE(longFilename);
|
||||
entry.lfname = file_info.fileName;
|
||||
entry.lfsize = ARRAY_SIZE(file_info.fileName);
|
||||
|
||||
for(;;)
|
||||
{
|
||||
res = f_readdir(&dir, &entry);
|
||||
res = f_readdir(&findDir, &entry);
|
||||
if (res != FR_OK || entry.fname[0] == 0) break;
|
||||
if (StringEquals(entry.fname, ".") || StringEquals(entry.fname, "..")) continue;
|
||||
|
||||
const char *filename = (longFilename[0] == 0) ? entry.fname : longFilename;
|
||||
file_info.isDirectory = (entry.fattrib & AM_DIR);
|
||||
file_info.size = entry.fsize;
|
||||
uint16_t day = entry.fdate & 0x1F;
|
||||
if (day == 0)
|
||||
{
|
||||
// This can happen if a transfer hasn't been processed completely.
|
||||
day = 1;
|
||||
}
|
||||
uint16_t month = (entry.fdate & 0x01E0) >> 5;
|
||||
uint16_t year = (entry.fdate >> 9) + 1980;
|
||||
const char *monthStr = (month <= 12) ? monthNames[month] : monthNames[0];
|
||||
file_info.day = day;
|
||||
file_info.month = (entry.fdate & 0x01E0) >> 5;
|
||||
file_info.year = (entry.fdate >> 9) + 1980;
|
||||
if (file_info.fileName[0] == 0)
|
||||
{
|
||||
strncpy(file_info.fileName, entry.fname, ARRAY_SIZE(file_info.fileName));
|
||||
}
|
||||
|
||||
// Example for a typical UNIX-like file list:
|
||||
// "drwxr-xr-x 2 ftp ftp 0 Apr 11 2013 bin\r\n"
|
||||
|
||||
char dirChar = (entry.fattrib & AM_DIR) ? 'd' : '-';
|
||||
sncatf(fileList, ARRAY_SIZE(fileList), "%crw-rw-rw- 1 ftp ftp %13d %s %02d %04d %s\r\n", dirChar, entry.fsize, monthStr, day, year, filename);
|
||||
return true;
|
||||
}
|
||||
|
||||
return fileList;
|
||||
}
|
||||
|
||||
return "";
|
||||
return false;
|
||||
}
|
||||
|
||||
// Find the next file in a directory. Returns true if another file has been read.
|
||||
bool MassStorage::FindNext(FileInfo &file_info)
|
||||
{
|
||||
FILINFO entry;
|
||||
entry.lfname = file_info.fileName;
|
||||
entry.lfsize = ARRAY_SIZE(file_info.fileName);
|
||||
|
||||
if (f_readdir(&findDir, &entry) != FR_OK || entry.fname[0] == 0)
|
||||
{
|
||||
//f_closedir(findDir);
|
||||
return false;
|
||||
}
|
||||
|
||||
file_info.isDirectory = (entry.fattrib & AM_DIR);
|
||||
file_info.size = entry.fsize;
|
||||
uint16_t day = entry.fdate & 0x1F;
|
||||
if (day == 0)
|
||||
{
|
||||
// This can happen if a transfer hasn't been processed completely.
|
||||
day = 1;
|
||||
}
|
||||
file_info.day = day;
|
||||
file_info.month = (entry.fdate & 0x01E0) >> 5;
|
||||
file_info.year = (entry.fdate >> 9) + 1980;
|
||||
if (file_info.fileName[0] == 0)
|
||||
{
|
||||
strncpy(file_info.fileName, entry.fname, ARRAY_UPB(file_info.fileName));
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
// Month names. The first entry is used for invalid month numbers.
|
||||
static const char *monthNames[13] = { "???", "Jan", "Feb", "Mar", "Apr", "May", "Jun", "Jul", "Aug", "Sep", "Oct", "Nov", "Dec" };
|
||||
|
||||
// Returns the name of the specified month or '???' if the specified value is invalid.
|
||||
const char* MassStorage::GetMonthName(const uint8_t month)
|
||||
{
|
||||
return (month <= 12) ? monthNames[month] : monthNames[0];
|
||||
}
|
||||
|
||||
// Delete a file or directory
|
||||
|
|
23
Platform.h
23
Platform.h
|
@ -85,7 +85,6 @@ Licence: GPL
|
|||
#define DISABLE_DRIVES {false, false, true, false, false, false, false, false} // Set true to disable a drive when it becomes idle
|
||||
#define LOW_STOP_PINS {11, -1, 60, 31, 24, 46, 45, 44} //E Stops not currently used
|
||||
#define HIGH_STOP_PINS {-1, 28, -1, -1, -1, -1, -1, -1}
|
||||
//#define HOME_DIRECTION {1, 1, 1, -1, -1, -1, -1, -1} // 1 for Max/High, -1 for Min/ Low
|
||||
#define ENDSTOP_HIT 1 // when a stop == this it is hit
|
||||
// Indices for motor current digipots (if any)
|
||||
// first 4 are for digipot 1,(on duet)
|
||||
|
@ -218,8 +217,6 @@ const int atxPowerPin = 12; // Arduino Due pin number that controls the ATX
|
|||
const uint16_t lineInBufsize = 256; // use a power of 2 for good performance
|
||||
const uint16_t lineOutBufSize = 2048; // ideally this should be large enough to hold the results of an M503 command,
|
||||
// but could be reduced if we ever need the memory
|
||||
const uint16_t fileListLength = 2000; // increased to allow for the larger size of the Unix-compatible list when using FTP
|
||||
|
||||
/****************************************************************************************************/
|
||||
|
||||
enum EndStopHit
|
||||
|
@ -307,12 +304,26 @@ private:
|
|||
unsigned int outputColumn;
|
||||
};
|
||||
|
||||
// Info returned by FindFirst/FindNext calls
|
||||
class FileInfo
|
||||
{
|
||||
public:
|
||||
|
||||
bool isDirectory;
|
||||
unsigned long size;
|
||||
uint8_t day;
|
||||
uint8_t month;
|
||||
uint16_t year;
|
||||
char fileName[255];
|
||||
};
|
||||
|
||||
class MassStorage
|
||||
{
|
||||
public:
|
||||
|
||||
const char* FileList(const char* directory, bool fromLine); // Returns a list of all the files in the named directory
|
||||
const char* UnixFileList(const char* directory); // Returns a UNIX-compatible file list for the specified directory
|
||||
bool FindFirst(const char *directory, FileInfo &file_info);
|
||||
bool FindNext(FileInfo &file_info);
|
||||
const char* GetMonthName(const uint8_t month);
|
||||
const char* CombineName(const char* directory, const char* fileName);
|
||||
bool Delete(const char* directory, const char* fileName);
|
||||
bool MakeDirectory(const char *parentDir, const char *dirName);
|
||||
|
@ -329,10 +340,10 @@ protected:
|
|||
|
||||
private:
|
||||
|
||||
char fileList[fileListLength];
|
||||
char scratchString[STRING_LENGTH];
|
||||
Platform* platform;
|
||||
FATFS fileSystem;
|
||||
DIR findDir;
|
||||
};
|
||||
|
||||
// This class handles input from, and output to, files.
|
||||
|
|
BIN
Release/RepRapFirmware-078i-dc42.bin
Normal file
BIN
Release/RepRapFirmware-078i-dc42.bin
Normal file
Binary file not shown.
246
Webserver.cpp
246
Webserver.cpp
|
@ -100,12 +100,9 @@ const float pasvPortTimeout = 10.0; // seconds to wait for the FTP data po
|
|||
|
||||
|
||||
// Constructor and initialisation
|
||||
Webserver::Webserver(Platform* p)
|
||||
Webserver::Webserver(Platform* p) : platform(p), webserverActive(false), readingConnection(NULL),
|
||||
fileInfoDetected(false), filamentCount(DRIVES - AXES), printStartTime(0.0)
|
||||
{
|
||||
platform = p;
|
||||
webserverActive = false;
|
||||
readingConnection = NULL;
|
||||
|
||||
httpInterpreter = new HttpInterpreter(p, this);
|
||||
ftpInterpreter = new FtpInterpreter(p, this);
|
||||
telnetInterpreter = new TelnetInterpreter(p, this);
|
||||
|
@ -179,12 +176,6 @@ void Webserver::Spin()
|
|||
{
|
||||
interpreter->ConnectionEstablished();
|
||||
|
||||
// Keep track of the uploading FTP data connections because we can't afford delayed data requests
|
||||
if (is_data_port && interpreter->IsUploading())
|
||||
{
|
||||
readingConnection = req->GetConnection();
|
||||
}
|
||||
|
||||
// Close this request unless ConnectionEstablished() has already used it for sending
|
||||
if (req == net->GetRequest(readingConnection))
|
||||
{
|
||||
|
@ -233,11 +224,7 @@ void Webserver::Spin()
|
|||
// it from the ready transactions by either calling SendAndClose() or CloseRequest().
|
||||
if (interpreter->CharFromClient(c))
|
||||
{
|
||||
if (!interpreter->IsUploading())
|
||||
{
|
||||
readingConnection = NULL;
|
||||
}
|
||||
|
||||
readingConnection = NULL;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
@ -332,6 +319,9 @@ void Webserver::ProcessGcode(const char* gc)
|
|||
}
|
||||
else if (StringStartsWith(gc, "M23 ")) // select SD card file to print next
|
||||
{
|
||||
fileInfoDetected = GetFileInfo(platform->GetGCodeDir(), &gc[4], length, height, filament, filamentCount, layerHeight, generatedBy, ARRAY_SIZE(generatedBy));
|
||||
printStartTime = platform->Time();
|
||||
strncpy(fileBeingPrinted, &gc[4], ARRAY_SIZE(fileBeingPrinted));
|
||||
reprap.GetGCodes()->QueueFileToPrint(&gc[4]);
|
||||
}
|
||||
else if (StringStartsWith(gc, "M112") && !isdigit(gc[4])) // emergency stop
|
||||
|
@ -351,9 +341,14 @@ void Webserver::ProcessGcode(const char* gc)
|
|||
{
|
||||
char c;
|
||||
size_t i = 0;
|
||||
bool reading_whitespace = false;
|
||||
while (i < ARRAY_UPB(gcodeReply) && configFile->Read(c))
|
||||
{
|
||||
gcodeReply[i++] = c;
|
||||
if (!reading_whitespace || (c != ' ' && c != '\t'))
|
||||
{
|
||||
gcodeReply[i++] = c;
|
||||
}
|
||||
reading_whitespace = (c == ' ' || c == '\t');
|
||||
}
|
||||
configFile->Close();
|
||||
gcodeReply[i] = 0;
|
||||
|
@ -471,6 +466,7 @@ void Webserver::StoreGcodeData(const char* data, size_t len)
|
|||
// Handle disconnects here
|
||||
void Webserver::ConnectionLost(const ConnectionState *cs)
|
||||
{
|
||||
// Inform protocol handlers that this connection has been lost
|
||||
uint16_t local_port = cs->GetLocalPort();
|
||||
ProtocolInterpreter *interpreter;
|
||||
switch (local_port)
|
||||
|
@ -499,27 +495,20 @@ void Webserver::ConnectionLost(const ConnectionState *cs)
|
|||
|
||||
interpreter->ConnectionLost(local_port);
|
||||
|
||||
// When our reading connection has been lost, it is no longer important which
|
||||
// connection is read from first.
|
||||
// If our reading connection is lost, it will be no longer important which connection is read from first.
|
||||
if (cs == readingConnection)
|
||||
{
|
||||
readingConnection = NULL;
|
||||
}
|
||||
}
|
||||
|
||||
// Make sure the current connection is preferred, so uploads are handled quicker
|
||||
void Webserver::SetReadingConnection()
|
||||
void Webserver::MessageStringToWebInterface(const char *s, bool error)
|
||||
{
|
||||
Network *net = reprap.GetNetwork();
|
||||
RequestState *r = net->GetRequest();
|
||||
if (r != NULL)
|
||||
if (!webserverActive)
|
||||
{
|
||||
readingConnection = r->GetConnection();
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
void Webserver::MessageStringToWebInterface(const char *s, bool error, bool finished)
|
||||
{
|
||||
if (strlen(s) == 0 && !error)
|
||||
{
|
||||
strcpy(gcodeReply, "ok");
|
||||
|
@ -536,22 +525,20 @@ void Webserver::MessageStringToWebInterface(const char *s, bool error, bool fini
|
|||
}
|
||||
}
|
||||
|
||||
if (finished)
|
||||
{
|
||||
httpInterpreter->ReceivedGcodeReply();
|
||||
telnetInterpreter->HandleGcodeReply(gcodeReply);
|
||||
}
|
||||
httpInterpreter->ReceivedGcodeReply();
|
||||
telnetInterpreter->HandleGcodeReply(s);
|
||||
}
|
||||
|
||||
void Webserver::AppendReplyToWebInterface(const char *s, bool error, bool finished)
|
||||
void Webserver::AppendReplyToWebInterface(const char *s, bool error)
|
||||
{
|
||||
sncatf(gcodeReply, ARRAY_SIZE(gcodeReply), "%s", s);
|
||||
|
||||
if (finished)
|
||||
if (!webserverActive)
|
||||
{
|
||||
httpInterpreter->ReceivedGcodeReply();
|
||||
telnetInterpreter->HandleGcodeReply(gcodeReply);
|
||||
return;
|
||||
}
|
||||
|
||||
sncatf(gcodeReply, ARRAY_SIZE(gcodeReply), "%s", s);
|
||||
httpInterpreter->ReceivedGcodeReply();
|
||||
telnetInterpreter->HandleGcodeReply(s);
|
||||
}
|
||||
|
||||
|
||||
|
@ -682,7 +669,7 @@ void ProtocolInterpreter::FinishUpload(const long file_length)
|
|||
filenameBeingUploaded[0] = 0;
|
||||
}
|
||||
|
||||
// This is overridden in class httpInterpreter
|
||||
// This is overridden in class HttpInterpreter
|
||||
bool ProtocolInterpreter::DebugEnabled() const
|
||||
{
|
||||
return reprap.Debug();
|
||||
|
@ -853,8 +840,6 @@ bool Webserver::HttpInterpreter::GetJsonResponse(const char* request, const char
|
|||
{
|
||||
FileStore *file = platform->GetFileStore("0:/", value, true);
|
||||
StartUpload(file);
|
||||
webserver->SetReadingConnection();
|
||||
|
||||
GetJsonUploadResponse();
|
||||
}
|
||||
else if (StringEquals(request, "upload_data") && StringEquals(key, "data"))
|
||||
|
@ -884,35 +869,82 @@ bool Webserver::HttpInterpreter::GetJsonResponse(const char* request, const char
|
|||
else if (StringEquals(request, "files"))
|
||||
{
|
||||
const char* dir = (StringEquals(key, "dir")) ? value : platform->GetGCodeDir();
|
||||
const char* fileList = platform->GetMassStorage()->FileList(dir, false);
|
||||
snprintf(jsonResponse, ARRAY_SIZE(jsonResponse), "{\"files\":[%s]}", fileList);
|
||||
}
|
||||
else if (StringEquals(request, "fileinfo") && StringEquals(key, "name"))
|
||||
{
|
||||
unsigned long length;
|
||||
float height, filament[DRIVES - AXES], layerHeight;
|
||||
unsigned int numFilaments = DRIVES - AXES;
|
||||
char generatedBy[50];
|
||||
bool found = webserver->GetFileInfo(value, length, height, filament, numFilaments, layerHeight, generatedBy, ARRAY_SIZE(generatedBy));
|
||||
if (found)
|
||||
|
||||
FileInfo file_info;
|
||||
if (platform->GetMassStorage()->FindFirst(dir, file_info))
|
||||
{
|
||||
strcpy(jsonResponse, "{\"files\":[");
|
||||
|
||||
do {
|
||||
// build the file list here, but keep 2 characters free to terminate the JSON message
|
||||
sncatf(jsonResponse, ARRAY_SIZE(jsonResponse) - 2, "%c%s%c%c", FILE_LIST_BRACKET, file_info.fileName, FILE_LIST_BRACKET, FILE_LIST_SEPARATOR);
|
||||
} while (platform->GetMassStorage()->FindNext(file_info));
|
||||
|
||||
jsonResponse[strlen(jsonResponse) -1] = 0;
|
||||
sncatf(jsonResponse, ARRAY_SIZE(jsonResponse), "]}");
|
||||
}
|
||||
else
|
||||
{
|
||||
strcpy(jsonResponse, "{\"files\":[NONE]}");
|
||||
}
|
||||
}
|
||||
else if (StringEquals(request, "fileinfo"))
|
||||
{
|
||||
// Poll file info for a specific file
|
||||
if (StringEquals(key, "name"))
|
||||
{
|
||||
unsigned long length;
|
||||
float height, filament[DRIVES - AXES], layerHeight;
|
||||
unsigned int numFilaments = DRIVES - AXES;
|
||||
char generatedBy[50];
|
||||
|
||||
bool found = webserver->GetFileInfo("0:/", value, length, height, filament, numFilaments, layerHeight, generatedBy, ARRAY_SIZE(generatedBy));
|
||||
if (found)
|
||||
{
|
||||
snprintf(jsonResponse, ARRAY_SIZE(jsonResponse),
|
||||
"{\"err\":0,\"size\":%lu,\"height\":%.2f,\"layerHeight\":%.2f,\"filament\":",
|
||||
length, height, layerHeight);
|
||||
char ch = '[';
|
||||
if (numFilaments == 0)
|
||||
{
|
||||
sncatf(jsonResponse, ARRAY_SIZE(jsonResponse), "%c", ch);
|
||||
}
|
||||
else
|
||||
{
|
||||
for (unsigned int i = 0; i < numFilaments; ++i)
|
||||
{
|
||||
sncatf(jsonResponse, ARRAY_SIZE(jsonResponse), "%c%.1f", ch, filament[i]);
|
||||
ch = ',';
|
||||
}
|
||||
}
|
||||
sncatf(jsonResponse, ARRAY_SIZE(jsonResponse), "],\"generatedBy\":\"%s\"}", generatedBy);
|
||||
}
|
||||
else
|
||||
{
|
||||
snprintf(jsonResponse, ARRAY_SIZE(jsonResponse), "{\"err\":1}");
|
||||
}
|
||||
}
|
||||
else if (reprap.GetGCodes()->PrintingAFile() && webserver->fileInfoDetected)
|
||||
{
|
||||
// Poll file info about a file currently being printed
|
||||
snprintf(jsonResponse, ARRAY_SIZE(jsonResponse),
|
||||
"{\"err\":0,\"size\":%lu,\"height\":%.2f,\"layerHeight\":%.2f,\"filament\":",
|
||||
length, height, layerHeight);
|
||||
webserver->length, webserver->height, webserver->layerHeight);
|
||||
char ch = '[';
|
||||
if (numFilaments == 0)
|
||||
if (webserver->filamentCount == 0)
|
||||
{
|
||||
sncatf(jsonResponse, ARRAY_SIZE(jsonResponse), "%c", ch);
|
||||
}
|
||||
else
|
||||
{
|
||||
for (unsigned int i = 0; i < numFilaments; ++i)
|
||||
for (unsigned int i = 0; i < webserver->filamentCount; ++i)
|
||||
{
|
||||
sncatf(jsonResponse, ARRAY_SIZE(jsonResponse), "%c%.1f", ch, filament[i]);
|
||||
sncatf(jsonResponse, ARRAY_SIZE(jsonResponse), "%c%.1f", ch, webserver->filament[i]);
|
||||
ch = ',';
|
||||
}
|
||||
}
|
||||
sncatf(jsonResponse, ARRAY_SIZE(jsonResponse), "],\"generatedBy\":\"%s\"}", generatedBy);
|
||||
sncatf(jsonResponse, ARRAY_SIZE(jsonResponse), "],\"generatedBy\":\"%s\",\"printDuration\":%d,\"fileName\":\"%s\"}",
|
||||
webserver->generatedBy, (int)((platform->Time() - webserver->printStartTime) * 1000.0), webserver->fileBeingPrinted);
|
||||
}
|
||||
else
|
||||
{
|
||||
|
@ -947,11 +979,11 @@ bool Webserver::HttpInterpreter::GetJsonResponse(const char* request, const char
|
|||
}
|
||||
else if (StringEquals(request, "axes"))
|
||||
{
|
||||
strncpy(jsonResponse, "{\"axes\":", ARRAY_SIZE(jsonResponse));
|
||||
strcpy(jsonResponse, "{\"axes\":");
|
||||
char ch = '[';
|
||||
for (int8_t drive = 0; drive < AXES; drive++)
|
||||
{
|
||||
sncatf(jsonResponse, ARRAY_SIZE(jsonResponse), "%c%.1f", ch, platform->AxisTotalLength(drive));
|
||||
sncatf(jsonResponse, ARRAY_SIZE(jsonResponse) - 2, "%c%.1f", ch, platform->AxisTotalLength(drive));
|
||||
ch = ',';
|
||||
}
|
||||
sncatf(jsonResponse, ARRAY_SIZE(jsonResponse), "]}");
|
||||
|
@ -1032,12 +1064,12 @@ void Webserver::HttpInterpreter::GetStatusResponse(uint8_t type)
|
|||
ch = ',';
|
||||
}
|
||||
|
||||
// Send extruder total extrusion since power up or last G92
|
||||
// Send extruder total extrusion since power up, last G92 or last M23
|
||||
sncatf(jsonResponse, ARRAY_SIZE(jsonResponse), "],\"extr\":"); // announce the extruder positions
|
||||
ch = '[';
|
||||
for (int8_t drive = 0; drive < reprap.GetExtrudersInUse(); drive++) // loop through extruders
|
||||
{
|
||||
sncatf(jsonResponse, ARRAY_SIZE(jsonResponse), "%c%.3f", ch, gc->GetExtruderPosition(drive));
|
||||
sncatf(jsonResponse, ARRAY_SIZE(jsonResponse), "%c%.1f", ch, gc->GetExtruderPosition(drive));
|
||||
ch = ',';
|
||||
}
|
||||
sncatf(jsonResponse, ARRAY_SIZE(jsonResponse), "]");
|
||||
|
@ -1121,7 +1153,7 @@ void Webserver::HttpInterpreter::GetStatusResponse(uint8_t type)
|
|||
|
||||
// Send the response to the last command. Do this last because it is long and may need to be truncated.
|
||||
sncatf(jsonResponse, ARRAY_SIZE(jsonResponse), ",\"resp\":\"");
|
||||
size_t jp = strnlen(jsonResponse, ARRAY_UPB(jsonResponse));
|
||||
size_t jp = strnlen(jsonResponse, ARRAY_SIZE(jsonResponse));
|
||||
while (*p != 0 && jp < ARRAY_SIZE(jsonResponse) - 3) // leave room for the final '"}\0'
|
||||
{
|
||||
char c = *p++;
|
||||
|
@ -2001,8 +2033,43 @@ void Webserver::FtpInterpreter::ProcessLine()
|
|||
// send file list via data port
|
||||
if (net->MakeDataRequest())
|
||||
{
|
||||
RequestState *data_req = net->GetRequest();
|
||||
data_req->Write(platform->GetMassStorage()->UnixFileList(currentDir));
|
||||
FileInfo file_info;
|
||||
if (platform->GetMassStorage()->FindFirst(currentDir, file_info))
|
||||
{
|
||||
RequestState *data_req = net->GetRequest();
|
||||
char line[300];
|
||||
|
||||
do {
|
||||
// Example for a typical UNIX-like file list:
|
||||
// "drwxr-xr-x 2 ftp ftp 0 Apr 11 2013 bin\r\n"
|
||||
char dirChar = (file_info.isDirectory) ? 'd' : '-';
|
||||
snprintf(line, ARRAY_SIZE(line), "%crw-rw-rw- 1 ftp ftp %13d %s %02d %04d %s\r\n",
|
||||
dirChar, file_info.size, platform->GetMassStorage()->GetMonthName(file_info.month),
|
||||
file_info.day, file_info.year, file_info.fileName);
|
||||
|
||||
// We may have to send the FTP file list in multiple chunks, so check
|
||||
// if there's enough room left to write the current line.
|
||||
if (!data_req->Write(line))
|
||||
{
|
||||
if (net->CanMakeRequest())
|
||||
{
|
||||
net->SendAndClose(NULL, true);
|
||||
|
||||
net->MakeDataRequest();
|
||||
data_req = net->GetRequest();
|
||||
data_req->Write(line);
|
||||
}
|
||||
else
|
||||
{
|
||||
// debugPrintf("Webserver: FTP file list was truncated\n");
|
||||
// Note: If f_closedir() was implemented in FatFs, we'd have to call
|
||||
// FindNext() here until it returns false.
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
} while (platform->GetMassStorage()->FindNext(file_info));
|
||||
}
|
||||
net->SendAndClose(NULL);
|
||||
state = doingPasvIO;
|
||||
}
|
||||
|
@ -2351,7 +2418,7 @@ void Webserver::TelnetInterpreter::ProcessLine()
|
|||
void Webserver::TelnetInterpreter::HandleGcodeReply(const char *reply)
|
||||
{
|
||||
Network *net = reprap.GetNetwork();
|
||||
if (state >= authenticated && net->MakeTelnetRequest())
|
||||
if (state >= authenticated && net->MakeTelnetRequest(strlen(reply)))
|
||||
{
|
||||
RequestState *req = net->GetRequest();
|
||||
|
||||
|
@ -2386,16 +2453,18 @@ void Webserver::TelnetInterpreter::HandleGcodeReply(const char *reply)
|
|||
//
|
||||
//********************************************************************************************
|
||||
|
||||
// Get information for a file on the SD card.
|
||||
bool Webserver::GetFileInfo(const char *fileName, unsigned long& length, float& height, float *filamentUsed, unsigned int& numFilaments, float& layerHeight, char* generatedBy, size_t generatedByLength)
|
||||
// Get information for a file on the SD card
|
||||
bool Webserver::GetFileInfo(const char *directory, const char *fileName, unsigned long& length, float& height,
|
||||
float *filamentUsed, unsigned int& numFilaments, float& layerHeight, char* generatedBy, size_t generatedByLength)
|
||||
{
|
||||
FileStore *f = platform->GetFileStore("0:/", fileName, false);
|
||||
FileStore *f = platform->GetFileStore(directory, fileName, false);
|
||||
if (f != NULL)
|
||||
{
|
||||
// Try to find the object height by looking for the last G1 Zxxx command in the file
|
||||
length = f->Length();
|
||||
height = 0.0;
|
||||
layerHeight = 0.0;
|
||||
numFilaments = DRIVES - AXES;
|
||||
generatedBy[0] = 0;
|
||||
|
||||
if (length != 0 && (StringEndsWith(fileName, ".gcode") || StringEndsWith(fileName, ".g") || StringEndsWith(fileName, ".gco") || StringEndsWith(fileName, ".gc")))
|
||||
|
@ -2403,6 +2472,7 @@ bool Webserver::GetFileInfo(const char *fileName, unsigned long& length, float&
|
|||
const size_t readSize = 512; // read 512 bytes at a time (1K doesn't seem to work when we read from the end)
|
||||
const size_t overlap = 100;
|
||||
char buf[readSize + overlap + 1]; // need the +1 so we can add a null terminator
|
||||
bool foundLayerHeight = false;
|
||||
|
||||
// Get slic3r settings by reading from the start of the file. We only read the first 1K or so, everything we are looking for should be there.
|
||||
{
|
||||
|
@ -2413,20 +2483,10 @@ bool Webserver::GetFileInfo(const char *fileName, unsigned long& length, float&
|
|||
buf[sizeToRead] = 0;
|
||||
|
||||
// Look for layer height
|
||||
const char* layerHeightString = "; layer_height ";
|
||||
const char *pos = strstr(buf, layerHeightString);
|
||||
if (pos != NULL)
|
||||
{
|
||||
pos += strlen(layerHeightString);
|
||||
while (strchr(" \t=", *pos))
|
||||
{
|
||||
++pos;
|
||||
}
|
||||
layerHeight = strtod(pos, NULL);
|
||||
}
|
||||
foundLayerHeight = FindLayerHeight(buf, sizeToRead, layerHeight);
|
||||
|
||||
const char* generatedByString = "; generated by ";
|
||||
pos = strstr(buf, generatedByString);
|
||||
const char* pos = strstr(buf, generatedByString);
|
||||
if (pos != NULL)
|
||||
{
|
||||
pos += strlen(generatedByString);
|
||||
|
@ -2496,6 +2556,12 @@ bool Webserver::GetFileInfo(const char *fileName, unsigned long& length, float&
|
|||
}
|
||||
}
|
||||
|
||||
// Search for layer height
|
||||
if (!foundLayerHeight)
|
||||
{
|
||||
foundLayerHeight = FindLayerHeight(buf, sizeToScan, layerHeight);
|
||||
}
|
||||
|
||||
// Search for object height
|
||||
if (FindHeight(buf, sizeToScan, height))
|
||||
{
|
||||
|
@ -2561,6 +2627,24 @@ bool Webserver::FindHeight(const char* buf, size_t len, float& height)
|
|||
return false;
|
||||
}
|
||||
|
||||
// Scan the buffer for the layer height. The buffer is null-terminated.
|
||||
bool Webserver::FindLayerHeight(const char *buf, size_t len, float& layerHeight)
|
||||
{
|
||||
const char* layerHeightString = "; layer_height ";
|
||||
const char *pos = strstr(buf, layerHeightString);
|
||||
if (pos != NULL)
|
||||
{
|
||||
pos += strlen(layerHeightString);
|
||||
while (strchr(" \t=", *pos))
|
||||
{
|
||||
++pos;
|
||||
}
|
||||
layerHeight = strtod(pos, NULL);
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
// Scan the buffer for the filament used. The buffer is null-terminated.
|
||||
// Returns the number of filaments found.
|
||||
unsigned int Webserver::FindFilamentUsed(const char* buf, size_t len, float *filamentUsed, unsigned int maxFilaments)
|
||||
|
|
33
Webserver.h
33
Webserver.h
|
@ -48,7 +48,7 @@ const unsigned int maxCommandWords = 4; // max number of space-separated words
|
|||
const unsigned int maxQualKeys = 5; // max number of key/value pairs in the qualifier
|
||||
const unsigned int maxHeaders = 10; // max number of key/value pairs in the headers
|
||||
|
||||
const unsigned int jsonReplyLength = 1000; // size of buffer used to hold JSON reply
|
||||
const unsigned int jsonReplyLength = 2000; // size of buffer used to hold JSON reply
|
||||
|
||||
/* FTP */
|
||||
|
||||
|
@ -69,18 +69,18 @@ class ProtocolInterpreter
|
|||
public:
|
||||
|
||||
ProtocolInterpreter(Platform *p, Webserver *ws);
|
||||
virtual void ConnectionEstablished() {}
|
||||
virtual void ConnectionLost(uint16_t local_port) {}
|
||||
virtual void ConnectionEstablished() { }
|
||||
virtual void ConnectionLost(uint16_t local_port) { }
|
||||
virtual bool CharFromClient(const char c) = 0;
|
||||
virtual void ResetState() = 0;
|
||||
|
||||
virtual bool StoreUploadData(const char* data, unsigned int len);
|
||||
virtual bool FlushUploadData();
|
||||
virtual bool DebugEnabled() const;
|
||||
|
||||
void CancelUpload();
|
||||
bool IsUploading() const { return uploadState != notUploading; }
|
||||
|
||||
virtual bool DebugEnabled() const;
|
||||
|
||||
virtual ~ProtocolInterpreter() { } // to keep Eclipse happy
|
||||
|
||||
protected:
|
||||
|
@ -126,7 +126,6 @@ class Webserver
|
|||
char ReadGCode();
|
||||
|
||||
void ConnectionLost(const ConnectionState *cs);
|
||||
void SetReadingConnection();
|
||||
void ConnectionError();
|
||||
void WebDebug(bool wdb);
|
||||
|
||||
|
@ -134,8 +133,16 @@ class Webserver
|
|||
|
||||
protected:
|
||||
|
||||
void MessageStringToWebInterface(const char *s, bool error, bool finished = true);
|
||||
void AppendReplyToWebInterface(const char* s, bool error, bool finished = true);
|
||||
// File information about the file being printed
|
||||
bool fileInfoDetected;
|
||||
unsigned long length;
|
||||
float height, filament[DRIVES - AXES], layerHeight;
|
||||
unsigned int filamentCount;
|
||||
char generatedBy[50], fileBeingPrinted[255];
|
||||
float printStartTime;
|
||||
|
||||
void MessageStringToWebInterface(const char *s, bool error);
|
||||
void AppendReplyToWebInterface(const char* s, bool error);
|
||||
|
||||
private:
|
||||
|
||||
|
@ -144,12 +151,12 @@ class Webserver
|
|||
public:
|
||||
|
||||
HttpInterpreter(Platform *p, Webserver *ws);
|
||||
|
||||
bool CharFromClient(const char c);
|
||||
void ResetState();
|
||||
|
||||
bool FlushUploadData();
|
||||
virtual bool DebugEnabled() /*override*/ const { return webDebug; }
|
||||
void ReceivedGcodeReply();
|
||||
virtual bool DebugEnabled() /*override*/ const { return webDebug; }
|
||||
void SetDebug(bool b) { webDebug = b; }
|
||||
|
||||
private:
|
||||
|
@ -295,15 +302,17 @@ class Webserver
|
|||
void StoreGcodeData(const char* data, size_t len);
|
||||
|
||||
// File info methods
|
||||
bool GetFileInfo(const char *fileName, unsigned long& length, float& height, float *filamentUsed, unsigned int& numFilaments, float& layerHeight, char* generatedBy, size_t generatedByLength);
|
||||
bool GetFileInfo(const char *directory, const char *fileName, unsigned long& length, float& height, float *filamentUsed,
|
||||
unsigned int& numFilaments, float& layerHeight, char* generatedBy, size_t generatedByLength);
|
||||
static bool FindHeight(const char* buf, size_t len, float& height);
|
||||
static bool FindLayerHeight(const char* buf, size_t len, float& layerHeight);
|
||||
static unsigned int FindFilamentUsed(const char* buf, size_t len, float *filamentUsed, unsigned int maxFilaments);
|
||||
static void CopyParameterText(const char* src, char *dst, size_t length);
|
||||
|
||||
// Buffer to hold gcode that is ready for processing
|
||||
char gcodeBuffer[gcodeBufLength];
|
||||
unsigned int gcodeReadIndex, gcodeWriteIndex; // head and tail indices into gcodeBuffer
|
||||
char gcodeReply[STRING_LENGTH + 1];
|
||||
char gcodeReply[2048];
|
||||
|
||||
// Misc
|
||||
char password[SHORT_STRING_LENGTH + 1];
|
||||
|
|
Reference in a new issue