Version 1.17RC3
Bed compensation taper is now applied to 3/4/5-point compensation methods too Recognise generated-with comment in new Cura gcode files Recognise filament-used info min new kisslicer files When uploading files, create the full path if necessary Duet 0.8.5 webserver looks for gzipped files first A second controlled fan on the Duet 0.6 is no longer inverted
This commit is contained in:
parent
8bfd6d49f6
commit
fdcef50706
29 changed files with 4327 additions and 214 deletions
BIN
Driver/DuetDriverFiles.zip
Normal file
BIN
Driver/DuetDriverFiles.zip
Normal file
Binary file not shown.
BIN
Release/Duet-0.6-0.8.5/Edge/DuetWebControl-1.14-b4.zip
Normal file
BIN
Release/Duet-0.6-0.8.5/Edge/DuetWebControl-1.14-b4.zip
Normal file
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
BIN
Release/Duet-WiFi/Edge/DuetWebControl-1.14-b4.bin
Normal file
BIN
Release/Duet-WiFi/Edge/DuetWebControl-1.14-b4.bin
Normal file
Binary file not shown.
After Width: | Height: | Size: 3 MiB |
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
|
@ -28,11 +28,11 @@ Licence: GPL
|
|||
// Firmware name is now defined in the Pins file
|
||||
|
||||
#ifndef VERSION
|
||||
# define VERSION "1.17RC2"
|
||||
# define VERSION "1.17RC3"
|
||||
#endif
|
||||
|
||||
#ifndef DATE
|
||||
# define DATE "2016-12-18"
|
||||
# define DATE "2016-12-21"
|
||||
#endif
|
||||
|
||||
#define AUTHORS "reprappro, dc42, zpl, t3p3, dnewman"
|
||||
|
|
|
@ -696,7 +696,7 @@ void Webserver::HttpInterpreter::DoFastUpload()
|
|||
void Webserver::HttpInterpreter::SendFile(const char* nameOfFileToSend, bool isWebFile)
|
||||
{
|
||||
NetworkTransaction *transaction = webserver->currentTransaction;
|
||||
FileStore *fileToSend;
|
||||
FileStore *fileToSend = nullptr;
|
||||
bool zip = false;
|
||||
|
||||
if (isWebFile)
|
||||
|
@ -709,10 +709,9 @@ void Webserver::HttpInterpreter::SendFile(const char* nameOfFileToSend, bool isW
|
|||
nameOfFileToSend = INDEX_PAGE_FILE;
|
||||
}
|
||||
}
|
||||
fileToSend = platform->GetFileStore(platform->GetWebDir(), nameOfFileToSend, false);
|
||||
|
||||
// If we failed to open the file, see if we can open a file with the same name and a ".gz" extension
|
||||
if (fileToSend == nullptr && !StringEndsWith(nameOfFileToSend, ".gz") && strlen(nameOfFileToSend) + 3 <= FILENAME_LENGTH)
|
||||
// Try to open a gzipped version of the file first
|
||||
if (!StringEndsWith(nameOfFileToSend, ".gz") && strlen(nameOfFileToSend) + 3 <= FILENAME_LENGTH)
|
||||
{
|
||||
char nameBuf[FILENAME_LENGTH + 1];
|
||||
strcpy(nameBuf, nameOfFileToSend);
|
||||
|
@ -724,6 +723,12 @@ 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);
|
||||
}
|
||||
|
||||
// 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")))
|
||||
{
|
||||
|
|
|
@ -213,4 +213,757 @@ void Network::SetHostname(const char *name)
|
|||
}
|
||||
}
|
||||
|
||||
bool Network::Lock()
|
||||
{
|
||||
//TODO
|
||||
return true;
|
||||
}
|
||||
|
||||
void Network::Unlock()
|
||||
{
|
||||
//TODO
|
||||
}
|
||||
|
||||
bool Network::InLwip() const
|
||||
{
|
||||
//TODO
|
||||
return false;
|
||||
}
|
||||
|
||||
// This is called by the web server to get the next networking transaction.
|
||||
//
|
||||
// If cs is NULL, the transaction from the head of readyTransactions will be retrieved.
|
||||
// If cs is not NULL, the first transaction with the matching connection will be returned.
|
||||
//
|
||||
// This method also ensures that the retrieved transaction is moved to the first item of
|
||||
// readyTransactions, so that a subsequent call with a NULL cs parameter will return exactly
|
||||
// the same instance.
|
||||
NetworkTransaction *Network::GetTransaction(const ConnectionState *cs)
|
||||
{
|
||||
#if 1
|
||||
return nullptr;
|
||||
#else
|
||||
// See if there is any transaction at all
|
||||
NetworkTransaction *transaction = readyTransactions;
|
||||
if (transaction == nullptr)
|
||||
{
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
// If no specific connection is specified or if the first item already matches the
|
||||
// connection we are looking for, just return it
|
||||
if (cs == nullptr || transaction->GetConnection() == cs)
|
||||
{
|
||||
return transaction;
|
||||
}
|
||||
|
||||
// We are looking for a specific transaction, but it's not the first item.
|
||||
// Search for it and move it to the head of readyTransactions
|
||||
NetworkTransaction *previous = transaction;
|
||||
for(NetworkTransaction *item = transaction->next; item != nullptr; item = item->next)
|
||||
{
|
||||
if (item->GetConnection() == cs)
|
||||
{
|
||||
previous->next = item->next;
|
||||
item->next = readyTransactions;
|
||||
readyTransactions = item;
|
||||
return item;
|
||||
}
|
||||
previous = item;
|
||||
}
|
||||
|
||||
// We failed to find a valid transaction for the given connection
|
||||
return nullptr;
|
||||
#endif
|
||||
}
|
||||
|
||||
void Network::OpenDataPort(uint16_t port)
|
||||
{
|
||||
//TODO
|
||||
#if 0
|
||||
closingDataPort = false;
|
||||
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);
|
||||
#endif
|
||||
}
|
||||
|
||||
uint16_t Network::GetDataPort() const
|
||||
{
|
||||
#if 1
|
||||
return 0; //TODO
|
||||
#else
|
||||
return (closingDataPort || (ftp_pasv_pcb == nullptr) ? 0 : ftp_pasv_pcb->local_port);
|
||||
#endif
|
||||
}
|
||||
|
||||
// Close FTP data port and purge associated PCB
|
||||
void Network::CloseDataPort()
|
||||
{
|
||||
//TODO
|
||||
#if 0
|
||||
// See if it's already being closed
|
||||
if (closingDataPort)
|
||||
{
|
||||
return;
|
||||
}
|
||||
closingDataPort = true;
|
||||
|
||||
// Close remote connection of our data port or do it as soon as the last packet has been sent
|
||||
if (dataCs != nullptr)
|
||||
{
|
||||
NetworkTransaction *mySendingTransaction = dataCs->sendingTransaction;
|
||||
if (mySendingTransaction != nullptr)
|
||||
{
|
||||
mySendingTransaction->Close();
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
// We can close it now, so do it here
|
||||
if (ftp_pasv_pcb != nullptr)
|
||||
{
|
||||
tcp_accept(ftp_pasv_pcb, nullptr);
|
||||
tcp_close(ftp_pasv_pcb);
|
||||
ftp_pasv_pcb = nullptr;
|
||||
}
|
||||
closingDataPort = false;
|
||||
#endif
|
||||
}
|
||||
|
||||
// These methods keep track of our connections in case we need to send to one of them
|
||||
void Network::SaveDataConnection()
|
||||
{
|
||||
//TODO
|
||||
#if 0
|
||||
dataCs = readyTransactions->cs;
|
||||
#endif
|
||||
}
|
||||
|
||||
void Network::SaveFTPConnection()
|
||||
{
|
||||
//TODO
|
||||
#if 0
|
||||
ftpCs = readyTransactions->cs;
|
||||
#endif
|
||||
}
|
||||
|
||||
void Network::SaveTelnetConnection()
|
||||
{
|
||||
//TODO
|
||||
#if 0
|
||||
telnetCs = readyTransactions->cs;
|
||||
#endif
|
||||
}
|
||||
|
||||
bool Network::AcquireFTPTransaction()
|
||||
{
|
||||
#if 1
|
||||
return false; //TODO
|
||||
#else
|
||||
return AcquireTransaction(ftpCs);
|
||||
#endif
|
||||
}
|
||||
|
||||
bool Network::AcquireDataTransaction()
|
||||
{
|
||||
#if 1
|
||||
return false; //TODO
|
||||
#else
|
||||
return AcquireTransaction(dataCs);
|
||||
#endif
|
||||
}
|
||||
|
||||
bool Network::AcquireTelnetTransaction()
|
||||
{
|
||||
#if 1
|
||||
return false; //TODO
|
||||
#else
|
||||
return AcquireTransaction(telnetCs);
|
||||
#endif
|
||||
}
|
||||
|
||||
//***************************************************************************************************
|
||||
|
||||
// ConnectionState class
|
||||
|
||||
#if 0
|
||||
void ConnectionState::Init(tcp_pcb *p)
|
||||
{
|
||||
pcb = p;
|
||||
localPort = p->local_port;
|
||||
remoteIPAddress = p->remote_ip.addr;
|
||||
remotePort = p->remote_port;
|
||||
next = nullptr;
|
||||
sendingTransaction = nullptr;
|
||||
persistConnection = true;
|
||||
isTerminated = false;
|
||||
}
|
||||
#endif
|
||||
|
||||
void ConnectionState::Terminate()
|
||||
{
|
||||
//TODO
|
||||
#if 0
|
||||
if (pcb != nullptr)
|
||||
{
|
||||
tcp_abort(pcb);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
//***************************************************************************************************
|
||||
// NetworkTransaction class
|
||||
|
||||
NetworkTransaction::NetworkTransaction(NetworkTransaction *n) : next(n), status(released)
|
||||
{
|
||||
sendStack = new OutputStack();
|
||||
}
|
||||
|
||||
void NetworkTransaction::Set(pbuf *p, ConnectionState *c, TransactionStatus s)
|
||||
{
|
||||
cs = c;
|
||||
// pb = readingPb = p;
|
||||
status = s;
|
||||
// inputPointer = 0;
|
||||
sendBuffer = nullptr;
|
||||
fileBeingSent = nullptr;
|
||||
closeRequested = false;
|
||||
nextWrite = nullptr;
|
||||
dataAcknowledged = false;
|
||||
}
|
||||
|
||||
bool NetworkTransaction::HasMoreDataToRead() const
|
||||
{
|
||||
//TODO
|
||||
return false;
|
||||
}
|
||||
|
||||
// Read one char from the NetworkTransaction
|
||||
bool NetworkTransaction::Read(char& b)
|
||||
{
|
||||
#if 1
|
||||
return false;
|
||||
#else
|
||||
if (readingPb == nullptr)
|
||||
{
|
||||
b = 0;
|
||||
return false;
|
||||
}
|
||||
|
||||
b = ((const char*)readingPb->payload)[inputPointer++];
|
||||
if (inputPointer == readingPb->len)
|
||||
{
|
||||
readingPb = readingPb->next;
|
||||
inputPointer = 0;
|
||||
}
|
||||
return true;
|
||||
#endif
|
||||
}
|
||||
|
||||
// Read data from the NetworkTransaction and return true on success
|
||||
bool NetworkTransaction::ReadBuffer(const char *&buffer, size_t &len)
|
||||
{
|
||||
#if 1
|
||||
return false;
|
||||
#else
|
||||
if (readingPb == nullptr)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
|
||||
if (inputPointer >= readingPb->len)
|
||||
{
|
||||
readingPb = readingPb->next;
|
||||
inputPointer = 0;
|
||||
if (readingPb == nullptr)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
buffer = (const char*)readingPb->payload + inputPointer;
|
||||
len = readingPb->len - inputPointer;
|
||||
readingPb = readingPb->next;
|
||||
inputPointer = 0;
|
||||
return true;
|
||||
#endif
|
||||
}
|
||||
|
||||
void NetworkTransaction::Write(char b)
|
||||
{
|
||||
if (CanWrite())
|
||||
{
|
||||
if (sendBuffer == nullptr && !OutputBuffer::Allocate(sendBuffer))
|
||||
{
|
||||
// Should never get here
|
||||
return;
|
||||
}
|
||||
sendBuffer->cat(b);
|
||||
}
|
||||
}
|
||||
|
||||
void NetworkTransaction::Write(const char* s)
|
||||
{
|
||||
if (CanWrite())
|
||||
{
|
||||
if (sendBuffer == nullptr && !OutputBuffer::Allocate(sendBuffer))
|
||||
{
|
||||
// Should never get here
|
||||
return;
|
||||
}
|
||||
sendBuffer->cat(s);
|
||||
}
|
||||
}
|
||||
|
||||
void NetworkTransaction::Write(StringRef ref)
|
||||
{
|
||||
Write(ref.Pointer(), ref.strlen());
|
||||
}
|
||||
|
||||
void NetworkTransaction::Write(const char* s, size_t len)
|
||||
{
|
||||
if (CanWrite())
|
||||
{
|
||||
if (sendBuffer == nullptr && !OutputBuffer::Allocate(sendBuffer))
|
||||
{
|
||||
// Should never get here
|
||||
return;
|
||||
}
|
||||
sendBuffer->cat(s, len);
|
||||
}
|
||||
}
|
||||
|
||||
void NetworkTransaction::Write(OutputBuffer *buffer)
|
||||
{
|
||||
if (CanWrite())
|
||||
{
|
||||
// Note we use an individual stack here, because we don't want to link different
|
||||
// OutputBuffers for different destinations together...
|
||||
sendStack->Push(buffer);
|
||||
}
|
||||
else
|
||||
{
|
||||
// Don't keep buffers we can't send...
|
||||
OutputBuffer::ReleaseAll(buffer);
|
||||
}
|
||||
}
|
||||
|
||||
void NetworkTransaction::Write(OutputStack *stack)
|
||||
{
|
||||
if (stack != nullptr)
|
||||
{
|
||||
if (CanWrite())
|
||||
{
|
||||
sendStack->Append(stack);
|
||||
}
|
||||
else
|
||||
{
|
||||
stack->ReleaseAll();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void NetworkTransaction::Printf(const char* fmt, ...)
|
||||
{
|
||||
if (CanWrite() && (sendBuffer != nullptr || OutputBuffer::Allocate(sendBuffer)))
|
||||
{
|
||||
va_list p;
|
||||
va_start(p, fmt);
|
||||
sendBuffer->vprintf(fmt, p);
|
||||
va_end(p);
|
||||
}
|
||||
}
|
||||
|
||||
void NetworkTransaction::SetFileToWrite(FileStore *file)
|
||||
{
|
||||
if (CanWrite())
|
||||
{
|
||||
fileBeingSent = file;
|
||||
}
|
||||
else if (file != nullptr)
|
||||
{
|
||||
file->Close();
|
||||
}
|
||||
}
|
||||
|
||||
// Send exactly one TCP window of data and return true when this transaction can be released
|
||||
bool NetworkTransaction::Send()
|
||||
{
|
||||
#if 1
|
||||
return true;
|
||||
#else
|
||||
// Free up this transaction if the connection is supposed to be closed
|
||||
if (closeRequested)
|
||||
{
|
||||
reprap.GetNetwork()->ConnectionClosed(cs, true); // This will release the transaction too
|
||||
return false;
|
||||
}
|
||||
|
||||
// Fill up the TCP window with some data chunks from our OutputBuffer instances
|
||||
size_t bytesBeingSent = 0, bytesLeftToSend = TCP_WND;
|
||||
while (sendBuffer != nullptr && bytesLeftToSend > 0)
|
||||
{
|
||||
size_t copyLength = min<size_t>(bytesLeftToSend, sendBuffer->BytesLeft());
|
||||
memcpy(sendingWindow + bytesBeingSent, sendBuffer->Read(copyLength), copyLength);
|
||||
bytesBeingSent += copyLength;
|
||||
bytesLeftToSend -= copyLength;
|
||||
|
||||
if (sendBuffer->BytesLeft() == 0)
|
||||
{
|
||||
sendBuffer = OutputBuffer::Release(sendBuffer);
|
||||
if (sendBuffer == nullptr)
|
||||
{
|
||||
sendBuffer = sendStack->Pop();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// We also intend to send a file, so check if we can fill up the TCP window
|
||||
if (sendBuffer == nullptr && bytesLeftToSend != 0 && fileBeingSent != nullptr)
|
||||
{
|
||||
// For HSMCI efficiency, read from the file in multiples of 4 bytes except at the end.
|
||||
// This ensures that the second and subsequent chunks can be DMA'd directly into sendingWindow.
|
||||
size_t bytesToRead = bytesLeftToSend & (~3);
|
||||
if (bytesToRead != 0)
|
||||
{
|
||||
int bytesRead = fileBeingSent->Read(sendingWindow + bytesBeingSent, bytesToRead);
|
||||
if (bytesRead > 0)
|
||||
{
|
||||
bytesBeingSent += bytesRead;
|
||||
}
|
||||
|
||||
if (bytesRead != (int)bytesToRead)
|
||||
{
|
||||
fileBeingSent->Close();
|
||||
fileBeingSent = nullptr;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
if (bytesBeingSent == 0)
|
||||
{
|
||||
// If we have no data to send, this connection can be closed next time
|
||||
if (!cs->persistConnection && nextWrite == nullptr)
|
||||
{
|
||||
Close();
|
||||
return false;
|
||||
}
|
||||
|
||||
// We want to send data from another transaction as well, so only free up this one
|
||||
cs->sendingTransaction = nextWrite;
|
||||
return true;
|
||||
}
|
||||
|
||||
// The TCP window has been filled up as much as possible, so send it now. There is no need to check
|
||||
// the available space in the SNDBUF queue, because we really write only one TCP window at once.
|
||||
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);
|
||||
tcp_abort(cs->pcb);
|
||||
return false;
|
||||
}
|
||||
|
||||
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);
|
||||
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);
|
||||
}
|
||||
|
||||
// Set LwIP callbacks for ACK and retransmission handling
|
||||
tcp_poll(cs->pcb, conn_poll, TCP_WRITE_TIMEOUT / TCP_SLOW_INTERVAL / TCP_MAX_SEND_RETRIES);
|
||||
tcp_sent(cs->pcb, conn_sent);
|
||||
|
||||
// Set all values for the send process
|
||||
sendingConnection = cs;
|
||||
sendingRetries = 0;
|
||||
sendingWindowSize = sentDataOutstanding = bytesBeingSent;
|
||||
return false;
|
||||
#endif
|
||||
}
|
||||
|
||||
// This is called by the Webserver to send output data to a client. If keepConnectionAlive is set to false,
|
||||
// the current connection will be terminated once everything has been sent.
|
||||
void NetworkTransaction::Commit(bool keepConnectionAlive)
|
||||
{
|
||||
#if 0
|
||||
// If the connection has been terminated (e.g. RST received while writing upload data), discard this transaction
|
||||
if (!IsConnected() || status == released)
|
||||
{
|
||||
Discard();
|
||||
return;
|
||||
}
|
||||
|
||||
// Free buffer holding the incoming data and prepare some values for the sending process
|
||||
FreePbuf();
|
||||
cs->persistConnection = keepConnectionAlive;
|
||||
if (sendBuffer == nullptr)
|
||||
{
|
||||
sendBuffer = sendStack->Pop();
|
||||
}
|
||||
status = sending;
|
||||
|
||||
// Unlink the item(s) from the list of ready transactions
|
||||
if (keepConnectionAlive)
|
||||
{
|
||||
// Our connection is still of interest, remove only this transaction from the list
|
||||
NetworkTransaction *previous = nullptr;
|
||||
for(NetworkTransaction *item = reprap.GetNetwork()->readyTransactions; item != nullptr; item = item->next)
|
||||
{
|
||||
if (item == this)
|
||||
{
|
||||
if (previous == nullptr)
|
||||
{
|
||||
reprap.GetNetwork()->readyTransactions = next;
|
||||
}
|
||||
else
|
||||
{
|
||||
previous->next = next;
|
||||
}
|
||||
break;
|
||||
}
|
||||
previous = item;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
// We will close this connection soon, stop receiving data from this PCB
|
||||
tcp_recv(cs->pcb, nullptr);
|
||||
|
||||
// Also remove all ready transactions pointing to our ConnectionState
|
||||
NetworkTransaction *previous = nullptr, *item = reprap.GetNetwork()->readyTransactions;
|
||||
while (item != nullptr)
|
||||
{
|
||||
if (item->cs == cs)
|
||||
{
|
||||
if (item == this)
|
||||
{
|
||||
// Only unlink this item
|
||||
if (previous == nullptr)
|
||||
{
|
||||
reprap.GetNetwork()->readyTransactions = next;
|
||||
}
|
||||
else
|
||||
{
|
||||
previous->next = next;
|
||||
}
|
||||
item = next;
|
||||
}
|
||||
else
|
||||
{
|
||||
// Remove all others
|
||||
item->Discard();
|
||||
item = (previous == nullptr) ? reprap.GetNetwork()->readyTransactions : previous->next;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
previous = item;
|
||||
item = item->next;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Enqueue this transaction, so it's sent in the right order
|
||||
NetworkTransaction *mySendingTransaction = cs->sendingTransaction;
|
||||
if (mySendingTransaction == nullptr)
|
||||
{
|
||||
cs->sendingTransaction = this;
|
||||
reprap.GetNetwork()->AppendTransaction(&reprap.GetNetwork()->writingTransactions, this);
|
||||
}
|
||||
else
|
||||
{
|
||||
while (mySendingTransaction->nextWrite != nullptr)
|
||||
{
|
||||
mySendingTransaction = mySendingTransaction->nextWrite;
|
||||
}
|
||||
mySendingTransaction->nextWrite = this;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
// Call this to perform some networking tasks while processing deferred requests,
|
||||
// and to move this transaction and all transactions that are associated with its
|
||||
// connection to the end of readyTransactions. There are three ways to do this:
|
||||
//
|
||||
// 1) DeferOnly: Do not modify any of the processed data and don't send an ACK.
|
||||
// This will ensure that zero-window packets are sent back to the client
|
||||
// 2) ResetData: Reset the read pointers and acknowledge that the data has been processed
|
||||
// 3) DiscardData: Free the processed data, acknowledge it and append this transaction as
|
||||
// an empty item again without payload (i.e. without pbufs)
|
||||
//
|
||||
void NetworkTransaction::Defer(DeferralMode mode)
|
||||
{
|
||||
#if 0
|
||||
if (mode == DeferralMode::ResetData)
|
||||
{
|
||||
// Reset the reading pointers and send an ACK
|
||||
inputPointer = 0;
|
||||
readingPb = pb;
|
||||
if (IsConnected() && pb != nullptr && !dataAcknowledged)
|
||||
{
|
||||
tcp_recved(cs->pcb, pb->tot_len);
|
||||
dataAcknowledged = true;
|
||||
}
|
||||
}
|
||||
else if (mode == DeferralMode::DiscardData)
|
||||
{
|
||||
// Discard the incoming data, because we don't need to process it any more
|
||||
FreePbuf();
|
||||
}
|
||||
|
||||
status = deferred;
|
||||
|
||||
// Unlink this transaction from the list of ready transactions and append it again
|
||||
Network *network = reprap.GetNetwork();
|
||||
NetworkTransaction *item, *previous = nullptr;
|
||||
for(item = network->readyTransactions; item != nullptr; item = item->next)
|
||||
{
|
||||
if (item == this)
|
||||
{
|
||||
if (previous == nullptr)
|
||||
{
|
||||
network->readyTransactions = next;
|
||||
}
|
||||
else
|
||||
{
|
||||
previous->next = next;
|
||||
}
|
||||
break;
|
||||
}
|
||||
previous = item;
|
||||
}
|
||||
network->AppendTransaction(&network->readyTransactions, this);
|
||||
|
||||
// Append all other transactions that are associated to this connection, so that the
|
||||
// Webserver gets a chance to deal with all connected clients even while multiple
|
||||
// deferred requests are present in the list.
|
||||
item = network->readyTransactions;
|
||||
previous = nullptr;
|
||||
while (item != this)
|
||||
{
|
||||
if (item->cs == cs)
|
||||
{
|
||||
NetworkTransaction *nextItem = item->next;
|
||||
if (previous == nullptr)
|
||||
{
|
||||
network->readyTransactions = item->next;
|
||||
network->AppendTransaction(&network->readyTransactions, item);
|
||||
}
|
||||
else
|
||||
{
|
||||
previous->next = item->next;
|
||||
network->AppendTransaction(&network->readyTransactions, item);
|
||||
}
|
||||
item = nextItem;
|
||||
}
|
||||
else
|
||||
{
|
||||
previous = item;
|
||||
item = item->next;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
// This method should be called if we don't want to send data to the client and if we
|
||||
// don't want to interfere with the connection state. May also be called from ISR!
|
||||
void NetworkTransaction::Discard()
|
||||
{
|
||||
#if 0
|
||||
// Can we do anything?
|
||||
if (status == released)
|
||||
{
|
||||
// No - don't free up released items multiple times
|
||||
return;
|
||||
}
|
||||
|
||||
// Free up some resources
|
||||
FreePbuf();
|
||||
|
||||
if (fileBeingSent != nullptr)
|
||||
{
|
||||
fileBeingSent->Close();
|
||||
fileBeingSent = nullptr;
|
||||
}
|
||||
|
||||
OutputBuffer::ReleaseAll(sendBuffer);
|
||||
sendStack->ReleaseAll();
|
||||
|
||||
// Unlink this transactions from the list of ready transactions and free it. It is then appended to the list of
|
||||
// free transactions because we don't want to risk reusing it when the ethernet ISR processes incoming data
|
||||
NetworkTransaction *previous = nullptr;
|
||||
for(NetworkTransaction *item = reprap.GetNetwork()->readyTransactions; item != nullptr; item = item->next)
|
||||
{
|
||||
if (item == this)
|
||||
{
|
||||
if (previous == nullptr)
|
||||
{
|
||||
reprap.GetNetwork()->readyTransactions = next;
|
||||
}
|
||||
else
|
||||
{
|
||||
previous->next = next;
|
||||
}
|
||||
break;
|
||||
}
|
||||
previous = item;
|
||||
}
|
||||
reprap.GetNetwork()->AppendTransaction(&reprap.GetNetwork()->freeTransactions, this);
|
||||
bool callDisconnectHandler = (cs != nullptr && status == disconnected);
|
||||
status = released;
|
||||
|
||||
// Call disconnect event if this transaction indicates a graceful disconnect and if the connection
|
||||
// still persists (may not be the case if a RST packet was received before)
|
||||
if (callDisconnectHandler)
|
||||
{
|
||||
if (reprap.Debug(moduleNetwork))
|
||||
{
|
||||
reprap.GetPlatform()->Message(HOST_MESSAGE, "Network: Discard() is handling a graceful disconnect\n");
|
||||
}
|
||||
reprap.GetNetwork()->ConnectionClosed(cs, false);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
uint32_t NetworkTransaction::GetRemoteIP() const
|
||||
{
|
||||
return (cs != nullptr) ? cs->GetRemoteIP() : 0;
|
||||
}
|
||||
|
||||
uint16_t NetworkTransaction::GetRemotePort() const
|
||||
{
|
||||
return (cs != nullptr) ? cs->GetRemotePort() : 0;
|
||||
}
|
||||
|
||||
uint16_t NetworkTransaction::GetLocalPort() const
|
||||
{
|
||||
return (cs != nullptr) ? cs->GetLocalPort() : 0;
|
||||
}
|
||||
|
||||
void NetworkTransaction::Close()
|
||||
{
|
||||
#if 0
|
||||
tcp_pcb *pcb = cs->pcb;
|
||||
tcp_recv(pcb, nullptr);
|
||||
closeRequested = true;
|
||||
#endif
|
||||
}
|
||||
|
||||
bool ConnectionState::IsConnected() const
|
||||
{
|
||||
//TODO
|
||||
return false;
|
||||
}
|
||||
|
||||
// End
|
||||
|
|
|
@ -16,21 +16,114 @@ Separated out from Platform.h by dc42 and extended by zpl
|
|||
|
||||
#include "MessageType.h"
|
||||
|
||||
// Return code definitions
|
||||
const uint32_t rcNumber = 0x0000FFFF;
|
||||
const uint32_t rcJson = 0x00010000;
|
||||
const uint32_t rcKeepOpen = 0x00020000;
|
||||
|
||||
const uint8_t MAC_ADDRESS[6] = { 0xBE, 0xEF, 0xDE, 0xAD, 0xFE, 0xED }; // Need some sort of default...
|
||||
const uint8_t IP_ADDRESS[4] = { 192, 168, 1, 10 }; // Need some sort of default...
|
||||
const uint8_t NET_MASK[4] = { 255, 255, 255, 0 };
|
||||
const uint8_t GATE_WAY[4] = { 192, 168, 1, 1 };
|
||||
const uint8_t MAC_ADDRESS[6] = { 0xBE, 0xEF, 0xDE, 0xAD, 0xFE, 0xED }; // Need some sort of default...
|
||||
const uint16_t DEFAULT_HTTP_PORT = 80;
|
||||
|
||||
class TransactionBuffer;
|
||||
class WifiFirmwareUploader;
|
||||
const uint16_t DEFAULT_HTTP_PORT = 80;
|
||||
const uint16_t FTP_PORT = 21;
|
||||
const uint16_t TELNET_PORT = 23;
|
||||
|
||||
class Platform;
|
||||
|
||||
struct tcp_pcb;
|
||||
struct pbuf;
|
||||
|
||||
class NetworkTransaction;
|
||||
|
||||
// ConnectionState structure that we use to track TCP connections. It is usually combined with NetworkTransactions.
|
||||
struct ConnectionState
|
||||
{
|
||||
// tcp_pcb *volatile pcb; // Connection PCB
|
||||
uint16_t localPort, remotePort; // Copy of the local and remote ports, because the PCB may be unavailable
|
||||
uint32_t remoteIPAddress; // Same for the remote IP address
|
||||
NetworkTransaction * volatile sendingTransaction; // NetworkTransaction that is currently sending via this connection
|
||||
ConnectionState * volatile next; // Next ConnectionState in this list
|
||||
bool persistConnection; // Do we expect this connection to stay alive?
|
||||
volatile bool isTerminated; // Will be true if the connection has gone down unexpectedly (TCP RST)
|
||||
|
||||
// void Init(tcp_pcb *p);
|
||||
uint16_t GetLocalPort() const { return localPort; }
|
||||
uint32_t GetRemoteIP() const { return remoteIPAddress; }
|
||||
uint16_t GetRemotePort() const { return remotePort; }
|
||||
bool IsConnected() const; // { return pcb != nullptr; }
|
||||
bool IsTerminated() const { return isTerminated; }
|
||||
void Terminate();
|
||||
};
|
||||
|
||||
// Assign a status to each NetworkTransaction
|
||||
enum TransactionStatus
|
||||
{
|
||||
released,
|
||||
connected,
|
||||
receiving,
|
||||
sending,
|
||||
disconnected,
|
||||
deferred,
|
||||
acquired
|
||||
};
|
||||
|
||||
// How is a deferred request supposed to be handled?
|
||||
enum class DeferralMode
|
||||
{
|
||||
DeferOnly, // don't change anything, because we want to read more of it next time
|
||||
ResetData, // keep the data and reset all reading pointers allowing us to process it again
|
||||
DiscardData // discard all incoming data and re-enqueue the empty transaction
|
||||
};
|
||||
|
||||
// Start with a class to hold input and output from the network that needs to be responded to.
|
||||
// This includes changes in the connection state, e.g. connects and disconnects.
|
||||
class NetworkTransaction
|
||||
{
|
||||
public:
|
||||
friend class Network;
|
||||
|
||||
NetworkTransaction(NetworkTransaction* n);
|
||||
void Set(pbuf *p, ConnectionState* c, TransactionStatus s);
|
||||
TransactionStatus GetStatus() const { return status; }
|
||||
bool IsConnected() const;
|
||||
|
||||
bool HasMoreDataToRead() const; // { return readingPb != nullptr; }
|
||||
bool Read(char& b);
|
||||
bool ReadBuffer(const char *&buffer, size_t &len);
|
||||
void Write(char b);
|
||||
void Write(const char* s);
|
||||
void Write(StringRef ref);
|
||||
void Write(const char* s, size_t len);
|
||||
void Write(OutputBuffer *buffer);
|
||||
void Write(OutputStack *stack);
|
||||
void Printf(const char *fmt, ...);
|
||||
void SetFileToWrite(FileStore *file);
|
||||
|
||||
ConnectionState *GetConnection() const { return cs; }
|
||||
uint16_t GetLocalPort() const;
|
||||
uint32_t GetRemoteIP() const;
|
||||
uint16_t GetRemotePort() const;
|
||||
|
||||
void Commit(bool keepConnectionAlive);
|
||||
void Defer(DeferralMode mode);
|
||||
void Discard();
|
||||
|
||||
private:
|
||||
bool CanWrite() const;
|
||||
bool Send();
|
||||
void Close();
|
||||
|
||||
ConnectionState* cs;
|
||||
NetworkTransaction* volatile next; // next NetworkTransaction in the list we are in
|
||||
NetworkTransaction* volatile nextWrite; // next NetworkTransaction queued to write to assigned connection
|
||||
// pbuf *pb, *readingPb; // received packet queue and a pointer to the pbuf being read from
|
||||
// size_t inputPointer; // amount of data already taken from the first packet buffer
|
||||
|
||||
OutputBuffer *sendBuffer;
|
||||
OutputStack *sendStack;
|
||||
FileStore * volatile fileBeingSent;
|
||||
|
||||
volatile TransactionStatus status;
|
||||
volatile bool closeRequested, dataAcknowledged;
|
||||
};
|
||||
|
||||
// The main network class that drives the network.
|
||||
class Network
|
||||
{
|
||||
|
@ -60,7 +153,9 @@ public:
|
|||
void Start();
|
||||
void Stop();
|
||||
|
||||
bool InLwip() const { return false; }
|
||||
bool Lock();
|
||||
void Unlock();
|
||||
bool InLwip() const;
|
||||
|
||||
void Enable();
|
||||
void Disable();
|
||||
|
@ -71,6 +166,22 @@ public:
|
|||
|
||||
void SetHostname(const char *name);
|
||||
|
||||
// Interfaces for the Webserver
|
||||
|
||||
NetworkTransaction *GetTransaction(const ConnectionState *cs = nullptr);
|
||||
|
||||
void OpenDataPort(uint16_t port);
|
||||
uint16_t GetDataPort() const;
|
||||
void CloseDataPort();
|
||||
|
||||
void SaveDataConnection();
|
||||
void SaveFTPConnection();
|
||||
void SaveTelnetConnection();
|
||||
|
||||
bool AcquireFTPTransaction();
|
||||
bool AcquireDataTransaction();
|
||||
bool AcquireTelnetTransaction();
|
||||
|
||||
private:
|
||||
void SetupSpi();
|
||||
|
||||
|
@ -96,4 +207,14 @@ private:
|
|||
bool activated;
|
||||
};
|
||||
|
||||
inline bool NetworkTransaction::IsConnected() const
|
||||
{
|
||||
return (cs != nullptr && cs->IsConnected());
|
||||
}
|
||||
|
||||
inline bool NetworkTransaction::CanWrite() const
|
||||
{
|
||||
return (IsConnected() && status != released);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
File diff suppressed because it is too large
Load diff
|
@ -30,8 +30,40 @@ Licence: GPL
|
|||
#ifndef WEBSERVER_H
|
||||
#define WEBSERVER_H
|
||||
|
||||
#include <cstdint>
|
||||
#include <cstddef>
|
||||
/* Generic values */
|
||||
|
||||
const size_t gcodeBufferLength = 512; // size of our gcode ring buffer, preferably a power of 2
|
||||
const unsigned int TCP_MSS = 1460;
|
||||
|
||||
class ConnectionState;
|
||||
class NetworkTransaction;
|
||||
|
||||
/* HTTP */
|
||||
|
||||
#define KO_START "rr_"
|
||||
#define KO_FIRST 3
|
||||
|
||||
const uint16_t webMessageLength = TCP_MSS; // maximum length of the web message we accept after decoding
|
||||
const size_t minHttpResponseSize = 768; // minimum number of bytes required for an HTTP response
|
||||
|
||||
const size_t maxCommandWords = 4; // max number of space-separated words in the command
|
||||
const size_t maxQualKeys = 5; // max number of key/value pairs in the qualifier
|
||||
const size_t maxHeaders = 16; // max number of key/value pairs in the headers
|
||||
|
||||
const size_t maxHttpSessions = 8; // maximum number of simultaneous HTTP sessions
|
||||
const uint32_t httpSessionTimeout = 8000; // HTTP session timeout in milliseconds
|
||||
|
||||
/* FTP */
|
||||
|
||||
const uint16_t ftpMessageLength = 128; // maximum line length for incoming FTP commands
|
||||
const uint32_t ftpPasvPortTimeout = 10000; // maximum time to wait for an FTP data connection in milliseconds
|
||||
|
||||
/* Telnet */
|
||||
|
||||
const uint32_t telnetSetupDuration = 4000; // ignore the first Telnet request within this duration (in ms)
|
||||
|
||||
|
||||
class Webserver;
|
||||
|
||||
// List of protocols that can execute G-Codes
|
||||
enum class WebSource
|
||||
|
@ -40,20 +72,56 @@ enum class WebSource
|
|||
Telnet
|
||||
};
|
||||
|
||||
const uint16_t gcodeBufferLength = 512; // size of our gcode ring buffer, preferably a power of 2
|
||||
const uint16_t webMessageLength = 2000; // maximum length of the web message we accept after decoding
|
||||
const size_t maxQualKeys = 5; // max number of key/value pairs in the qualifier
|
||||
const size_t maxHttpSessions = 8; // maximum number of simultaneous HTTP sessions
|
||||
const uint32_t httpSessionTimeout = 20000; // HTTP session timeout in milliseconds
|
||||
// This is the abstract class for all supported protocols
|
||||
// Any inherited class should implement a state machine to increase performance and reduce memory usage.
|
||||
class ProtocolInterpreter
|
||||
{
|
||||
public:
|
||||
|
||||
class Platform;
|
||||
class Network;
|
||||
ProtocolInterpreter(Platform *p, Webserver *ws, Network *n);
|
||||
virtual ~ProtocolInterpreter() { } // to keep Eclipse happy
|
||||
virtual void Diagnostics(MessageType mtype) = 0;
|
||||
virtual void Spin();
|
||||
|
||||
virtual void ConnectionEstablished();
|
||||
virtual void ConnectionLost(const ConnectionState *cs) { }
|
||||
virtual bool CanParseData();
|
||||
virtual bool CharFromClient(const char c) = 0;
|
||||
virtual void NoMoreDataAvailable();
|
||||
|
||||
virtual bool DoingFastUpload() const;
|
||||
virtual void DoFastUpload();
|
||||
void CancelUpload(); // may be called from ISR!
|
||||
|
||||
protected:
|
||||
|
||||
Platform *platform;
|
||||
Webserver *webserver;
|
||||
Network *network;
|
||||
|
||||
// Information for file uploading
|
||||
enum UploadState
|
||||
{
|
||||
notUploading, // no upload in progress
|
||||
uploadOK, // upload in progress, no error so far
|
||||
uploadError // upload in progress but had error
|
||||
};
|
||||
|
||||
UploadState uploadState;
|
||||
FileData fileBeingUploaded;
|
||||
char filenameBeingUploaded[FILENAME_LENGTH];
|
||||
|
||||
bool StartUpload(FileStore *file, const char *fileName);
|
||||
bool IsUploading() const;
|
||||
bool FinishUpload(uint32_t fileLength);
|
||||
};
|
||||
|
||||
class Webserver
|
||||
{
|
||||
public:
|
||||
public:
|
||||
|
||||
friend class Platform;
|
||||
friend class ProtocolInterpreter;
|
||||
|
||||
Webserver(Platform* p, Network *n);
|
||||
void Init();
|
||||
|
@ -65,12 +133,252 @@ public:
|
|||
char ReadGCode(const WebSource source);
|
||||
void HandleGCodeReply(const WebSource source, OutputBuffer *reply);
|
||||
void HandleGCodeReply(const WebSource source, const char *reply);
|
||||
uint32_t GetReplySeq() const { return seq; }
|
||||
// Returns the available G-Code buffer space of the HTTP interpreter (may be dropped in a future version)
|
||||
uint16_t GetGCodeBufferSpace(const WebSource source) const { return 0; }
|
||||
uint32_t GetReplySeq() const;
|
||||
|
||||
private:
|
||||
uint32_t seq;
|
||||
// Returns the available G-Code buffer space of the HTTP interpreter (may be dropped in a future version)
|
||||
uint16_t GetGCodeBufferSpace(const WebSource source) const;
|
||||
|
||||
void ConnectionLost(const ConnectionState *cs);
|
||||
void ConnectionError();
|
||||
|
||||
protected:
|
||||
|
||||
class HttpInterpreter : public ProtocolInterpreter
|
||||
{
|
||||
public:
|
||||
|
||||
HttpInterpreter(Platform *p, Webserver *ws, Network *n);
|
||||
void Spin();
|
||||
void Diagnostics(MessageType mtype) override;
|
||||
void ConnectionLost(const ConnectionState *cs);
|
||||
bool CanParseData() override;
|
||||
bool CharFromClient(const char c) override;
|
||||
void NoMoreDataAvailable() override;
|
||||
void ResetState();
|
||||
void ResetSessions();
|
||||
|
||||
bool DoingFastUpload() const override;
|
||||
void DoFastUpload();
|
||||
|
||||
bool GCodeAvailable() const;
|
||||
char ReadGCode();
|
||||
void HandleGCodeReply(OutputBuffer *reply);
|
||||
void HandleGCodeReply(const char *reply);
|
||||
uint16_t GetGCodeBufferSpace() const;
|
||||
uint32_t GetReplySeq() const;
|
||||
|
||||
private:
|
||||
|
||||
// HTTP server state enumeration. The order is important, in particular xxxEsc1 must follow xxx, and xxxEsc2 must follow xxxEsc1.
|
||||
// We assume that qualifier keys do not contain escapes, because none of ours needs to be encoded. If we are sent escapes in the key,
|
||||
// it won't do any harm, but the key won't be recognised even if it would be valid were it decoded.
|
||||
enum HttpState
|
||||
{
|
||||
doingCommandWord, // receiving a word in the first line of the HTTP request
|
||||
doingFilename, // receiving the filename (second word in the command line)
|
||||
doingFilenameEsc1, // received '%' in the filename (e.g. we are being asked for a filename with spaces in it)
|
||||
doingFilenameEsc2, // received '%' and one hex digit in the filename
|
||||
doingQualifierKey, // receiving a key name in the HTTP request
|
||||
doingQualifierValue, // receiving a key value in the HTTP request
|
||||
doingQualifierValueEsc1, // received '%' in the qualifier
|
||||
doingQualifierValueEsc2, // received '%' and one hex digit in the qualifier
|
||||
doingHeaderKey, // receiving a header key
|
||||
expectingHeaderValue, // expecting a header value
|
||||
doingHeaderValue, // receiving a header value
|
||||
doingHeaderContinuation // received a newline after a header value
|
||||
};
|
||||
HttpState state;
|
||||
|
||||
struct KeyValueIndices
|
||||
{
|
||||
const char* key;
|
||||
const char* value;
|
||||
};
|
||||
|
||||
void SendFile(const char* nameOfFileToSend, bool isWebFile);
|
||||
void SendGCodeReply();
|
||||
void SendJsonResponse(const char* command);
|
||||
void GetJsonResponse(const char* request, OutputBuffer *&response, const char* key, const char* value, size_t valueLength, bool& keepOpen);
|
||||
bool ProcessMessage();
|
||||
bool RejectMessage(const char* s, unsigned int code = 500);
|
||||
|
||||
// Buffers for processing HTTP input
|
||||
char clientMessage[webMessageLength + 3]; // holds the command, qualifier, and headers
|
||||
size_t clientPointer; // current index into clientMessage
|
||||
char decodeChar;
|
||||
|
||||
const char* commandWords[maxCommandWords];
|
||||
KeyValueIndices qualifiers[maxQualKeys + 1]; // offsets into clientQualifier of the key/value pairs, the +1 is needed so that values can contain nulls
|
||||
KeyValueIndices headers[maxHeaders]; // offsets into clientHeader of the key/value pairs
|
||||
size_t numCommandWords;
|
||||
size_t numQualKeys; // number of qualifier keys we have found, <= maxQualKeys
|
||||
size_t numHeaderKeys; // number of keys we have found, <= maxHeaders
|
||||
|
||||
// HTTP sessions
|
||||
struct HttpSession
|
||||
{
|
||||
uint32_t ip;
|
||||
uint32_t lastQueryTime;
|
||||
bool isPostUploading;
|
||||
uint16_t postPort;
|
||||
};
|
||||
|
||||
HttpSession sessions[maxHttpSessions];
|
||||
uint8_t numSessions;
|
||||
uint8_t clientsServed;
|
||||
|
||||
bool Authenticate();
|
||||
bool IsAuthenticated() const;
|
||||
void UpdateAuthentication();
|
||||
bool RemoveAuthentication();
|
||||
|
||||
// Deal with incoming G-Codes
|
||||
|
||||
char gcodeBuffer[gcodeBufferLength];
|
||||
uint16_t gcodeReadIndex, gcodeWriteIndex; // head and tail indices into gcodeBuffer
|
||||
|
||||
void LoadGcodeBuffer(const char* gc);
|
||||
void ProcessGcode(const char* gc);
|
||||
void StoreGcodeData(const char* data, uint16_t len);
|
||||
|
||||
// Responses from GCodes class
|
||||
|
||||
uint32_t seq; // Sequence number for G-Code replies
|
||||
OutputStack *gcodeReply;
|
||||
|
||||
// File uploads
|
||||
uint32_t postFileLength, uploadedBytes; // How many POST bytes do we expect and how many have already been written?
|
||||
time_t fileLastModified;
|
||||
|
||||
// Deferred requests (rr_fileinfo)
|
||||
ConnectionState * volatile deferredRequestConnection; // Which connection expects a response for a deferred request?
|
||||
char filenameBeingProcessed[FILENAME_LENGTH]; // The filename being processed (for rr_fileinfo)
|
||||
|
||||
void ProcessDeferredRequest();
|
||||
};
|
||||
HttpInterpreter *httpInterpreter;
|
||||
|
||||
class FtpInterpreter : public ProtocolInterpreter
|
||||
{
|
||||
public:
|
||||
|
||||
FtpInterpreter(Platform *p, Webserver *ws, Network *n);
|
||||
void Diagnostics(MessageType mtype) override;
|
||||
|
||||
void ConnectionEstablished() override;
|
||||
void ConnectionLost(const ConnectionState *cs) override;
|
||||
bool CharFromClient(const char c) override;
|
||||
void ResetState();
|
||||
|
||||
bool DoingFastUpload() const override;
|
||||
|
||||
private:
|
||||
|
||||
enum FtpState
|
||||
{
|
||||
idle, // no client connected
|
||||
authenticating, // not logged in
|
||||
authenticated, // logged in
|
||||
waitingForPasvPort, // waiting for connection to be established on PASV port
|
||||
pasvPortConnected, // client connected to PASV port, ready to send data
|
||||
doingPasvIO // client is connected and data is being transferred
|
||||
};
|
||||
FtpState state;
|
||||
uint8_t connectedClients;
|
||||
|
||||
char clientMessage[ftpMessageLength];
|
||||
size_t clientPointer;
|
||||
|
||||
char filename[FILENAME_LENGTH];
|
||||
char currentDir[FILENAME_LENGTH];
|
||||
|
||||
uint32_t portOpenTime;
|
||||
|
||||
void ProcessLine();
|
||||
void SendReply(int code, const char *message, bool keepConnection = true);
|
||||
void SendFeatures();
|
||||
|
||||
void ReadFilename(uint16_t start);
|
||||
void ChangeDirectory(const char *newDirectory);
|
||||
};
|
||||
FtpInterpreter *ftpInterpreter;
|
||||
|
||||
class TelnetInterpreter : public ProtocolInterpreter
|
||||
{
|
||||
public:
|
||||
|
||||
TelnetInterpreter(Platform *p, Webserver *ws, Network *n);
|
||||
void Diagnostics(MessageType mtype) override;
|
||||
|
||||
void ConnectionEstablished() override;
|
||||
void ConnectionLost(const ConnectionState *cs) override;
|
||||
bool CanParseData() override;
|
||||
bool CharFromClient(const char c) override;
|
||||
void ResetState();
|
||||
|
||||
bool GCodeAvailable() const;
|
||||
char ReadGCode();
|
||||
void HandleGCodeReply(OutputBuffer *reply);
|
||||
void HandleGCodeReply(const char *reply);
|
||||
uint16_t GetGCodeBufferSpace() const;
|
||||
|
||||
void SendGCodeReply();
|
||||
|
||||
private:
|
||||
|
||||
enum TelnetState
|
||||
{
|
||||
idle, // not connected
|
||||
justConnected, // not logged in, but the client has just connected
|
||||
authenticating, // not logged in
|
||||
authenticated // logged in
|
||||
};
|
||||
TelnetState state;
|
||||
uint8_t connectedClients;
|
||||
uint32_t connectTime;
|
||||
|
||||
bool processNextLine;
|
||||
char clientMessage[GCODE_LENGTH];
|
||||
size_t clientPointer;
|
||||
|
||||
bool ProcessLine();
|
||||
|
||||
// Deal with incoming G-Codes
|
||||
|
||||
char gcodeBuffer[gcodeBufferLength];
|
||||
uint16_t gcodeReadIndex, gcodeWriteIndex; // head and tail indices into gcodeBuffer
|
||||
|
||||
void ProcessGcode(const char* gc);
|
||||
void StoreGcodeData(const char* data, uint16_t len);
|
||||
|
||||
// Converted response from GCodes class (NL -> CRNL)
|
||||
|
||||
OutputBuffer * volatile gcodeReply;
|
||||
};
|
||||
TelnetInterpreter *telnetInterpreter;
|
||||
|
||||
private:
|
||||
|
||||
Platform* platform;
|
||||
Network* network;
|
||||
bool webserverActive;
|
||||
NetworkTransaction *currentTransaction;
|
||||
ConnectionState * volatile readingConnection;
|
||||
|
||||
float longWait;
|
||||
};
|
||||
|
||||
inline bool ProtocolInterpreter::CanParseData() { return true; }
|
||||
inline bool ProtocolInterpreter::DoingFastUpload() const { return false; }
|
||||
inline bool ProtocolInterpreter::IsUploading() const { return uploadState != notUploading; }
|
||||
|
||||
inline uint32_t Webserver::GetReplySeq() const { return httpInterpreter->GetReplySeq(); }
|
||||
|
||||
inline uint16_t Webserver::HttpInterpreter::GetGCodeBufferSpace() const { return (gcodeReadIndex - gcodeWriteIndex - 1u) % gcodeBufferLength; }
|
||||
inline bool Webserver::HttpInterpreter::GCodeAvailable() const { return gcodeReadIndex != gcodeWriteIndex; }
|
||||
inline uint32_t Webserver::HttpInterpreter::GetReplySeq() const { return seq; }
|
||||
|
||||
inline uint16_t Webserver::TelnetInterpreter::GetGCodeBufferSpace() const { return (gcodeReadIndex - gcodeWriteIndex - 1u) % gcodeBufferLength; }
|
||||
inline bool Webserver::TelnetInterpreter::GCodeAvailable() const { return gcodeReadIndex != gcodeWriteIndex; }
|
||||
|
||||
#endif
|
||||
|
|
|
@ -21,9 +21,7 @@ enum class GCodeState : uint8_t
|
|||
normal, // not doing anything and ready to process a new GCode
|
||||
waitingForMoveToComplete, // doing a homing move, so we must wait for it to finish before processing another GCode
|
||||
homing,
|
||||
setBed1,
|
||||
setBed2,
|
||||
setBed3,
|
||||
setBed,
|
||||
|
||||
// These next 3 must be contiguous
|
||||
toolChange1,
|
||||
|
|
|
@ -101,6 +101,7 @@ void GCodes::Init()
|
|||
|
||||
retractLength = retractExtra = retractHop = 0.0;
|
||||
retractSpeed = unRetractSpeed = 600.0;
|
||||
isRetracted = false;
|
||||
}
|
||||
|
||||
// This is called from Init and when doing an emergency stop
|
||||
|
@ -233,25 +234,16 @@ void GCodes::Spin()
|
|||
}
|
||||
break;
|
||||
|
||||
case GCodeState::setBed1:
|
||||
reprap.GetMove()->SetIdentityTransform();
|
||||
probeCount = 0;
|
||||
gb.SetState(GCodeState::setBed2);
|
||||
// no break
|
||||
|
||||
case GCodeState::setBed2:
|
||||
{
|
||||
int numProbePoints = reprap.GetMove()->NumberOfXYProbePoints();
|
||||
case GCodeState::setBed:
|
||||
if (DoSingleZProbeAtPoint(gb, probeCount, 0.0))
|
||||
{
|
||||
probeCount++;
|
||||
if (probeCount >= numProbePoints)
|
||||
if (probeCount >= reprap.GetMove()->NumberOfXYProbePoints())
|
||||
{
|
||||
reprap.GetMove()->FinishedBedProbing(0, reply);
|
||||
gb.SetState(GCodeState::normal);
|
||||
}
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
case GCodeState::toolChange1: // Release the old tool (if any)
|
||||
|
@ -1078,12 +1070,19 @@ unsigned int GCodes::LoadMoveBufferFromGCode(GCodeBuffer& gb, int moveType)
|
|||
{
|
||||
moveArg += moveBuffer.coords[axis];
|
||||
}
|
||||
else if (currentTool != nullptr && moveType == 0)
|
||||
else if (moveType == 0)
|
||||
{
|
||||
if (axis == Z_AXIS && isRetracted)
|
||||
{
|
||||
moveArg += retractHop; // handle firmware retraction on layer change
|
||||
}
|
||||
if (currentTool != nullptr)
|
||||
{
|
||||
moveArg -= currentTool->GetOffset()[axis]; // adjust requested position to compensate for tool offset
|
||||
}
|
||||
}
|
||||
|
||||
if (axis < Z_AXIS && moveType == 0)
|
||||
if (axis != Z_AXIS && moveType == 0)
|
||||
{
|
||||
const HeightMap& heightMap = reprap.GetMove()->AccessBedProbeGrid();
|
||||
if (heightMap.UsingHeightMap())
|
||||
|
@ -1352,6 +1351,7 @@ bool GCodes::DoCannedCycleMove(GCodeBuffer& gb, EndstopChecks ce)
|
|||
{
|
||||
return true; // stack overflow
|
||||
}
|
||||
gb.MachineState().state = gb.MachineState().previous->state; // stay in the same state
|
||||
|
||||
for (size_t drive = 0; drive < DRIVES; drive++)
|
||||
{
|
||||
|
@ -1569,7 +1569,7 @@ bool GCodes::DoHome(GCodeBuffer& gb, StringRef& reply, bool& error)
|
|||
// probes the bed height, and records the Z coordinate probed. If you want to program any general
|
||||
// internal canned cycle, this shows how to do it.
|
||||
// On entry, probePointIndex specifies which of the points this is.
|
||||
bool GCodes::DoSingleZProbeAtPoint(GCodeBuffer& gb, int probePointIndex, float heightAdjust)
|
||||
bool GCodes::DoSingleZProbeAtPoint(GCodeBuffer& gb, size_t probePointIndex, float heightAdjust)
|
||||
{
|
||||
reprap.GetMove()->SetIdentityTransform(); // It doesn't matter if these are called repeatedly
|
||||
|
||||
|
@ -3001,7 +3001,7 @@ void GCodes::StartToolChange(GCodeBuffer& gb, bool inM109)
|
|||
// Retract or un-retract filament, returning true if movement has been queued, false if this needs to be called again
|
||||
bool GCodes::RetractFilament(GCodeBuffer& gb, bool retract)
|
||||
{
|
||||
if (retractLength != 0.0 || retractHop != 0.0 || (!retract && retractExtra != 0.0))
|
||||
if (retract != isRetracted && (retractLength != 0.0 || retractHop != 0.0 || (!retract && retractExtra != 0.0)))
|
||||
{
|
||||
const Tool *tool = reprap.GetCurrentTool();
|
||||
if (tool != nullptr)
|
||||
|
@ -3039,6 +3039,7 @@ bool GCodes::RetractFilament(GCodeBuffer& gb, bool retract)
|
|||
segmentsLeft = 1;
|
||||
}
|
||||
}
|
||||
isRetracted = retract;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -166,7 +166,7 @@ private:
|
|||
bool DoDwell(GCodeBuffer& gb); // Wait for a bit
|
||||
bool DoDwellTime(float dwell); // Really wait for a bit
|
||||
bool DoHome(GCodeBuffer& gb, StringRef& reply, bool& error); // Home some axes
|
||||
bool DoSingleZProbeAtPoint(GCodeBuffer& gb, int probePointIndex, float heightAdjust); // Probe at a given point
|
||||
bool DoSingleZProbeAtPoint(GCodeBuffer& gb, size_t probePointIndex, float heightAdjust); // Probe at a given point
|
||||
bool DoSingleZProbe(GCodeBuffer& gb, StringRef& reply, bool reportOnly, float heightAdjust); // Probe where we are
|
||||
int DoZProbe(GCodeBuffer& gb, float distance); // Do a Z probe cycle up to the maximum specified distance
|
||||
bool SetSingleZProbeAtAPosition(GCodeBuffer& gb, StringRef& reply); // Probes at a given position - see the comment at the head of the function itself
|
||||
|
@ -262,7 +262,7 @@ private:
|
|||
const char* eofString; // What's at the end of an HTML file?
|
||||
uint8_t eofStringCounter; // Check the...
|
||||
uint8_t eofStringLength; // ... EoF string as we read.
|
||||
int probeCount; // Counts multiple probe points
|
||||
size_t probeCount; // Counts multiple probe points
|
||||
int8_t cannedCycleMoveCount; // Counts through internal (i.e. not macro) canned cycle moves
|
||||
bool cannedCycleMoveQueued; // True if a canned cycle move has been set
|
||||
float longWait; // Timer for things that happen occasionally (seconds)
|
||||
|
@ -287,6 +287,7 @@ private:
|
|||
float retractSpeed; // retract speed in mm/min
|
||||
float unRetractSpeed; // un=retract speed in mm/min
|
||||
float retractHop; // Z hop when retracting
|
||||
bool isRetracted; // true if filament has been firmware-retracted
|
||||
|
||||
// Triggers
|
||||
Trigger triggers[MaxTriggers]; // Trigger conditions
|
||||
|
|
|
@ -220,7 +220,9 @@ bool GCodes::HandleGcode(GCodeBuffer& gb, StringRef& reply)
|
|||
// If we get here then we are not on a delta printer and there is no bed.g file
|
||||
if (GetAxisIsHomed(X_AXIS) && GetAxisIsHomed(Y_AXIS))
|
||||
{
|
||||
gb.SetState(GCodeState::setBed1); // no bed.g file, so use the coordinates specified by M557
|
||||
probeCount = 0;
|
||||
reprap.GetMove()->SetIdentityTransform();
|
||||
gb.SetState(GCodeState::setBed); // no bed.g file, so use the coordinates specified by M557
|
||||
}
|
||||
else
|
||||
{
|
||||
|
@ -1958,14 +1960,14 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, StringRef& reply)
|
|||
|
||||
case 376: // Set taper height
|
||||
{
|
||||
HeightMap& heightMap = reprap.GetMove()->AccessBedProbeGrid();
|
||||
Move *move = reprap.GetMove();
|
||||
if (gb.Seen('H'))
|
||||
{
|
||||
heightMap.SetTaperHeight(gb.GetFValue());
|
||||
move->SetTaperHeight(gb.GetFValue());
|
||||
}
|
||||
else if (heightMap.GetTaperHeight() > 0.0)
|
||||
else if (move->GetTaperHeight() > 0.0)
|
||||
{
|
||||
reply.printf("Bed compensation taper height is %.1fmm", heightMap.GetTaperHeight());
|
||||
reply.printf("Bed compensation taper height is %.1fmm", move->GetTaperHeight());
|
||||
}
|
||||
else
|
||||
{
|
||||
|
|
|
@ -109,7 +109,7 @@ void GridDefinition::PrintError(StringRef& r) const
|
|||
// Increase the version number in the following string whenever we change the format of the height map file.
|
||||
const char *HeightMap::HeightMapComment = "RepRapFirmware height map file v1";
|
||||
|
||||
HeightMap::HeightMap(float *heightStorage) : gridHeights(heightStorage), useMap(false), useTaper(false) { }
|
||||
HeightMap::HeightMap(float *heightStorage) : gridHeights(heightStorage), useMap(false) { }
|
||||
|
||||
void HeightMap::SetGrid(const GridDefinition& gd)
|
||||
{
|
||||
|
@ -316,46 +316,6 @@ void HeightMap::UseHeightMap(bool b)
|
|||
useMap = b && def.IsValid();
|
||||
}
|
||||
|
||||
void HeightMap::SetTaperHeight(float h)
|
||||
{
|
||||
useTaper = (h > 1.0);
|
||||
if (useTaper)
|
||||
{
|
||||
taperHeight = h;
|
||||
recipTaperHeight = 1.0/h;
|
||||
}
|
||||
}
|
||||
|
||||
// Compute the height error at the specified point i.e. value that needs to be added to the Z coordinate
|
||||
float HeightMap::ComputeHeightError(float x, float y, float z) const
|
||||
{
|
||||
if (!useMap || (useTaper && z >= taperHeight))
|
||||
{
|
||||
return 0.0;
|
||||
}
|
||||
|
||||
const float rawError = GetInterpolatedHeightError(x, y);
|
||||
return (useTaper) ? (taperHeight - z) * recipTaperHeight * rawError : rawError;
|
||||
}
|
||||
|
||||
// Compute the inverse height error at the specified point i.e. value that needs to be subtracted form the Z coordinate
|
||||
float HeightMap::ComputeInverseHeightError(float x, float y, float z) const
|
||||
{
|
||||
if (!useMap)
|
||||
{
|
||||
return 0.0;
|
||||
}
|
||||
|
||||
const float rawError = GetInterpolatedHeightError(x, y);
|
||||
if (!useTaper || rawError > taperHeight) // need check on rawError to avoid possible divide by zero
|
||||
{
|
||||
return rawError;
|
||||
}
|
||||
|
||||
const float zreq = (z - rawError)/(1.0 - (rawError * recipTaperHeight));
|
||||
return (zreq >= taperHeight) ? 0.0 : z - zreq;
|
||||
}
|
||||
|
||||
// Compute the height error at the specified point
|
||||
float HeightMap::GetInterpolatedHeightError(float x, float y) const
|
||||
{
|
||||
|
|
|
@ -68,8 +68,7 @@ public:
|
|||
const GridDefinition& GetGrid() const { return def; }
|
||||
void SetGrid(const GridDefinition& gd);
|
||||
|
||||
float ComputeHeightError(float x, float y, float z) const; // Compute the height error at the specified point
|
||||
float ComputeInverseHeightError(float x, float y, float z) const; // Compute the inverse height error at the specified point
|
||||
float GetInterpolatedHeightError(float x, float y) const; // Compute the interpolated height error at the specified point
|
||||
void ClearGridHeights(); // Clear all grid height corrections
|
||||
void SetGridHeight(size_t xIndex, size_t yIndex, float height); // Set the height of a grid point
|
||||
|
||||
|
@ -82,8 +81,6 @@ public:
|
|||
|
||||
void UseHeightMap(bool b);
|
||||
bool UsingHeightMap() const { return useMap; }
|
||||
float GetTaperHeight() const { return (useTaper) ? taperHeight : 0.0; }
|
||||
void SetTaperHeight(float h);
|
||||
|
||||
unsigned int GetStatistics(float& mean, float& deviation) const; // Return number of points probed, mean and RMS deviation
|
||||
|
||||
|
@ -93,17 +90,11 @@ private:
|
|||
GridDefinition def;
|
||||
float *gridHeights; // The map of grid heights, must have at least MaxGridProbePoints entries
|
||||
uint32_t gridHeightSet[MaxGridProbePoints/32]; // Bitmap of which heights are set
|
||||
float taperHeight; // Height over which we taper
|
||||
float recipTaperHeight; // Reciprocal of the taper height
|
||||
bool useMap; // True to do bed compensation
|
||||
bool useTaper; // True to taper off the compensation
|
||||
|
||||
uint32_t GetMapIndex(uint32_t xIndex, uint32_t yIndex) const { return (yIndex * def.NumXpoints()) + xIndex; }
|
||||
bool IsHeightSet(uint32_t index) const { return (gridHeightSet[index/32] & (1 << (index & 31))) != 0; }
|
||||
|
||||
float GetInterpolatedHeightError(float x, float y) const // Compute the interpolated height error at the specified point
|
||||
pre(useMap);
|
||||
|
||||
float GetHeightError(uint32_t xIndex, uint32_t yIndex) const;
|
||||
float InterpolateX(uint32_t xIndex, uint32_t yIndex, float xFrac) const;
|
||||
float InterpolateY(uint32_t xIndex, uint32_t yIndex, float yFrac) const;
|
||||
|
|
|
@ -88,6 +88,7 @@ void Move::Init()
|
|||
|
||||
xRectangle = 1.0/(0.8 * reprap.GetPlatform()->AxisMaximum(X_AXIS));
|
||||
yRectangle = xRectangle;
|
||||
useTaper = false;
|
||||
|
||||
longWait = reprap.GetPlatform()->Time();
|
||||
idleTimeout = DEFAULT_IDLE_TIMEOUT;
|
||||
|
@ -641,6 +642,8 @@ void Move::InverseTransform(float xyzPoint[MAX_AXES], uint32_t xAxes) const
|
|||
// Do the bed transform AFTER the axis transform
|
||||
void Move::BedTransform(float xyzPoint[MAX_AXES], uint32_t xAxes) const
|
||||
{
|
||||
if (!useTaper || xyzPoint[Z_AXIS] < taperHeight)
|
||||
{
|
||||
float zCorrection = 0.0;
|
||||
const size_t numAxes = reprap.GetGCodes()->GetNumAxes();
|
||||
unsigned int numXAxes = 0;
|
||||
|
@ -655,7 +658,7 @@ void Move::BedTransform(float xyzPoint[MAX_AXES], uint32_t xAxes) const
|
|||
switch(numBedCompensationPoints)
|
||||
{
|
||||
case 0:
|
||||
zCorrection += grid.ComputeHeightError(xCoord, xyzPoint[Y_AXIS], xyzPoint[Z_AXIS]);
|
||||
zCorrection += grid.GetInterpolatedHeightError(xCoord, xyzPoint[Y_AXIS]);
|
||||
break;
|
||||
|
||||
case 3:
|
||||
|
@ -676,11 +679,14 @@ void Move::BedTransform(float xyzPoint[MAX_AXES], uint32_t xAxes) const
|
|||
++numXAxes;
|
||||
}
|
||||
}
|
||||
|
||||
if (numXAxes > 1)
|
||||
{
|
||||
zCorrection /= numXAxes; // take an average
|
||||
}
|
||||
xyzPoint[Z_AXIS] += zCorrection;
|
||||
|
||||
xyzPoint[Z_AXIS] += (useTaper) ? (taperHeight - xyzPoint[Z_AXIS]) * recipTaperHeight * zCorrection : zCorrection;
|
||||
}
|
||||
}
|
||||
|
||||
// Invert the bed transform BEFORE the axis transform
|
||||
|
@ -700,7 +706,7 @@ void Move::InverseBedTransform(float xyzPoint[MAX_AXES], uint32_t xAxes) const
|
|||
switch(numBedCompensationPoints)
|
||||
{
|
||||
case 0:
|
||||
zCorrection += grid.ComputeInverseHeightError(xCoord, xyzPoint[Y_AXIS], xyzPoint[Z_AXIS]);
|
||||
zCorrection += grid.GetInterpolatedHeightError(xCoord, xyzPoint[Y_AXIS]);
|
||||
break;
|
||||
|
||||
case 3:
|
||||
|
@ -721,11 +727,24 @@ void Move::InverseBedTransform(float xyzPoint[MAX_AXES], uint32_t xAxes) const
|
|||
++numXAxes;
|
||||
}
|
||||
}
|
||||
|
||||
if (numXAxes > 1)
|
||||
{
|
||||
zCorrection /= numXAxes; // take an average
|
||||
}
|
||||
|
||||
if (!useTaper || zCorrection >= taperHeight) // need check on zCorrection to avoid possible divide by zero
|
||||
{
|
||||
xyzPoint[Z_AXIS] -= zCorrection;
|
||||
}
|
||||
else
|
||||
{
|
||||
const float zreq = (xyzPoint[Z_AXIS] - zCorrection)/(1.0 - (zCorrection * recipTaperHeight));
|
||||
if (zreq < taperHeight)
|
||||
{
|
||||
xyzPoint[Z_AXIS] = zreq;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void Move::SetIdentityTransform()
|
||||
|
@ -734,6 +753,16 @@ void Move::SetIdentityTransform()
|
|||
grid.ClearGridHeights();
|
||||
}
|
||||
|
||||
void Move::SetTaperHeight(float h)
|
||||
{
|
||||
useTaper = (h > 1.0);
|
||||
if (useTaper)
|
||||
{
|
||||
taperHeight = h;
|
||||
recipTaperHeight = 1.0/h;
|
||||
}
|
||||
}
|
||||
|
||||
float Move::AxisCompensation(int8_t axis) const
|
||||
{
|
||||
switch(axis)
|
||||
|
|
|
@ -79,6 +79,8 @@ public:
|
|||
void SetIdentityTransform(); // Cancel the bed equation; does not reset axis angle compensation
|
||||
void Transform(float move[], uint32_t xAxes) const; // Take a position and apply the bed and the axis-angle compensations
|
||||
void InverseTransform(float move[], uint32_t xAxes) const; // Go from a transformed point back to user coordinates
|
||||
float GetTaperHeight() const { return (useTaper) ? taperHeight : 0.0; }
|
||||
void SetTaperHeight(float h);
|
||||
|
||||
void Diagnostics(MessageType mtype); // Report useful stuff
|
||||
|
||||
|
@ -178,6 +180,9 @@ private:
|
|||
float tanXY, tanYZ, tanXZ; // Axis compensation - 90 degrees + angle gives angle between axes
|
||||
int numBedCompensationPoints; // The number of points we are actually using for bed compensation, 0 means identity bed transform
|
||||
float xRectangle, yRectangle; // The side lengths of the rectangle used for second-degree bed compensation
|
||||
float taperHeight; // Height over which we taper
|
||||
float recipTaperHeight; // Reciprocal of the taper height
|
||||
bool useTaper; // True to taper off the compensation
|
||||
|
||||
HeightMap grid; // Grid definition and height map for G29 bed probing. The probe heights are stored in zBedProbePoints, see above.
|
||||
|
||||
|
|
|
@ -2130,7 +2130,8 @@ void Platform::SetFanValue(size_t fan, float speed)
|
|||
// Enable or disable the fan that shares its PWM pin with the last heater. Called when we disable or enable the last heater.
|
||||
void Platform::EnableSharedFan(bool enable)
|
||||
{
|
||||
fans[NUM_FANS - 1].Init((enable) ? COOLING_FAN_PINS[NUM_FANS - 1] : NoPin, FansHardwareInverted());
|
||||
const size_t sharedFanNumber = NUM_FANS - 1;
|
||||
fans[sharedFanNumber].Init((enable) ? COOLING_FAN_PINS[sharedFanNumber] : NoPin, FansHardwareInverted(sharedFanNumber));
|
||||
}
|
||||
|
||||
#endif
|
||||
|
@ -2148,13 +2149,14 @@ float Platform::GetFanRPM()
|
|||
: 0.0; // else assume fan is off or tacho not connected
|
||||
}
|
||||
|
||||
bool Platform::FansHardwareInverted() const
|
||||
bool Platform::FansHardwareInverted(size_t fanNumber) const
|
||||
{
|
||||
#if defined(DUET_NG) || defined(__RADDS__)
|
||||
return false;
|
||||
#else
|
||||
// The cooling fan output pin gets inverted on a Duet 0.6 or 0.7
|
||||
return board == BoardType::Duet_06 || board == BoardType::Duet_07;
|
||||
// The cooling fan output pin gets inverted on a Duet 0.6 or 0.7.
|
||||
// We allow a second fan controlled by a mosfet on the PC4 pin, which is not inverted.
|
||||
return fanNumber == 0 && (board == BoardType::Duet_06 || board == BoardType::Duet_07);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -2162,7 +2164,7 @@ void Platform::InitFans()
|
|||
{
|
||||
for (size_t i = 0; i < NUM_FANS; ++i)
|
||||
{
|
||||
fans[i].Init(COOLING_FAN_PINS[i], FansHardwareInverted());
|
||||
fans[i].Init(COOLING_FAN_PINS[i], FansHardwareInverted(i));
|
||||
}
|
||||
|
||||
if (NUM_FANS > 1)
|
||||
|
|
|
@ -760,7 +760,7 @@ private:
|
|||
Pin coolingFanRpmPin; // we currently support only one fan RPM input
|
||||
float lastRpmResetTime;
|
||||
void InitFans();
|
||||
bool FansHardwareInverted() const;
|
||||
bool FansHardwareInverted(size_t fanNumber) const;
|
||||
|
||||
// Serial/USB
|
||||
|
||||
|
|
|
@ -396,68 +396,53 @@ bool PrintMonitor::GetFileInfo(const char *directory, const char *fileName, GCod
|
|||
{
|
||||
// Slic3r and S3D
|
||||
const char* generatedByString = "generated by ";
|
||||
char* pos = strstr(buf, generatedByString);
|
||||
const char* introString = "";
|
||||
const char* pos = strstr(buf, generatedByString);
|
||||
if (pos != nullptr)
|
||||
{
|
||||
pos += strlen(generatedByString);
|
||||
size_t i = 0;
|
||||
while (i < ARRAY_SIZE(parsedFileInfo.generatedBy) - 1 && *pos >= ' ')
|
||||
}
|
||||
else
|
||||
{
|
||||
char c = *pos++;
|
||||
if (c == '"' || c == '\\')
|
||||
// KISSlicer
|
||||
pos = strstr(buf, "; KISSlicer");
|
||||
if (pos != nullptr)
|
||||
{
|
||||
// Need to escape the quote-mark for JSON
|
||||
if (i > ARRAY_SIZE(parsedFileInfo.generatedBy) - 3)
|
||||
pos += 2;
|
||||
}
|
||||
else
|
||||
{
|
||||
break;
|
||||
}
|
||||
parsedFileInfo.generatedBy[i++] = '\\';
|
||||
}
|
||||
parsedFileInfo.generatedBy[i++] = c;
|
||||
}
|
||||
parsedFileInfo.generatedBy[i] = 0;
|
||||
}
|
||||
|
||||
// Cura
|
||||
// Cura (old)
|
||||
const char* slicedAtString = ";Sliced at: ";
|
||||
pos = strstr(buf, slicedAtString);
|
||||
if (pos != nullptr)
|
||||
{
|
||||
pos += strlen(slicedAtString);
|
||||
strcpy(parsedFileInfo.generatedBy, "Cura at ");
|
||||
size_t i = 8;
|
||||
introString = "Cura at ";
|
||||
}
|
||||
else
|
||||
{
|
||||
// Cura (new)
|
||||
const char* generatedWithString = ";Generated with ";
|
||||
pos = strstr(buf, generatedWithString);
|
||||
if (pos != nullptr)
|
||||
{
|
||||
pos += strlen(generatedWithString);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
if (pos != nullptr)
|
||||
{
|
||||
strcpy(parsedFileInfo.generatedBy, introString);
|
||||
size_t i = strlen(introString);
|
||||
while (i < ARRAY_SIZE(parsedFileInfo.generatedBy) - 1 && *pos >= ' ')
|
||||
{
|
||||
char c = *pos++;
|
||||
if (c == '"' || c == '\\')
|
||||
{
|
||||
if (i > ARRAY_SIZE(parsedFileInfo.generatedBy) - 3)
|
||||
{
|
||||
break;
|
||||
}
|
||||
parsedFileInfo.generatedBy[i++] = '\\';
|
||||
}
|
||||
parsedFileInfo.generatedBy[i++] = c;
|
||||
parsedFileInfo.generatedBy[i++] = *pos++;
|
||||
}
|
||||
parsedFileInfo.generatedBy[i] = 0;
|
||||
}
|
||||
|
||||
// KISSlicer
|
||||
const char* kisslicerStart = "; KISSlicer";
|
||||
if (StringStartsWith(buf, kisslicerStart))
|
||||
{
|
||||
size_t stringLength = 0;
|
||||
for(size_t i = 2; i < ARRAY_UPB(parsedFileInfo.generatedBy); i++)
|
||||
{
|
||||
if (buf[i] == '\r' || buf[i] == '\n')
|
||||
{
|
||||
break;
|
||||
}
|
||||
|
||||
parsedFileInfo.generatedBy[stringLength++] = buf[i];
|
||||
}
|
||||
parsedFileInfo.generatedBy[stringLength] = 0;
|
||||
}
|
||||
}
|
||||
headerInfoComplete &= (parsedFileInfo.generatedBy[0] != 0);
|
||||
|
||||
|
@ -638,7 +623,9 @@ bool PrintMonitor::GetFileInfoResponse(const char *filename, OutputBuffer *&resp
|
|||
ch = ',';
|
||||
}
|
||||
}
|
||||
response->catf("],\"generatedBy\":\"%s\"}", info.generatedBy);
|
||||
response->cat("],\"generatedBy\":");
|
||||
response->EncodeString(info.generatedBy, ARRAY_SIZE(info.generatedBy), false);
|
||||
response->cat("}");
|
||||
}
|
||||
else
|
||||
{
|
||||
|
@ -1110,14 +1097,38 @@ unsigned int PrintMonitor::FindFilamentUsed(const char* buf, size_t len, float *
|
|||
}
|
||||
if (isDigit(*p))
|
||||
{
|
||||
char* q;
|
||||
filamentUsed[filamentsFound] = strtod(p, &q); // S3D reports filament usage in mm, no conversion needed
|
||||
filamentUsed[filamentsFound] = strtod(p, nullptr); // S3D reports filament usage in mm, no conversion needed
|
||||
++filamentsFound;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Special case: KISSlicer only generates the filament volume, so we need to calculate the length from it
|
||||
// Look for filament usage as generated by recent KISSlicer versions
|
||||
if (!filamentsFound)
|
||||
{
|
||||
const char *filamentLengthStr = "; Ext ";
|
||||
p = buf;
|
||||
while (filamentsFound < maxFilaments && (p = strstr(p, filamentLengthStr)) != nullptr)
|
||||
{
|
||||
p += strlen(filamentLengthStr);
|
||||
while(isdigit(*p))
|
||||
{
|
||||
++p;
|
||||
}
|
||||
while(strchr(" :=\t", *p) != nullptr)
|
||||
{
|
||||
++p;
|
||||
}
|
||||
|
||||
if (isDigit(*p))
|
||||
{
|
||||
filamentUsed[filamentsFound] = strtod(p, nullptr);
|
||||
++filamentsFound;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Special case: Old KISSlicer only generates the filament volume, so we need to calculate the length from it
|
||||
if (!filamentsFound)
|
||||
{
|
||||
const char *filamentVolumeStr = "; Estimated Build Volume: ";
|
||||
|
|
|
@ -47,6 +47,36 @@ bool FileStore::Open(const char* directory, const char* fileName, bool write)
|
|||
writing = write;
|
||||
lastBufferEntry = FileBufLen;
|
||||
|
||||
// Try to create the path of this file if we want to write to it
|
||||
if (writing)
|
||||
{
|
||||
char filePathBuffer[FILENAME_LENGTH];
|
||||
StringRef filePath(filePathBuffer, FILENAME_LENGTH);
|
||||
filePath.copy(location);
|
||||
|
||||
bool isVolume = isdigit(filePath[0]);
|
||||
for(size_t i = 1; i < filePath.strlen(); i++)
|
||||
{
|
||||
if (filePath[i] == '/')
|
||||
{
|
||||
if (isVolume)
|
||||
{
|
||||
isVolume = false;
|
||||
continue;
|
||||
}
|
||||
|
||||
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",
|
||||
filePath.Pointer(), location);
|
||||
return false;
|
||||
}
|
||||
filePath[i] = '/';
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
FRESULT openReturn = f_open(&file, location, (writing) ? FA_CREATE_ALWAYS | FA_WRITE : FA_OPEN_EXISTING | FA_READ);
|
||||
if (openReturn != FR_OK)
|
||||
{
|
||||
|
|
Reference in a new issue