Version 1.09q-alpha3
Merged in chrishamm's changes including OutputBuffer fix, changes to Roland pin numbers, rr_configfile support in web server, and Roland and inkjet pin numbers moved to Pins_duet.h Merged in wrangellboy's http response changes for compatibility with Edge browser Other minor changes
This commit is contained in:
parent
0636efee40
commit
4a1072a8e7
29 changed files with 804 additions and 547 deletions
|
@ -26,11 +26,11 @@ Licence: GPL
|
|||
#define NAME "RepRapFirmware"
|
||||
|
||||
#ifndef VERSION
|
||||
#define VERSION "1.09p-alpha2-dc42"
|
||||
#define VERSION "1.09q-alpha3-dc42"
|
||||
#endif
|
||||
|
||||
#ifndef DATE
|
||||
#define DATE "2016-01-10"
|
||||
#define DATE "2016-01-16"
|
||||
#endif
|
||||
|
||||
#define AUTHORS "reprappro, dc42, zpl, t3p3, dnewman"
|
||||
|
@ -64,7 +64,7 @@ const float MINIMUM_TOOL_WARNING_INTERVAL = 4.0; // Seconds
|
|||
|
||||
// Comms defaults
|
||||
|
||||
const unsigned int USB_BAUD_RATE = 115200; // Default communication speed of the USB if needed
|
||||
const unsigned int MAIN_BAUD_RATE = 115200; // Default communication speed of the USB if needed
|
||||
const unsigned int AUX_BAUD_RATE = 57600; // Ditto - for auxiliary UART device
|
||||
const unsigned int AUX2_BAUD_RATE = 115200; // Ditto - for second auxiliary UART device
|
||||
|
||||
|
|
|
@ -48,7 +48,7 @@ void DeltaParameters::Recalc()
|
|||
Q2 = fsquare(Q);
|
||||
D2 = fsquare(diagonal);
|
||||
|
||||
// Calculate the base carriage height when the printer is homed.
|
||||
// Calculate the base carriage height when the printer is homed, i.e. the carriages are at the endstops less the corrections
|
||||
const float tempHeight = diagonal; // any sensible height will do here
|
||||
float machinePos[AXES];
|
||||
InverseTransform(tempHeight, tempHeight, tempHeight, machinePos);
|
||||
|
@ -203,7 +203,8 @@ void DeltaParameters::Adjust(size_t numFactors, const float v[])
|
|||
void DeltaParameters::PrintParameters(StringRef& reply) const
|
||||
{
|
||||
reply.printf("Endstops X%.2f Y%.2f Z%.2f, height %.2f, diagonal %.2f, radius %.2f, xcorr %.2f, ycorr %.2f, zcorr %.2f\n",
|
||||
endstopAdjustments[A_AXIS], endstopAdjustments[B_AXIS], endstopAdjustments[C_AXIS], homedHeight, diagonal, radius, xCorrection, yCorrection, zCorrection);
|
||||
endstopAdjustments[A_AXIS], endstopAdjustments[B_AXIS], endstopAdjustments[C_AXIS], homedHeight, diagonal, radius,
|
||||
xCorrection, yCorrection, zCorrection);
|
||||
}
|
||||
|
||||
// End
|
||||
|
|
20
Heat.cpp
20
Heat.cpp
|
@ -64,9 +64,9 @@ void Heat::Spin()
|
|||
{
|
||||
pids[heater]->Spin();
|
||||
}
|
||||
platform->ClassReport(longWait);
|
||||
}
|
||||
}
|
||||
platform->ClassReport(longWait);
|
||||
}
|
||||
|
||||
void Heat::Diagnostics()
|
||||
|
@ -74,16 +74,19 @@ void Heat::Diagnostics()
|
|||
platform->Message(GENERIC_MESSAGE, "Heat Diagnostics:\n");
|
||||
for (size_t heater=0; heater < HEATERS; heater++)
|
||||
{
|
||||
if (pids[heater]->active)
|
||||
if (pids[heater]->Active())
|
||||
{
|
||||
platform->MessageF(GENERIC_MESSAGE, "Heater %d: I-accumulator = %.1f\n", heater, pids[heater]->temp_iState);
|
||||
platform->MessageF(GENERIC_MESSAGE, "Heater %d: I-accumulator = %.1f\n", heater, pids[heater]->GetAccumulator());
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
bool Heat::AllHeatersAtSetTemperatures(bool includingBed) const
|
||||
{
|
||||
for (int8_t heater = (includingBed) ? 0 : 1; heater < HEATERS; heater++)
|
||||
size_t firstHeater = (bedHeater == -1) ? E0_HEATER :
|
||||
(includingBed) ? min<int8_t>(bedHeater, E0_HEATER) : E0_HEATER;
|
||||
|
||||
for(size_t heater = firstHeater; heater < HEATERS; heater++)
|
||||
{
|
||||
if (!HeaterAtSetTemperature(heater))
|
||||
{
|
||||
|
@ -96,7 +99,8 @@ bool Heat::AllHeatersAtSetTemperatures(bool includingBed) const
|
|||
//query an individual heater
|
||||
bool Heat::HeaterAtSetTemperature(int8_t heater) const
|
||||
{
|
||||
if (pids[heater]->SwitchedOff()) // If it hasn't anything to do, it must be right wherever it is...
|
||||
// If it hasn't anything to do, it must be right wherever it is...
|
||||
if (heater < 0 || pids[heater]->SwitchedOff() || pids[heater]->FaultOccurred())
|
||||
{
|
||||
return true;
|
||||
}
|
||||
|
@ -169,7 +173,7 @@ void PID::Spin()
|
|||
// heater off in that case anyway.
|
||||
if (temperatureFault || switchedOff)
|
||||
{
|
||||
SetHeater(0.0); // Make sure...
|
||||
SetHeater(0.0); // Make sure to turn it off...
|
||||
averagePWM *= (1.0 - invHeatPwmAverageCount);
|
||||
return;
|
||||
}
|
||||
|
@ -195,7 +199,6 @@ void PID::Spin()
|
|||
{
|
||||
SetHeater(0.0);
|
||||
temperatureFault = true;
|
||||
//switchedOff = true;
|
||||
platform->MessageF(GENERIC_MESSAGE, "Temperature fault on heater %d%s%s, T = %.1f\n",
|
||||
heater,
|
||||
(err != Platform::TempError::errOk) ? ", " : "",
|
||||
|
@ -210,7 +213,7 @@ void PID::Spin()
|
|||
}
|
||||
|
||||
// Now check how long it takes to warm up. If too long, maybe the thermistor is not in contact with the heater
|
||||
if (heatingUp && heater != BED_HEATER) // FIXME - also check bed warmup time?
|
||||
if (heatingUp && heater != reprap.GetHeat()->GetBedHeater()) // FIXME - also check bed warmup time?
|
||||
{
|
||||
float tmp = (active) ? activeTemperature : standbyTemperature;
|
||||
if (temperature < tmp - TEMPERATURE_CLOSE_ENOUGH)
|
||||
|
@ -221,7 +224,6 @@ void PID::Spin()
|
|||
{
|
||||
SetHeater(0.0);
|
||||
temperatureFault = true;
|
||||
//switchedOff = true;
|
||||
platform->MessageF(GENERIC_MESSAGE, "Heating fault on heater %d, T = %.1f C; still not at temperature %.1f after %f seconds.\n", heater, temperature, tmp, tim);
|
||||
reprap.FlagTemperatureFault(heater);
|
||||
}
|
||||
|
|
88
Heat.h
88
Heat.h
|
@ -27,8 +27,7 @@ Licence: GPL
|
|||
|
||||
class PID
|
||||
{
|
||||
friend class Heat;
|
||||
protected:
|
||||
public:
|
||||
|
||||
PID(Platform* p, int8_t h);
|
||||
void Init(); // (Re)Set everything to start
|
||||
|
@ -42,12 +41,14 @@ class PID
|
|||
bool Active() const; // Are we active?
|
||||
void SwitchOff(); // Not even standby - all heater power off
|
||||
bool SwitchedOff() const; // Are we switched off?
|
||||
bool FaultOccurred() const; // Has a heater fault occurred?
|
||||
void ResetFault(); // Reset a fault condition - only call this if you know what you are doing
|
||||
float GetTemperature() const; // Get the current temperature
|
||||
float GetAveragePWM() const; // Return the running average PWM to the heater. Answer is a fraction in [0, 1].
|
||||
float GetLastSampleTime() const; // Return when the temp sensor was last sampled
|
||||
float GetAccumulator() const; // Return the integral accumulator
|
||||
|
||||
private:
|
||||
private:
|
||||
|
||||
void SwitchOn();
|
||||
void SetHeater(float power) const; // power is a fraction in [0,1]
|
||||
|
@ -104,14 +105,13 @@ class Heat
|
|||
HeaterStatus GetStatus(int8_t heater) const; // Get the off/standby/active status
|
||||
void SwitchOff(int8_t heater); // Turn off a specific heater
|
||||
void SwitchOffAll(); // Turn all heaters off
|
||||
bool FaultOccurred() const; // Has a heater fault occurred?
|
||||
void ResetFault(int8_t heater); // Reset a heater fault - only call this if you know what you are doing
|
||||
bool AllHeatersAtSetTemperatures(bool includingBed) const; // Is everything at temperature within tolerance?
|
||||
bool HeaterAtSetTemperature(int8_t heater) const; // Is a specific heater at temperature within tolerance?
|
||||
void Diagnostics(); // Output useful information
|
||||
float GetAveragePWM(int8_t heater) const; // Return the running average PWM to the heater as a fraction in [0, 1].
|
||||
|
||||
bool UseSlowPwm(int8_t heater) const; // called by the PID class
|
||||
bool UseSlowPwm(int8_t heater) const; // Queried by the Platform class
|
||||
float GetLastSampleTime(int8_t heater) const;
|
||||
|
||||
private:
|
||||
|
@ -139,51 +139,76 @@ inline bool PID::Active() const
|
|||
|
||||
inline void PID::SetActiveTemperature(float t)
|
||||
{
|
||||
SwitchOn();
|
||||
activeTemperature = t;
|
||||
if (t > BAD_HIGH_TEMPERATURE)
|
||||
{
|
||||
platform->MessageF(GENERIC_MESSAGE, "Error: Temperature %.1f too high for heater %d!\n", t, heater);
|
||||
}
|
||||
|
||||
SwitchOn();
|
||||
activeTemperature = t;
|
||||
}
|
||||
|
||||
inline float PID::GetActiveTemperature() const
|
||||
{
|
||||
return activeTemperature;
|
||||
return activeTemperature;
|
||||
}
|
||||
|
||||
inline void PID::SetStandbyTemperature(float t)
|
||||
{
|
||||
SwitchOn();
|
||||
standbyTemperature = t;
|
||||
if (t > BAD_HIGH_TEMPERATURE)
|
||||
{
|
||||
platform->MessageF(GENERIC_MESSAGE, "Error: Temperature %.1f too high for heater %d!\n", t, heater);
|
||||
}
|
||||
|
||||
SwitchOn();
|
||||
standbyTemperature = t;
|
||||
}
|
||||
|
||||
inline float PID::GetStandbyTemperature() const
|
||||
{
|
||||
return standbyTemperature;
|
||||
return standbyTemperature;
|
||||
}
|
||||
|
||||
inline float PID::GetTemperature() const
|
||||
{
|
||||
return (temperatureFault ? ABS_ZERO : temperature);
|
||||
return temperature;
|
||||
}
|
||||
|
||||
inline void PID::Activate()
|
||||
{
|
||||
SwitchOn();
|
||||
active = true;
|
||||
if(!heatingUp)
|
||||
{
|
||||
timeSetHeating = platform->Time();
|
||||
}
|
||||
heatingUp = activeTemperature > temperature;
|
||||
if (temperatureFault)
|
||||
{
|
||||
return;
|
||||
}
|
||||
|
||||
SwitchOn();
|
||||
active = true;
|
||||
if (!heatingUp)
|
||||
{
|
||||
timeSetHeating = platform->Time();
|
||||
}
|
||||
heatingUp = activeTemperature > temperature;
|
||||
}
|
||||
|
||||
inline void PID::Standby()
|
||||
{
|
||||
SwitchOn();
|
||||
active = false;
|
||||
if(!heatingUp)
|
||||
{
|
||||
timeSetHeating = platform->Time();
|
||||
}
|
||||
heatingUp = standbyTemperature > temperature;
|
||||
if (temperatureFault)
|
||||
{
|
||||
return;
|
||||
}
|
||||
|
||||
SwitchOn();
|
||||
active = false;
|
||||
if (!heatingUp)
|
||||
{
|
||||
timeSetHeating = platform->Time();
|
||||
}
|
||||
heatingUp = standbyTemperature > temperature;
|
||||
}
|
||||
|
||||
inline bool PID::FaultOccurred() const
|
||||
{
|
||||
return temperatureFault;
|
||||
}
|
||||
|
||||
inline void PID::ResetFault()
|
||||
|
@ -211,6 +236,12 @@ inline float PID::GetLastSampleTime() const
|
|||
return lastSampleTime;
|
||||
}
|
||||
|
||||
inline float PID::GetAccumulator() const
|
||||
{
|
||||
return temp_iState;
|
||||
}
|
||||
|
||||
|
||||
//**********************************************************************************
|
||||
|
||||
// Heat
|
||||
|
@ -253,8 +284,11 @@ inline void Heat::SetChamberHeater(int8_t heater)
|
|||
inline Heat::HeaterStatus Heat::GetStatus(int8_t heater) const
|
||||
{
|
||||
if (heater < 0 || heater >= HEATERS)
|
||||
{
|
||||
return HS_off;
|
||||
return (pids[heater]->temperatureFault ? HS_fault
|
||||
}
|
||||
|
||||
return (pids[heater]->FaultOccurred() ? HS_fault
|
||||
: pids[heater]->SwitchedOff()) ? HS_off
|
||||
: (pids[heater]->Active()) ? HS_active
|
||||
: HS_standby;
|
||||
|
|
|
@ -89,11 +89,9 @@ extern "C" {
|
|||
*/
|
||||
uint8_t ethernet_phy_read_register(Emac *p_emac, uint8_t uc_phy_addr, uint32_t ul_phy_reg, uint32_t *p_ul_reg_cont)
|
||||
{
|
||||
uint8_t uc_rc;
|
||||
|
||||
emac_enable_management(p_emac, true);
|
||||
|
||||
uc_rc = emac_phy_read(p_emac, uc_phy_addr, ul_phy_reg, p_ul_reg_cont);
|
||||
uint8_t uc_rc = emac_phy_read(p_emac, uc_phy_addr, ul_phy_reg, p_ul_reg_cont);
|
||||
if (uc_rc != EMAC_OK) {
|
||||
/* Disable PHY management and start the EMAC transfer */
|
||||
emac_enable_management(p_emac, false);
|
||||
|
|
|
@ -50,7 +50,6 @@
|
|||
//#include "board.h"
|
||||
//#include "emac.h"
|
||||
#include "Arduino.h"
|
||||
//#include "SamNonDuePin/SamNonDuePin.h"
|
||||
#include <include/emac.h>
|
||||
#include "conf_eth.h"
|
||||
|
||||
|
|
|
@ -250,8 +250,8 @@ void ethernet_hardware_init(void)
|
|||
emac_dev_init(EMAC, &gs_emac_dev, &emac_option);
|
||||
}
|
||||
|
||||
/* Set lower priority */
|
||||
NVIC_SetPriority(EMAC_IRQn, 12);
|
||||
/* Set IRQ priority */
|
||||
NVIC_SetPriority(EMAC_IRQn, 4);
|
||||
|
||||
/* Enable Interrupt */
|
||||
NVIC_EnableIRQ(EMAC_IRQn);
|
||||
|
@ -504,7 +504,7 @@ void ethernetif_set_rx_callback(emac_dev_tx_cb_t callback)
|
|||
|
||||
void ethernetif_set_mac_address(const u8_t macAddress[])
|
||||
{
|
||||
for (size_t i = 0; i < 6; ++i)
|
||||
for(size_t i = 0; i < 6; ++i)
|
||||
{
|
||||
gs_uc_mac_address[i] = macAddress[i];
|
||||
}
|
||||
|
|
|
@ -4,7 +4,7 @@
|
|||
Library to control the MCP4461 Digital Potentiometer over I2C.
|
||||
http://ww1.microchip.com/downloads/en/DeviceDoc/22265a.pdf
|
||||
This library does not fully implement the functionality of
|
||||
the MCP4461 – just the basics of changing the wiper values.
|
||||
the MCP4461 just the basics of changing the wiper values.
|
||||
Note this is currently configured to use the second I2C bus
|
||||
on the Due: Wire1
|
||||
The master joins the bus with the default address of 0
|
||||
|
|
|
@ -69,6 +69,7 @@
|
|||
#ifndef __ASSEMBLY__ // Not defined for assembling.
|
||||
|
||||
#include <stdio.h>
|
||||
#undef printf // some idiot defined printf as a macro inside cstdio, which prevents us using it as a member function name
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
|
|
|
@ -332,8 +332,7 @@ void dmac_channel_keep(
|
|||
* "DMAC Channel Handler Status Register" in the device-specific datasheet for more
|
||||
* information.
|
||||
*/
|
||||
uint32_t dmac_channel_get_status(
|
||||
Dmac *p_dmac)
|
||||
uint32_t dmac_channel_get_status(Dmac *p_dmac)
|
||||
{
|
||||
/* Validate parameters. */
|
||||
Assert(p_dmac);
|
||||
|
|
|
@ -78,9 +78,9 @@ typedef uint8_t sd_mmc_err_t; //!< Type of return error code
|
|||
#define SD_MMC_INIT_ONGOING 1 //! Card not initialized
|
||||
#define SD_MMC_ERR_NO_CARD 2 //! No SD/MMC card inserted
|
||||
#define SD_MMC_ERR_UNUSABLE 3 //! Unusable card
|
||||
#define SD_MMC_ERR_SLOT 4 //! Slot unknow
|
||||
#define SD_MMC_ERR_SLOT 4 //! Slot unknown
|
||||
#define SD_MMC_ERR_COMM 5 //! General communication error
|
||||
#define SD_MMC_ERR_PARAM 6 //! Illeage input parameter
|
||||
#define SD_MMC_ERR_PARAM 6 //! Illegal input parameter
|
||||
#define SD_MMC_ERR_WP 7 //! Card write protected
|
||||
//! @}
|
||||
|
||||
|
|
92
Network.cpp
92
Network.cpp
|
@ -925,6 +925,11 @@ uint16_t ConnectionState::GetRemotePort() const
|
|||
|
||||
// NetworkTransaction class members
|
||||
|
||||
NetworkTransaction::NetworkTransaction(NetworkTransaction *n) : next(n)
|
||||
{
|
||||
sendStack = new OutputStack();
|
||||
}
|
||||
|
||||
void NetworkTransaction::Set(pbuf *p, ConnectionState *c, TransactionStatus s)
|
||||
{
|
||||
cs = c;
|
||||
|
@ -941,7 +946,7 @@ void NetworkTransaction::Set(pbuf *p, ConnectionState *c, TransactionStatus s)
|
|||
}
|
||||
|
||||
// How many incoming bytes do we have to process?
|
||||
uint16_t NetworkTransaction::DataLength() const
|
||||
size_t NetworkTransaction::DataLength() const
|
||||
{
|
||||
return (pb == nullptr) ? 0 : pb->tot_len;
|
||||
}
|
||||
|
@ -1013,7 +1018,7 @@ bool NetworkTransaction::ReadBuffer(char *&buffer, unsigned int &len)
|
|||
|
||||
void NetworkTransaction::Write(char b)
|
||||
{
|
||||
if (!LostConnection() && status != disconnected)
|
||||
if (CanWrite())
|
||||
{
|
||||
if (sendBuffer == nullptr && !OutputBuffer::Allocate(sendBuffer))
|
||||
{
|
||||
|
@ -1027,7 +1032,7 @@ void NetworkTransaction::Write(char b)
|
|||
// It may be necessary to split it up into multiple SendBuffers.
|
||||
void NetworkTransaction::Write(const char* s)
|
||||
{
|
||||
if (!LostConnection() && status != disconnected)
|
||||
if (CanWrite())
|
||||
{
|
||||
if (sendBuffer == nullptr && !OutputBuffer::Allocate(sendBuffer))
|
||||
{
|
||||
|
@ -1044,7 +1049,7 @@ void NetworkTransaction::Write(StringRef ref)
|
|||
|
||||
void NetworkTransaction::Write(const char* s, size_t len)
|
||||
{
|
||||
if (!LostConnection() && status != disconnected)
|
||||
if (CanWrite())
|
||||
{
|
||||
if (sendBuffer == nullptr && !OutputBuffer::Allocate(sendBuffer))
|
||||
{
|
||||
|
@ -1056,22 +1061,29 @@ void NetworkTransaction::Write(const char* s, size_t len)
|
|||
|
||||
void NetworkTransaction::Write(OutputBuffer *buffer)
|
||||
{
|
||||
if (!LostConnection() && status != disconnected)
|
||||
if (CanWrite())
|
||||
{
|
||||
if (sendBuffer == nullptr)
|
||||
{
|
||||
sendBuffer = buffer;
|
||||
}
|
||||
else
|
||||
{
|
||||
sendBuffer->Append(buffer);
|
||||
}
|
||||
// Note we use an individual stack here, because we don't want to link different
|
||||
// OutputBuffers for different destinations together...
|
||||
sendStack->Push(buffer);
|
||||
}
|
||||
else
|
||||
{
|
||||
while (buffer != nullptr)
|
||||
OutputBuffer::ReleaseAll(buffer);
|
||||
}
|
||||
}
|
||||
|
||||
void NetworkTransaction::Write(OutputStack *stack)
|
||||
{
|
||||
if (stack != nullptr)
|
||||
{
|
||||
if (CanWrite())
|
||||
{
|
||||
buffer = OutputBuffer::Release(buffer);
|
||||
sendStack->Append(stack);
|
||||
}
|
||||
else
|
||||
{
|
||||
stack->ReleaseAll();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -1079,25 +1091,25 @@ void NetworkTransaction::Write(OutputBuffer *buffer)
|
|||
// Write formatted data to the output buffer
|
||||
void NetworkTransaction::Printf(const char* fmt, ...)
|
||||
{
|
||||
if (LostConnection() || status == disconnected)
|
||||
if (CanWrite() && (sendBuffer != nullptr || OutputBuffer::Allocate(sendBuffer)))
|
||||
{
|
||||
return;
|
||||
va_list p;
|
||||
va_start(p, fmt);
|
||||
sendBuffer->vprintf(fmt, p);
|
||||
va_end(p);
|
||||
}
|
||||
|
||||
if (sendBuffer == nullptr && !OutputBuffer::Allocate(sendBuffer))
|
||||
{
|
||||
return;
|
||||
}
|
||||
|
||||
va_list p;
|
||||
va_start(p, fmt);
|
||||
sendBuffer->vprintf(fmt, p);
|
||||
va_end(p);
|
||||
}
|
||||
|
||||
void NetworkTransaction::SetFileToWrite(FileStore *file)
|
||||
{
|
||||
fileBeingSent = file;
|
||||
if (CanWrite())
|
||||
{
|
||||
fileBeingSent = file;
|
||||
}
|
||||
else if (file != nullptr)
|
||||
{
|
||||
file->Close();
|
||||
}
|
||||
}
|
||||
|
||||
// Send exactly one TCP window of data or return true if we can free up this object
|
||||
|
@ -1113,10 +1125,8 @@ bool NetworkTransaction::Send()
|
|||
fileBeingSent = nullptr;
|
||||
}
|
||||
|
||||
while (sendBuffer != nullptr)
|
||||
{
|
||||
sendBuffer = OutputBuffer::Release(sendBuffer);
|
||||
}
|
||||
OutputBuffer::ReleaseAll(sendBuffer);
|
||||
sendStack->ReleaseAll();
|
||||
|
||||
if (!LostConnection())
|
||||
{
|
||||
|
@ -1143,7 +1153,7 @@ bool NetworkTransaction::Send()
|
|||
}
|
||||
|
||||
// We're still waiting for data to be ACK'ed, so check timeouts here
|
||||
if (sentDataOutstanding)
|
||||
if (sentDataOutstanding != 0)
|
||||
{
|
||||
if (!isnan(lastWriteTime))
|
||||
{
|
||||
|
@ -1174,6 +1184,10 @@ bool NetworkTransaction::Send()
|
|||
if (sendBuffer->BytesLeft() == 0)
|
||||
{
|
||||
sendBuffer = OutputBuffer::Release(sendBuffer);
|
||||
if (sendBuffer == nullptr)
|
||||
{
|
||||
sendBuffer = sendStack->Pop();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -1256,9 +1270,13 @@ void NetworkTransaction::Commit(bool keepConnectionAlive)
|
|||
else
|
||||
{
|
||||
// We're actually sending, so this transaction must be complete
|
||||
reprap.GetNetwork()->readyTransactions = next;
|
||||
FreePbuf();
|
||||
reprap.GetNetwork()->readyTransactions = next;
|
||||
cs->persistConnection = keepConnectionAlive;
|
||||
if (sendBuffer == nullptr)
|
||||
{
|
||||
sendBuffer = sendStack->Pop();
|
||||
}
|
||||
status = dataSending;
|
||||
|
||||
// Enqueue this transaction, so it's sent in the right order
|
||||
|
@ -1311,10 +1329,8 @@ void NetworkTransaction::Discard()
|
|||
fileBeingSent->Close();
|
||||
}
|
||||
|
||||
while (sendBuffer != nullptr)
|
||||
{
|
||||
sendBuffer = OutputBuffer::Release(sendBuffer);
|
||||
}
|
||||
OutputBuffer::ReleaseAll(sendBuffer);
|
||||
sendStack->ReleaseAll();
|
||||
|
||||
// Free this transaction again unless it's still referenced
|
||||
if (status != dataSending)
|
||||
|
|
31
Network.h
31
Network.h
|
@ -16,7 +16,7 @@ Separated out from Platform.h by dc42 and extended by zpl
|
|||
|
||||
#include "lwipopts.h"
|
||||
#include "ethernet_sam.h"
|
||||
#include "OutputBuffer.h"
|
||||
#include "OutputMemory.h"
|
||||
|
||||
// This class handles the network - typically an Ethernet.
|
||||
|
||||
|
@ -28,17 +28,17 @@ Separated out from Platform.h by dc42 and extended by zpl
|
|||
// 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.
|
||||
|
||||
static const uint8_t NETWORK_TRANSACTION_COUNT = 16; // Number of NetworkTransactions to be used for network IO
|
||||
static const float TCP_WRITE_TIMEOUT = 4.0; // Seconds to wait for data we have written to be acknowledged
|
||||
const uint8_t NETWORK_TRANSACTION_COUNT = 16; // Number of NetworkTransactions to be used for network IO
|
||||
const float TCP_WRITE_TIMEOUT = 8.0; // Seconds to wait for data we have written to be acknowledged
|
||||
|
||||
|
||||
static const uint8_t IP_ADDRESS[4] = { 192, 168, 1, 10 }; // Need some sort of default...
|
||||
static const uint8_t NET_MASK[4] = { 255, 255, 255, 0 };
|
||||
static const uint8_t GATE_WAY[4] = { 192, 168, 1, 1 };
|
||||
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 };
|
||||
|
||||
static const uint16_t FTP_PORT = 21;
|
||||
static const uint16_t TELNET_PORT = 23;
|
||||
static const uint16_t DEFAULT_HTTP_PORT = 80;
|
||||
const uint16_t FTP_PORT = 21;
|
||||
const uint16_t TELNET_PORT = 23;
|
||||
const uint16_t DEFAULT_HTTP_PORT = 80;
|
||||
|
||||
|
||||
/****************************************************************************************************/
|
||||
|
@ -78,11 +78,11 @@ class NetworkTransaction
|
|||
public:
|
||||
friend class Network;
|
||||
|
||||
NetworkTransaction(NetworkTransaction* n) : next(n) { }
|
||||
NetworkTransaction(NetworkTransaction* n);
|
||||
void Set(pbuf *p, ConnectionState* c, TransactionStatus s);
|
||||
TransactionStatus GetStatus() const { return status; }
|
||||
|
||||
uint16_t DataLength() const;
|
||||
size_t DataLength() const;
|
||||
bool Read(char& b);
|
||||
bool ReadBuffer(char *&buffer, unsigned int &len);
|
||||
void Write(char b);
|
||||
|
@ -90,6 +90,7 @@ class NetworkTransaction
|
|||
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);
|
||||
|
||||
|
@ -105,6 +106,7 @@ class NetworkTransaction
|
|||
void Discard();
|
||||
|
||||
private:
|
||||
bool CanWrite() const;
|
||||
bool Send();
|
||||
void Close();
|
||||
void FreePbuf();
|
||||
|
@ -117,6 +119,7 @@ class NetworkTransaction
|
|||
unsigned int inputPointer; // amount of data already taken from the first packet buffer
|
||||
|
||||
OutputBuffer *sendBuffer;
|
||||
OutputStack *sendStack;
|
||||
FileStore *fileBeingSent;
|
||||
|
||||
TransactionStatus status;
|
||||
|
@ -158,6 +161,7 @@ class Network
|
|||
|
||||
Network(Platform* p);
|
||||
void Init();
|
||||
void Exit() {}
|
||||
void Spin();
|
||||
void Interrupt();
|
||||
void Diagnostics();
|
||||
|
@ -200,6 +204,11 @@ class Network
|
|||
ConnectionState * volatile freeConnections; // May be referenced by Ethernet ISR, hence it's volatile
|
||||
};
|
||||
|
||||
inline bool NetworkTransaction::CanWrite() const
|
||||
{
|
||||
return (!LostConnection() && status != disconnected && status != dataSending);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
// vim: ts=4:sw=4
|
||||
|
|
|
@ -1,89 +0,0 @@
|
|||
/*
|
||||
* OutputBuffer.h
|
||||
*
|
||||
* Created on: 10 Jan 2016
|
||||
* Author: David
|
||||
*/
|
||||
|
||||
#ifndef OUTPUTBUFFER_H_
|
||||
#define OUTPUTBUFFER_H_
|
||||
|
||||
#include "Arduino.h"
|
||||
#include "Configuration.h"
|
||||
#include "StringRef.h"
|
||||
|
||||
// This class is used to hold data for sending (either for Serial or Network destinations)
|
||||
class OutputBuffer
|
||||
{
|
||||
public:
|
||||
OutputBuffer(OutputBuffer *n) : next(n) { }
|
||||
|
||||
OutputBuffer *Next() const { return next; }
|
||||
void Append(OutputBuffer *other);
|
||||
size_t References() const { return references; }
|
||||
void IncreaseReferences(size_t refs);
|
||||
|
||||
const char *Data() const { return data; }
|
||||
uint16_t DataLength() const { return dataLength; } // How many bytes have been written to this instance?
|
||||
uint32_t Length() const; // How many bytes have been written to the whole chain?
|
||||
|
||||
char& operator[](size_t index);
|
||||
char operator[](size_t index) const;
|
||||
const char *Read(uint16_t len);
|
||||
uint16_t BytesLeft() const { return bytesLeft; } // How many bytes have not been sent yet?
|
||||
|
||||
int printf(const char *fmt, ...);
|
||||
int vprintf(const char *fmt, va_list vargs);
|
||||
int catf(const char *fmt, ...);
|
||||
|
||||
size_t copy(const char c);
|
||||
size_t copy(const char *src);
|
||||
size_t copy(const char *src, size_t len);
|
||||
|
||||
size_t cat(const char c);
|
||||
size_t cat(const char *src);
|
||||
size_t cat(const char *src, size_t len);
|
||||
size_t cat(StringRef &str);
|
||||
|
||||
size_t EncodeString(const char *src, uint16_t srcLength, bool allowControlChars, bool encapsulateString = true);
|
||||
size_t EncodeReply(OutputBuffer *src, bool allowControlChars);
|
||||
|
||||
// Initialise the output buffers manager
|
||||
static void Init();
|
||||
|
||||
// Allocate an unused OutputBuffer instance. Returns true on success or false if no instance could be allocated.
|
||||
// Setting isAppending to true will guarantee that one OutputBuffer will remain available for single allocation.
|
||||
static bool Allocate(OutputBuffer *&buf, bool isAppending = false);
|
||||
|
||||
// Get the number of bytes left for allocation. If writingBuffer is not NULL, this returns the number of free bytes for
|
||||
// continuous writes, i.e. for writes that need to allocate an extra OutputBuffer instance to finish the message.
|
||||
static size_t GetBytesLeft(const OutputBuffer *writingBuffer);
|
||||
|
||||
// Replace an existing OutputBuffer with another one.
|
||||
static void Replace(OutputBuffer *&destination, OutputBuffer *source);
|
||||
|
||||
// Truncate an OutputBuffer instance to free up more memory. Returns the number of released bytes.
|
||||
static size_t Truncate(OutputBuffer *buffer, size_t bytesNeeded);
|
||||
|
||||
// Release one OutputBuffer instance. Returns the next item from the chain or nullptr if this was the last instance.
|
||||
static OutputBuffer *Release(OutputBuffer *buf);
|
||||
|
||||
// Release all OutputBuffer objects in a chain
|
||||
static void ReleaseAll(OutputBuffer *buf);
|
||||
|
||||
static void Diagnostics();
|
||||
|
||||
private:
|
||||
OutputBuffer *next;
|
||||
|
||||
char data[OUTPUT_BUFFER_SIZE];
|
||||
uint16_t dataLength, bytesLeft;
|
||||
|
||||
size_t references;
|
||||
|
||||
static OutputBuffer * volatile freeOutputBuffers; // Messages may also be sent by ISRs,
|
||||
static volatile size_t usedOutputBuffers; // so make these volatile.
|
||||
static volatile size_t maxUsedOutputBuffers;
|
||||
};
|
||||
|
||||
#endif /* OUTPUTBUFFER_H_ */
|
|
@ -1,16 +1,16 @@
|
|||
/*
|
||||
* OuputBuffer.cpp
|
||||
* OutputMemory.cpp
|
||||
*
|
||||
* Created on: 10 Jan 2016
|
||||
* Author: David
|
||||
* Authors: David and Christian
|
||||
*/
|
||||
|
||||
#include "OutputBuffer.h"
|
||||
#include "OutputMemory.h"
|
||||
#include "RepRapFirmware.h"
|
||||
#include <cstdarg>
|
||||
|
||||
/*static*/ OutputBuffer * volatile OutputBuffer::freeOutputBuffers = nullptr; // Messages may also be sent by ISRs,
|
||||
/*static*/ volatile size_t OutputBuffer::usedOutputBuffers = 0; // so make these volatile.
|
||||
/*static*/ volatile size_t OutputBuffer::usedOutputBuffers = 0; // so make these volatile.
|
||||
/*static*/ volatile size_t OutputBuffer::maxUsedOutputBuffers = 0;
|
||||
|
||||
//*************************************************************************************************
|
||||
|
@ -20,32 +20,34 @@ void OutputBuffer::Append(OutputBuffer *other)
|
|||
{
|
||||
if (other != nullptr)
|
||||
{
|
||||
OutputBuffer *lastBuffer = this;
|
||||
while (lastBuffer->next != nullptr)
|
||||
last->next = other;
|
||||
last = other->last;
|
||||
for(OutputBuffer *item = Next(); item != other; item = item->Next())
|
||||
{
|
||||
lastBuffer = lastBuffer->next;
|
||||
item->last = last;
|
||||
}
|
||||
lastBuffer->next = other;
|
||||
}
|
||||
}
|
||||
|
||||
void OutputBuffer::IncreaseReferences(size_t refs)
|
||||
{
|
||||
references += refs;
|
||||
if (next != nullptr)
|
||||
if (refs > 0)
|
||||
{
|
||||
next->IncreaseReferences(refs);
|
||||
for(OutputBuffer *item = this; item != nullptr; item = item->Next())
|
||||
{
|
||||
item->references += refs;
|
||||
item->isReferenced = true;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
uint32_t OutputBuffer::Length() const
|
||||
size_t OutputBuffer::Length() const
|
||||
{
|
||||
uint32_t totalLength = 0;
|
||||
const OutputBuffer *current = this;
|
||||
do {
|
||||
size_t totalLength = 0;
|
||||
for(const OutputBuffer *current = this; current != nullptr; current = current->Next())
|
||||
{
|
||||
totalLength += current->DataLength();
|
||||
current = current->next;
|
||||
} while (current != nullptr);
|
||||
}
|
||||
return totalLength;
|
||||
}
|
||||
|
||||
|
@ -77,24 +79,22 @@ char OutputBuffer::operator[](size_t index) const
|
|||
return itemToIndex->data[index];
|
||||
}
|
||||
|
||||
const char *OutputBuffer::Read(uint16_t len)
|
||||
const char *OutputBuffer::Read(size_t len)
|
||||
{
|
||||
size_t offset = dataLength - bytesLeft;
|
||||
bytesLeft -= len;
|
||||
size_t offset = bytesRead;
|
||||
bytesRead += len;
|
||||
return data + offset;
|
||||
}
|
||||
|
||||
int OutputBuffer::printf(const char *fmt, ...)
|
||||
{
|
||||
char formatBuffer[FORMAT_STRING_LENGTH];
|
||||
|
||||
va_list vargs;
|
||||
va_start(vargs, fmt);
|
||||
int ret = vsnprintf(formatBuffer, ARRAY_SIZE(formatBuffer), fmt, vargs);
|
||||
va_end(vargs);
|
||||
|
||||
copy(formatBuffer);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
|
@ -102,6 +102,7 @@ int OutputBuffer::vprintf(const char *fmt, va_list vargs)
|
|||
{
|
||||
char formatBuffer[FORMAT_STRING_LENGTH];
|
||||
int res = vsnprintf(formatBuffer, ARRAY_SIZE(formatBuffer), fmt, vargs);
|
||||
|
||||
cat(formatBuffer);
|
||||
return res;
|
||||
}
|
||||
|
@ -109,21 +110,28 @@ int OutputBuffer::vprintf(const char *fmt, va_list vargs)
|
|||
int OutputBuffer::catf(const char *fmt, ...)
|
||||
{
|
||||
char formatBuffer[FORMAT_STRING_LENGTH];
|
||||
|
||||
va_list vargs;
|
||||
va_start(vargs, fmt);
|
||||
int ret = vsnprintf(formatBuffer, ARRAY_SIZE(formatBuffer), fmt, vargs);
|
||||
va_end(vargs);
|
||||
|
||||
cat(formatBuffer);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
size_t OutputBuffer::copy(const char c)
|
||||
{
|
||||
// Unlink existing entries before starting the copy process
|
||||
if (next != nullptr)
|
||||
{
|
||||
ReleaseAll(next);
|
||||
next = nullptr;
|
||||
last = this;
|
||||
}
|
||||
|
||||
// Set the date
|
||||
data[0] = c;
|
||||
dataLength = bytesLeft = 1;
|
||||
dataLength = 1;
|
||||
return 1;
|
||||
}
|
||||
|
||||
|
@ -134,69 +142,70 @@ size_t OutputBuffer::copy(const char *src)
|
|||
|
||||
size_t OutputBuffer::copy(const char *src, size_t len)
|
||||
{
|
||||
// Unlink other entries before starting the copy process
|
||||
OutputBuffer *nextBuffer = next;
|
||||
while (nextBuffer != nullptr)
|
||||
// Unlink existing entries before starting the copy process
|
||||
if (next != nullptr)
|
||||
{
|
||||
nextBuffer = Release(nextBuffer);
|
||||
ReleaseAll(next);
|
||||
next = nullptr;
|
||||
last = this;
|
||||
}
|
||||
|
||||
// Does the whole string fit into this instance?
|
||||
if (len > OUTPUT_BUFFER_SIZE)
|
||||
{
|
||||
// No - copy what we can't write into a new chain
|
||||
OutputBuffer *currentBuffer, *lastBuffer = nullptr;
|
||||
OutputBuffer *currentBuffer;
|
||||
size_t bytesCopied = OUTPUT_BUFFER_SIZE;
|
||||
do {
|
||||
if (!Allocate(currentBuffer, true))
|
||||
{
|
||||
// We cannot store the whole string. Should never happen
|
||||
// We cannot store the whole string, stop here
|
||||
break;
|
||||
}
|
||||
currentBuffer->references = references;
|
||||
|
||||
// Fill up the next instance
|
||||
const size_t copyLength = min<size_t>(OUTPUT_BUFFER_SIZE, len - bytesCopied);
|
||||
memcpy(currentBuffer->data, src + bytesCopied, copyLength);
|
||||
currentBuffer->dataLength = currentBuffer->bytesLeft = copyLength;
|
||||
currentBuffer->dataLength = copyLength;
|
||||
bytesCopied += copyLength;
|
||||
|
||||
// Link it to the chain
|
||||
if (next == nullptr)
|
||||
{
|
||||
next = lastBuffer = currentBuffer;
|
||||
next = last = currentBuffer;
|
||||
}
|
||||
else
|
||||
{
|
||||
lastBuffer->next = currentBuffer;
|
||||
lastBuffer = currentBuffer;
|
||||
last->next = currentBuffer;
|
||||
last = currentBuffer;
|
||||
}
|
||||
} while (bytesCopied < len);
|
||||
|
||||
// Update references to the last entry for all items
|
||||
for(OutputBuffer *item = Next(); item != last; item = item->Next())
|
||||
{
|
||||
item->last = last;
|
||||
}
|
||||
|
||||
// Then copy the rest into this instance
|
||||
memcpy(data, src, OUTPUT_BUFFER_SIZE);
|
||||
dataLength = bytesLeft = OUTPUT_BUFFER_SIZE;
|
||||
next = nextBuffer;
|
||||
dataLength = OUTPUT_BUFFER_SIZE;
|
||||
return bytesCopied;
|
||||
}
|
||||
|
||||
// Yes - no need to use a new item
|
||||
// Yes, the whole string fits into this instance. No need to allocate a new item
|
||||
memcpy(data, src, len);
|
||||
dataLength = bytesLeft = len;
|
||||
dataLength = len;
|
||||
return len;
|
||||
}
|
||||
|
||||
size_t OutputBuffer::cat(const char c)
|
||||
{
|
||||
// Get the last entry from the chain
|
||||
OutputBuffer *lastBuffer = this;
|
||||
while (lastBuffer->next != nullptr)
|
||||
{
|
||||
lastBuffer = lastBuffer->next;
|
||||
}
|
||||
|
||||
// See if we can append a char
|
||||
if (lastBuffer->dataLength == OUTPUT_BUFFER_SIZE)
|
||||
if (last->dataLength == OUTPUT_BUFFER_SIZE)
|
||||
{
|
||||
// No - allocate a new item and link it
|
||||
// No - allocate a new item and copy the data
|
||||
OutputBuffer *nextBuffer;
|
||||
if (!Allocate(nextBuffer, true))
|
||||
{
|
||||
|
@ -206,13 +215,17 @@ size_t OutputBuffer::cat(const char c)
|
|||
nextBuffer->references = references;
|
||||
nextBuffer->copy(c);
|
||||
|
||||
lastBuffer->next = nextBuffer;
|
||||
// Link the new item to this list
|
||||
last->next = nextBuffer;
|
||||
for(OutputBuffer *item = this; item != nextBuffer; item = item->Next())
|
||||
{
|
||||
item->last = nextBuffer;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
// Yes - we have enough space left
|
||||
lastBuffer->data[lastBuffer->dataLength++] = c;
|
||||
lastBuffer->bytesLeft++;
|
||||
last->data[last->dataLength++] = c;
|
||||
}
|
||||
return 1;
|
||||
}
|
||||
|
@ -224,42 +237,35 @@ size_t OutputBuffer::cat(const char *src)
|
|||
|
||||
size_t OutputBuffer::cat(const char *src, size_t len)
|
||||
{
|
||||
// Get the last entry from the chain
|
||||
OutputBuffer *lastBuffer = this;
|
||||
while (lastBuffer->next != nullptr)
|
||||
{
|
||||
lastBuffer = lastBuffer->next;
|
||||
}
|
||||
// Copy what we can into the last buffer
|
||||
size_t copyLength = min<size_t>(len, OUTPUT_BUFFER_SIZE - last->dataLength);
|
||||
memcpy(last->data + last->dataLength, src, copyLength);
|
||||
last->dataLength += copyLength;
|
||||
|
||||
// Do we need to use an extra buffer?
|
||||
if (lastBuffer->dataLength + len > OUTPUT_BUFFER_SIZE)
|
||||
// Is there any more data left?
|
||||
if (len > copyLength)
|
||||
{
|
||||
size_t copyLength = OUTPUT_BUFFER_SIZE - lastBuffer->dataLength;
|
||||
size_t bytesCopied = copyLength;
|
||||
bytesCopied = copyLength;
|
||||
|
||||
// Yes - copy what we can't write into a new chain
|
||||
// Yes - copy what we couldn't write into a new chain
|
||||
OutputBuffer *nextBuffer;
|
||||
if (!Allocate(nextBuffer, true))
|
||||
{
|
||||
// We cannot store any more data. Should never happen
|
||||
return 0;
|
||||
// We cannot store any more data, stop here
|
||||
return copyLength;
|
||||
}
|
||||
nextBuffer->references = references;
|
||||
bytesCopied += nextBuffer->copy(src + copyLength, len - copyLength);
|
||||
lastBuffer->next = nextBuffer;
|
||||
const size_t bytesCopied = copyLength + nextBuffer->copy(src + copyLength, len - copyLength);
|
||||
|
||||
// Then copy the rest into this one
|
||||
memcpy(lastBuffer->data + lastBuffer->dataLength, src, copyLength);
|
||||
lastBuffer->dataLength += copyLength;
|
||||
lastBuffer->bytesLeft += copyLength;
|
||||
// Done - now append the new entry to the chain
|
||||
last->next = nextBuffer;
|
||||
last = nextBuffer->last;
|
||||
for(OutputBuffer *item = Next(); item != nextBuffer; item = item->Next())
|
||||
{
|
||||
item->last = last;
|
||||
}
|
||||
return bytesCopied;
|
||||
}
|
||||
|
||||
// No - reuse this one instead
|
||||
memcpy(lastBuffer->data + lastBuffer->dataLength, src, len);
|
||||
lastBuffer->dataLength += len;
|
||||
lastBuffer->bytesLeft += len;
|
||||
// No more data had to be written, we could store everything
|
||||
return len;
|
||||
}
|
||||
|
||||
|
@ -269,7 +275,7 @@ size_t OutputBuffer::cat(StringRef &str)
|
|||
}
|
||||
|
||||
// Encode a string in JSON format and append it to a string buffer and return the number of bytes written
|
||||
size_t OutputBuffer::EncodeString(const char *src, uint16_t srcLength, bool allowControlChars, bool encapsulateString)
|
||||
size_t OutputBuffer::EncodeString(const char *src, size_t srcLength, bool allowControlChars, bool encapsulateString)
|
||||
{
|
||||
size_t bytesWritten = 0;
|
||||
if (encapsulateString)
|
||||
|
@ -356,6 +362,7 @@ size_t OutputBuffer::EncodeReply(OutputBuffer *src, bool allowControlChars)
|
|||
|
||||
if (freeOutputBuffers == nullptr)
|
||||
{
|
||||
reprap.GetPlatform()->RecordError(ErrorCode::OutputStarvation);
|
||||
cpu_irq_restore(flags);
|
||||
|
||||
buf = nullptr;
|
||||
|
@ -384,57 +391,57 @@ size_t OutputBuffer::EncodeReply(OutputBuffer *src, bool allowControlChars)
|
|||
}
|
||||
|
||||
buf->next = nullptr;
|
||||
buf->dataLength = buf->bytesLeft = 0;
|
||||
buf->last = buf;
|
||||
buf->dataLength = buf->bytesRead = 0;
|
||||
buf->references = 1; // Assume it's only used once by default
|
||||
buf->isReferenced = false;
|
||||
|
||||
cpu_irq_restore(flags);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
// Get the number of bytes left for continuous writing
|
||||
/*static*/ size_t OutputBuffer::GetBytesLeft(const OutputBuffer *writingBuffer)
|
||||
{
|
||||
// If writingBuffer is NULL, just return how much space there is left for everything
|
||||
// If writingBuffer is NULL, just return how much space there is left for continuous writing
|
||||
if (writingBuffer == nullptr)
|
||||
{
|
||||
return (OUTPUT_BUFFER_COUNT - usedOutputBuffers) * OUTPUT_BUFFER_SIZE;
|
||||
}
|
||||
if (usedOutputBuffers == OUTPUT_BUFFER_COUNT)
|
||||
{
|
||||
// No more instances can be allocated
|
||||
return 0;
|
||||
}
|
||||
|
||||
// Otherwise get the last entry from the chain
|
||||
const OutputBuffer *lastBuffer = writingBuffer;
|
||||
while (lastBuffer->Next() != nullptr)
|
||||
{
|
||||
lastBuffer = lastBuffer->Next();
|
||||
return (OUTPUT_BUFFER_COUNT - usedOutputBuffers - 1) * OUTPUT_BUFFER_SIZE;
|
||||
}
|
||||
|
||||
// Do we have any more buffers left for writing?
|
||||
if (usedOutputBuffers >= OUTPUT_BUFFER_COUNT)
|
||||
if (usedOutputBuffers == OUTPUT_BUFFER_COUNT)
|
||||
{
|
||||
// No - refer to this one only
|
||||
return OUTPUT_BUFFER_SIZE - lastBuffer->DataLength();
|
||||
return OUTPUT_BUFFER_SIZE - writingBuffer->last->DataLength();
|
||||
}
|
||||
|
||||
// Yes - we know how many buffers are in use, so there is no need to work through the free list
|
||||
return (OUTPUT_BUFFER_SIZE - lastBuffer->DataLength() + (OUTPUT_BUFFER_COUNT - usedOutputBuffers - 1) * OUTPUT_BUFFER_SIZE);
|
||||
return (OUTPUT_BUFFER_SIZE - writingBuffer->last->DataLength() + (OUTPUT_BUFFER_COUNT - usedOutputBuffers - 1) * OUTPUT_BUFFER_SIZE);
|
||||
}
|
||||
|
||||
|
||||
// Truncate an output buffer to free up more memory. Returns the number of released bytes.
|
||||
/*static */ size_t OutputBuffer::Truncate(OutputBuffer *buffer, size_t bytesNeeded)
|
||||
{
|
||||
// Can we free up space from this entry?
|
||||
// Can we free up space from this chain?
|
||||
if (buffer == nullptr || buffer->Next() == nullptr)
|
||||
{
|
||||
// No
|
||||
return 0;
|
||||
}
|
||||
|
||||
// Yes - free up the last entry (entries) from this chain
|
||||
size_t releasedBytes = OUTPUT_BUFFER_SIZE;
|
||||
// Yes - free up the last entries
|
||||
size_t releasedBytes = 0;
|
||||
OutputBuffer *previousItem;
|
||||
do {
|
||||
// Get the last entry from the chain
|
||||
// Get two the last entries from the chain
|
||||
previousItem = buffer;
|
||||
OutputBuffer *lastItem = previousItem->Next();
|
||||
while (lastItem->Next() != nullptr)
|
||||
|
@ -443,24 +450,18 @@ size_t OutputBuffer::EncodeReply(OutputBuffer *src, bool allowControlChars)
|
|||
lastItem = lastItem->Next();
|
||||
}
|
||||
|
||||
// Unlink and free it
|
||||
// Unlink and free the last entry
|
||||
previousItem->next = nullptr;
|
||||
Release(lastItem);
|
||||
releasedBytes += OUTPUT_BUFFER_SIZE;
|
||||
} while (previousItem != buffer && releasedBytes < bytesNeeded);
|
||||
|
||||
return releasedBytes;
|
||||
}
|
||||
|
||||
/*static*/ void OutputBuffer::Replace(OutputBuffer *&destination, OutputBuffer *source)
|
||||
{
|
||||
OutputBuffer *temp = destination;
|
||||
while (temp != nullptr)
|
||||
// Update all the references to the last item
|
||||
for(OutputBuffer *item = buffer; item != nullptr; item = item->Next())
|
||||
{
|
||||
temp = Release(temp);
|
||||
item->last = previousItem;
|
||||
}
|
||||
|
||||
destination = source;
|
||||
return releasedBytes;
|
||||
}
|
||||
|
||||
// Releases an output buffer instance and returns the next entry from the chain
|
||||
|
@ -473,7 +474,7 @@ size_t OutputBuffer::EncodeReply(OutputBuffer *src, bool allowControlChars)
|
|||
if (buf->references > 1)
|
||||
{
|
||||
buf->references--;
|
||||
buf->bytesLeft = buf->dataLength;
|
||||
buf->bytesRead = 0;
|
||||
cpu_irq_restore(flags);
|
||||
return nextBuffer;
|
||||
}
|
||||
|
@ -501,9 +502,140 @@ size_t OutputBuffer::EncodeReply(OutputBuffer *src, bool allowControlChars)
|
|||
usedOutputBuffers, OUTPUT_BUFFER_COUNT, maxUsedOutputBuffers);
|
||||
}
|
||||
|
||||
// End
|
||||
//*************************************************************************************************
|
||||
// OutputStack class implementation
|
||||
|
||||
// Push an OutputBuffer chain to the stack
|
||||
void OutputStack::Push(OutputBuffer *buffer)
|
||||
{
|
||||
if (count == OUTPUT_STACK_DEPTH)
|
||||
{
|
||||
OutputBuffer::ReleaseAll(buffer);
|
||||
reprap.GetPlatform()->RecordError(ErrorCode::OutputStackOverflow);
|
||||
return;
|
||||
}
|
||||
|
||||
if (buffer != nullptr)
|
||||
{
|
||||
const irqflags_t flags = cpu_irq_save();
|
||||
items[count++] = buffer;
|
||||
cpu_irq_restore(flags);
|
||||
}
|
||||
}
|
||||
|
||||
// Pop an OutputBuffer chain or return NULL if none is available
|
||||
OutputBuffer *OutputStack::Pop()
|
||||
{
|
||||
if (count == 0)
|
||||
{
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
const irqflags_t flags = cpu_irq_save();
|
||||
OutputBuffer *item = items[0];
|
||||
for(size_t i = 1; i < count; i++)
|
||||
{
|
||||
items[i - 1] = items[i];
|
||||
}
|
||||
count--;
|
||||
cpu_irq_restore(flags);
|
||||
|
||||
return item;
|
||||
}
|
||||
|
||||
// Returns the first item from the stack or NULL if none is available
|
||||
OutputBuffer *OutputStack::GetFirstItem() const
|
||||
{
|
||||
if (count == 0)
|
||||
{
|
||||
return nullptr;
|
||||
}
|
||||
return items[0];
|
||||
}
|
||||
|
||||
// Set the first item of the stack. If it's NULL, then the first item will be removed
|
||||
void OutputStack::SetFirstItem(OutputBuffer *buffer)
|
||||
{
|
||||
const irqflags_t flags = cpu_irq_save();
|
||||
if (buffer == nullptr)
|
||||
{
|
||||
// If buffer is NULL, then the first item is removed from the stack
|
||||
for(size_t i = 1; i < count; i++)
|
||||
{
|
||||
items[i - 1] = items[i];
|
||||
}
|
||||
count--;
|
||||
}
|
||||
else
|
||||
{
|
||||
// Else only the first item is updated
|
||||
items[0] = buffer;
|
||||
}
|
||||
cpu_irq_restore(flags);
|
||||
}
|
||||
|
||||
// Returns the last item from the stack or NULL if none is available
|
||||
OutputBuffer *OutputStack::GetLastItem() const
|
||||
{
|
||||
if (count == 0)
|
||||
{
|
||||
return nullptr;
|
||||
}
|
||||
return items[count - 1];
|
||||
}
|
||||
|
||||
// Get the total length of all queued buffers
|
||||
size_t OutputStack::DataLength() const
|
||||
{
|
||||
size_t totalLength = 0;
|
||||
|
||||
const irqflags_t flags = cpu_irq_save();
|
||||
for(size_t i = 0; i < count; i++)
|
||||
{
|
||||
totalLength += items[i]->Length();
|
||||
}
|
||||
cpu_irq_restore(flags);
|
||||
|
||||
return totalLength;
|
||||
}
|
||||
|
||||
// Append another OutputStack to this instance. If no more space is available,
|
||||
// all OutputBuffers that can't be added are automatically released
|
||||
void OutputStack::Append(OutputStack *stack)
|
||||
{
|
||||
for(size_t i = 0; i < stack->count; i++)
|
||||
{
|
||||
if (count < OUTPUT_STACK_DEPTH)
|
||||
{
|
||||
items[count++] = stack->items[i];
|
||||
}
|
||||
else
|
||||
{
|
||||
reprap.GetPlatform()->RecordError(ErrorCode::OutputStackOverflow);
|
||||
OutputBuffer::ReleaseAll(stack->items[i]);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Increase the number of references for each OutputBuffer on the stack
|
||||
void OutputStack::IncreaseReferences(size_t num)
|
||||
{
|
||||
const irqflags_t flags = cpu_irq_save();
|
||||
for(size_t i = 0; i < count; i++)
|
||||
{
|
||||
items[i]->IncreaseReferences(num);
|
||||
}
|
||||
cpu_irq_restore(flags);
|
||||
}
|
||||
|
||||
// Release all buffers and clean up
|
||||
void OutputStack::ReleaseAll()
|
||||
{
|
||||
for(size_t i = 0; i < count; i++)
|
||||
{
|
||||
OutputBuffer::ReleaseAll(items[i]);
|
||||
}
|
||||
count = 0;
|
||||
}
|
||||
|
||||
// vim: ts=4:sw=4
|
142
OutputMemory.h
Normal file
142
OutputMemory.h
Normal file
|
@ -0,0 +1,142 @@
|
|||
/*
|
||||
* OutputMemory.h
|
||||
*
|
||||
* Created on: 10 Jan 2016
|
||||
* Authors: David and Christian
|
||||
*/
|
||||
|
||||
#ifndef OUTPUTMEMORY_H_
|
||||
#define OUTPUTMEMORY_H_
|
||||
|
||||
#include "Arduino.h"
|
||||
#include "Configuration.h"
|
||||
#include "StringRef.h"
|
||||
|
||||
const size_t OUTPUT_STACK_DEPTH = 4; // Number of OutputBuffer chains that can be pushed onto one stack instance
|
||||
|
||||
class OutputStack;
|
||||
|
||||
// This class is used to hold data for sending (either for Serial or Network destinations)
|
||||
class OutputBuffer
|
||||
{
|
||||
public:
|
||||
friend class OutputStack;
|
||||
|
||||
OutputBuffer(OutputBuffer *n) : next(n) { }
|
||||
|
||||
void Append(OutputBuffer *other);
|
||||
OutputBuffer *Next() const { return next; }
|
||||
bool IsReferenced() const { return isReferenced; }
|
||||
void IncreaseReferences(size_t refs);
|
||||
|
||||
const char *Data() const { return data; }
|
||||
size_t DataLength() const { return dataLength; } // How many bytes have been written to this instance?
|
||||
size_t Length() const; // How many bytes have been written to the whole chain?
|
||||
|
||||
char& operator[](size_t index);
|
||||
char operator[](size_t index) const;
|
||||
const char *Read(size_t len);
|
||||
size_t BytesLeft() const { return dataLength - bytesRead; } // How many bytes have not been sent yet?
|
||||
|
||||
int printf(const char *fmt, ...);
|
||||
int vprintf(const char *fmt, va_list vargs);
|
||||
int catf(const char *fmt, ...);
|
||||
|
||||
size_t copy(const char c);
|
||||
size_t copy(const char *src);
|
||||
size_t copy(const char *src, size_t len);
|
||||
|
||||
size_t cat(const char c);
|
||||
size_t cat(const char *src);
|
||||
size_t cat(const char *src, size_t len);
|
||||
size_t cat(StringRef &str);
|
||||
|
||||
size_t EncodeString(const char *src, size_t srcLength, bool allowControlChars, bool encapsulateString = true);
|
||||
size_t EncodeReply(OutputBuffer *src, bool allowControlChars);
|
||||
|
||||
// Initialise the output buffers manager
|
||||
static void Init();
|
||||
|
||||
// Allocate an unused OutputBuffer instance. Returns true on success or false if no instance could be allocated.
|
||||
// Setting isAppending to true will guarantee that one OutputBuffer will remain available for single allocation.
|
||||
static bool Allocate(OutputBuffer *&buf, bool isAppending = false);
|
||||
|
||||
// Get the number of bytes left for allocation. If writingBuffer is not NULL, this returns the number of free bytes for
|
||||
// continuous writes, i.e. for writes that need to allocate an extra OutputBuffer instance to finish the message.
|
||||
static size_t GetBytesLeft(const OutputBuffer *writingBuffer);
|
||||
|
||||
// Truncate an OutputBuffer instance to free up more memory. Returns the number of released bytes.
|
||||
static size_t Truncate(OutputBuffer *buffer, size_t bytesNeeded);
|
||||
|
||||
// Release one OutputBuffer instance. Returns the next item from the chain or nullptr if this was the last instance.
|
||||
static OutputBuffer *Release(OutputBuffer *buf);
|
||||
|
||||
// Release all OutputBuffer objects in a chain
|
||||
static void ReleaseAll(OutputBuffer *buf);
|
||||
|
||||
static void Diagnostics();
|
||||
|
||||
private:
|
||||
|
||||
OutputBuffer *next;
|
||||
OutputBuffer *last;
|
||||
|
||||
char data[OUTPUT_BUFFER_SIZE];
|
||||
size_t dataLength, bytesRead;
|
||||
|
||||
bool isReferenced;
|
||||
size_t references;
|
||||
|
||||
static OutputBuffer * volatile freeOutputBuffers; // Messages may also be sent by ISRs,
|
||||
static volatile size_t usedOutputBuffers; // so make these volatile.
|
||||
static volatile size_t maxUsedOutputBuffers;
|
||||
};
|
||||
|
||||
// This class is used to manage references to OutputBuffer chains for all output destinations
|
||||
class OutputStack
|
||||
{
|
||||
public:
|
||||
OutputStack() : count(0) { }
|
||||
|
||||
// Is there anything on this stack?
|
||||
bool IsEmpty() const { return count == 0; }
|
||||
|
||||
// Clear the reference list
|
||||
void Clear() { count = 0; }
|
||||
|
||||
// Push an OutputBuffer chain
|
||||
void Push(OutputBuffer *buffer);
|
||||
|
||||
// Pop an OutputBuffer chain or return NULL if none is available
|
||||
OutputBuffer *Pop();
|
||||
|
||||
// Returns the first item from the stack or NULL if none is available
|
||||
OutputBuffer *GetFirstItem() const;
|
||||
|
||||
// Set the first item of the stack. If it's NULL, then the first item will be removed
|
||||
void SetFirstItem(OutputBuffer *buffer);
|
||||
|
||||
// Returns the last item from the stack or NULL if none is available
|
||||
OutputBuffer *GetLastItem() const;
|
||||
|
||||
// Get the total length of all queued buffers
|
||||
size_t DataLength() const;
|
||||
|
||||
// Append another OutputStack to this instance. If no more space is available,
|
||||
// all OutputBuffers that can't be added are automatically released
|
||||
void Append(OutputStack *stack);
|
||||
|
||||
// Increase the number of references for each OutputBuffer on the stack
|
||||
void IncreaseReferences(size_t num);
|
||||
|
||||
// Release all buffers and clean up
|
||||
void ReleaseAll();
|
||||
|
||||
private:
|
||||
volatile size_t count;
|
||||
OutputBuffer * volatile items[OUTPUT_STACK_DEPTH];
|
||||
};
|
||||
|
||||
#endif /* OUTPUTMEMORY_H_ */
|
||||
|
||||
// vim: ts=4:sw=4
|
19
Pins_duet.h
19
Pins_duet.h
|
@ -2,10 +2,10 @@
|
|||
#define PINS_DUET_H__
|
||||
|
||||
// What are we supposed to be running on
|
||||
#define ELECTRONICS "Duet (+ Extension)"
|
||||
|
||||
// Default board type
|
||||
#define DEFAULT_BOARD_TYPE BoardType::Duet_06
|
||||
#define ELECTRONICS "Duet (+ Extension)"
|
||||
|
||||
// The physical capabilities of the machine
|
||||
|
||||
|
@ -26,7 +26,7 @@ const size_t NUM_SERIAL_CHANNELS = 3; // The number of serial IO channels (USB
|
|||
// DRIVES
|
||||
|
||||
const Pin ENABLE_PINS[DRIVES] = { 29, 27, X1, X0, 37, X8, 50, 47, X13 };
|
||||
const bool ENABLE_VALUES[DRIVES] = { false, false, false, false, false, false, false, false, false }; // what to send to enable a drive
|
||||
const bool ENABLE_VALUES[DRIVES] = { false, false, false, false, false, false, false, false, false }; // What to send to enable a drive
|
||||
const Pin STEP_PINS[DRIVES] = { 14, 25, 5, X2, 41, 39, X4, 49, X10 };
|
||||
const Pin DIRECTION_PINS[DRIVES] = { 15, 26, 4, X3, 35, 53, 51, 48, X11 };
|
||||
const bool DIRECTIONS[DRIVES] = { BACKWARDS, FORWARDS, FORWARDS, FORWARDS, FORWARDS, FORWARDS, FORWARDS, FORWARDS, FORWARDS }; // What each axis needs to make it go forwards - defaults
|
||||
|
@ -40,6 +40,7 @@ const uint8_t POT_WIPES[8] = { 1, 3, 2, 0, 1, 3, 2, 0 };
|
|||
const float SENSE_RESISTOR = 0.1; // Stepper motor current sense resistor
|
||||
const float MAX_STEPPER_DIGIPOT_VOLTAGE = (3.3 * 2.5 / (2.7 + 2.5)); // Stepper motor current reference voltage
|
||||
const float MAX_STEPPER_DAC_VOLTAGE = 2.12; // Stepper motor current reference voltage for E1 if using a DAC
|
||||
const int DAC0_DIGITAL_PIN = 66; // Arduino Due pin number corresponding to DAC0 output pin
|
||||
|
||||
// HEATERS
|
||||
|
||||
|
@ -67,7 +68,7 @@ const size_t MAX31855_DEVICES = 4;
|
|||
const Pin MAX31855_CS_PINS[MAX31855_DEVICES] = { 16, 17, 18, 19 };
|
||||
|
||||
// Arduino Due pin number that controls the ATX power on/off
|
||||
const Pin atxPowerPin = 12; // Arduino Due pin number that controls the ATX power on/off
|
||||
const Pin ATX_POWER_PIN = 12; // Arduino Due pin number that controls the ATX power on/off
|
||||
|
||||
// Analogue pin numbers
|
||||
const Pin Z_PROBE_PIN = 10; // Analogue pin number
|
||||
|
@ -82,6 +83,18 @@ const size_t NUM_FANS = 2;
|
|||
const Pin COOLING_FAN_PINS[NUM_FANS] = { X6, X17 }; // Pin D34 is PWM capable but not an Arduino PWM pin - use X6 instead
|
||||
const Pin COOLING_FAN_RPM_PIN = 23; // Pin PA15
|
||||
|
||||
// INKJET CONTROL PINS
|
||||
|
||||
const Pin INKJET_SERIAL_OUT = 65; // Serial bitpattern into the shift register
|
||||
const Pin INKJET_SHIFT_CLOCK = 20; // Shift the register
|
||||
const Pin INKJET_STORAGE_CLOCK = 67; // Put the pattern in the output register
|
||||
const Pin INKJET_OUTPUT_ENABLE = 66; // Make the output visible
|
||||
const Pin INKJET_CLEAR = 36; // Clear the register to 0
|
||||
|
||||
// Roland mill
|
||||
const int8_t ROLAND_RTS_PIN = 77; // Expansion pin 27, SPI0_NPCS0
|
||||
const int8_t ROLAND_CTS_PIN = 87; // Expansion pin 26, SPI0_NPCS1
|
||||
|
||||
// Definition of which pins we allow to be controlled using M42
|
||||
//
|
||||
// The allowed pins are these ones on the DueX4 expansion connector:
|
||||
|
|
122
Platform.cpp
122
Platform.cpp
|
@ -109,10 +109,14 @@ bool PidParameters::operator==(const PidParameters& other) const
|
|||
|
||||
Platform::Platform() :
|
||||
autoSaveEnabled(false), board(DEFAULT_BOARD_TYPE), active(false), errorCodeBits(0),
|
||||
auxOutputBuffer(nullptr), aux2OutputBuffer(nullptr), usbOutputBuffer(nullptr),
|
||||
fileStructureInitialised(false), tickState(0), debugCode(0),
|
||||
messageString(messageStringBuffer, ARRAY_SIZE(messageStringBuffer))
|
||||
{
|
||||
// Output
|
||||
auxOutput = new OutputStack();
|
||||
aux2Output = new OutputStack();
|
||||
usbOutput = new OutputStack();
|
||||
|
||||
// Files
|
||||
|
||||
massStorage = new MassStorage(this);
|
||||
|
@ -128,14 +132,14 @@ Platform::Platform() :
|
|||
void Platform::Init()
|
||||
{
|
||||
// Deal with power first
|
||||
digitalWriteNonDue(atxPowerPin, LOW); // ensure ATX power is off by default
|
||||
pinModeNonDue(atxPowerPin, OUTPUT);
|
||||
digitalWriteNonDue(ATX_POWER_PIN, LOW); // ensure ATX power is off by default
|
||||
pinModeNonDue(ATX_POWER_PIN, OUTPUT);
|
||||
|
||||
SetBoardType(BoardType::Auto);
|
||||
|
||||
// Comms
|
||||
|
||||
baudRates[0] = USB_BAUD_RATE;
|
||||
baudRates[0] = MAIN_BAUD_RATE;
|
||||
baudRates[1] = AUX_BAUD_RATE;
|
||||
baudRates[2] = AUX2_BAUD_RATE;
|
||||
commsParams[0] = 0;
|
||||
|
@ -726,6 +730,7 @@ void Platform::Spin()
|
|||
return;
|
||||
|
||||
// Write non-blocking data to the AUX line
|
||||
OutputBuffer *auxOutputBuffer = auxOutput->GetFirstItem();
|
||||
if (auxOutputBuffer != nullptr)
|
||||
{
|
||||
size_t bytesToWrite = min<size_t>(SERIAL_AUX_DEVICE.canWrite(), auxOutputBuffer->BytesLeft());
|
||||
|
@ -737,10 +742,12 @@ void Platform::Spin()
|
|||
if (auxOutputBuffer->BytesLeft() == 0)
|
||||
{
|
||||
auxOutputBuffer = OutputBuffer::Release(auxOutputBuffer);
|
||||
auxOutput->SetFirstItem(auxOutputBuffer);
|
||||
}
|
||||
}
|
||||
|
||||
// Write non-blocking data to the second AUX line
|
||||
OutputBuffer *aux2OutputBuffer = aux2Output->GetFirstItem();
|
||||
if (aux2OutputBuffer != nullptr)
|
||||
{
|
||||
size_t bytesToWrite = min<size_t>(SERIAL_AUX2_DEVICE.canWrite(), aux2OutputBuffer->BytesLeft());
|
||||
|
@ -752,18 +759,19 @@ void Platform::Spin()
|
|||
if (aux2OutputBuffer->BytesLeft() == 0)
|
||||
{
|
||||
aux2OutputBuffer = OutputBuffer::Release(aux2OutputBuffer);
|
||||
aux2Output->SetFirstItem(aux2OutputBuffer);
|
||||
}
|
||||
}
|
||||
|
||||
// Write non-blocking data to the USB line
|
||||
OutputBuffer *usbOutputBuffer = usbOutput->GetFirstItem();
|
||||
if (usbOutputBuffer != nullptr)
|
||||
{
|
||||
if (!SERIAL_MAIN_DEVICE)
|
||||
{
|
||||
// If the USB port is not opened, free the data left for writing
|
||||
OutputBuffer *buffer = usbOutputBuffer;
|
||||
usbOutputBuffer = nullptr;
|
||||
OutputBuffer::ReleaseAll(buffer);
|
||||
OutputBuffer::ReleaseAll(usbOutputBuffer);
|
||||
usbOutput->SetFirstItem(nullptr);
|
||||
}
|
||||
else
|
||||
{
|
||||
|
@ -777,6 +785,7 @@ void Platform::Spin()
|
|||
if (usbOutputBuffer->BytesLeft() == 0)
|
||||
{
|
||||
usbOutputBuffer = OutputBuffer::Release(usbOutputBuffer);
|
||||
usbOutput->SetFirstItem(usbOutputBuffer);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -1657,23 +1666,32 @@ void Platform::Message(MessageType type, const char *message)
|
|||
|
||||
case AUX_MESSAGE:
|
||||
// Message that is to be sent to the first auxiliary device
|
||||
if (auxOutputBuffer != nullptr)
|
||||
if (!auxOutput->IsEmpty())
|
||||
{
|
||||
// If we're still busy sending a response to the UART device, append this message to the output buffer
|
||||
auxOutputBuffer->cat(message);
|
||||
auxOutput->GetLastItem()->cat(message);
|
||||
}
|
||||
else
|
||||
{
|
||||
// Send the beep command to the aux channel. There is no flow control on this port, so it can't block for long.
|
||||
Serial.write(message);
|
||||
Serial.flush();
|
||||
// Send short strings immediately through the aux channel. There is no flow control on this port, so it can't block for long
|
||||
SERIAL_AUX_DEVICE.write(message);
|
||||
SERIAL_AUX_DEVICE.flush();
|
||||
}
|
||||
break;
|
||||
|
||||
case AUX2_MESSAGE:
|
||||
// Message that is to be sent to the second auxiliary device (blocking)
|
||||
Serial1.write(message);
|
||||
Serial1.flush();
|
||||
if (!aux2Output->IsEmpty())
|
||||
{
|
||||
// If we're still busy sending a response to the USART device, append this message to the output buffer
|
||||
aux2Output->GetLastItem()->cat(message);
|
||||
}
|
||||
else
|
||||
{
|
||||
// Send short strings immediately through the aux channel. There is no flow control on this port, so it can't block for long
|
||||
SERIAL_AUX2_DEVICE.write(message);
|
||||
SERIAL_AUX2_DEVICE.flush();
|
||||
}
|
||||
break;
|
||||
|
||||
case DISPLAY_MESSAGE:
|
||||
|
@ -1689,21 +1707,20 @@ void Platform::Message(MessageType type, const char *message)
|
|||
|
||||
case HOST_MESSAGE:
|
||||
// Message that is to be sent via the USB line (non-blocking)
|
||||
//
|
||||
// Ensure we have a valid buffer to write to
|
||||
if (usbOutputBuffer == nullptr)
|
||||
{
|
||||
OutputBuffer *buffer;
|
||||
if (!OutputBuffer::Allocate(buffer))
|
||||
// Ensure we have a valid buffer to write to that isn't referenced for other destinations
|
||||
OutputBuffer *usbOutputBuffer = usbOutput->GetLastItem();
|
||||
if (usbOutputBuffer == nullptr || usbOutputBuffer->IsReferenced())
|
||||
{
|
||||
// Should never happen
|
||||
return;
|
||||
if (!OutputBuffer::Allocate(usbOutputBuffer))
|
||||
{
|
||||
// Should never happen
|
||||
return;
|
||||
}
|
||||
usbOutput->Push(usbOutputBuffer);
|
||||
}
|
||||
usbOutputBuffer = buffer;
|
||||
}
|
||||
|
||||
// Check if we need to write the indentation chars first
|
||||
{
|
||||
// Check if we need to write the indentation chars first
|
||||
const size_t stackPointer = reprap.GetGCodes()->GetStackPointer();
|
||||
if (stackPointer > 0)
|
||||
{
|
||||
|
@ -1715,13 +1732,13 @@ void Platform::Message(MessageType type, const char *message)
|
|||
}
|
||||
indentation[stackPointer * 2] = 0;
|
||||
|
||||
// Append the indentation string to our chain, or allocate a new buffer if there is none
|
||||
// Append the indentation string
|
||||
usbOutputBuffer->cat(indentation);
|
||||
}
|
||||
}
|
||||
|
||||
// Append the message string to the output buffer chain
|
||||
usbOutputBuffer->cat(message);
|
||||
// Append the message string
|
||||
usbOutputBuffer->cat(message);
|
||||
}
|
||||
break;
|
||||
|
||||
case HTTP_MESSAGE:
|
||||
|
@ -1736,9 +1753,9 @@ void Platform::Message(MessageType type, const char *message)
|
|||
case GENERIC_MESSAGE:
|
||||
// Message that is to be sent to the web & host. Make this the default one, too.
|
||||
default:
|
||||
Message(HOST_MESSAGE, message);
|
||||
Message(HTTP_MESSAGE, message);
|
||||
Message(TELNET_MESSAGE, message);
|
||||
Message(HOST_MESSAGE, message);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
@ -1761,26 +1778,12 @@ void Platform::Message(const MessageType type, OutputBuffer *buffer)
|
|||
}
|
||||
|
||||
// For big responses it makes sense to write big chunks of data in portions. Store this data here
|
||||
if (auxOutputBuffer == nullptr)
|
||||
{
|
||||
auxOutputBuffer = buffer;
|
||||
}
|
||||
else
|
||||
{
|
||||
auxOutputBuffer->Append(buffer);
|
||||
}
|
||||
auxOutput->Push(buffer);
|
||||
break;
|
||||
|
||||
case AUX2_MESSAGE:
|
||||
// Send this message to the second UART device
|
||||
if (aux2OutputBuffer == nullptr)
|
||||
{
|
||||
aux2OutputBuffer = buffer;
|
||||
}
|
||||
else
|
||||
{
|
||||
aux2OutputBuffer->Append(buffer);
|
||||
}
|
||||
aux2Output->Push(buffer);
|
||||
break;
|
||||
|
||||
case DEBUG_MESSAGE:
|
||||
|
@ -1795,22 +1798,15 @@ void Platform::Message(const MessageType type, OutputBuffer *buffer)
|
|||
break;
|
||||
|
||||
case HOST_MESSAGE:
|
||||
// If the serial USB line is not open, discard its content right away
|
||||
if (!SERIAL_MAIN_DEVICE)
|
||||
{
|
||||
// If the serial USB line is not open, discard the message right away
|
||||
OutputBuffer::ReleaseAll(buffer);
|
||||
}
|
||||
else
|
||||
{
|
||||
// Append incoming data to the list of our output buffers
|
||||
if (usbOutputBuffer == nullptr)
|
||||
{
|
||||
usbOutputBuffer = buffer;
|
||||
}
|
||||
else
|
||||
{
|
||||
usbOutputBuffer->Append(buffer);
|
||||
}
|
||||
// Else append incoming data to the stack
|
||||
usbOutput->Push(buffer);
|
||||
}
|
||||
break;
|
||||
|
||||
|
@ -1826,15 +1822,15 @@ void Platform::Message(const MessageType type, OutputBuffer *buffer)
|
|||
case GENERIC_MESSAGE:
|
||||
// Message that is to be sent to the web & host.
|
||||
buffer->IncreaseReferences(2); // This one is handled by two additional destinations
|
||||
Message(HOST_MESSAGE, buffer);
|
||||
Message(HTTP_MESSAGE, buffer);
|
||||
Message(TELNET_MESSAGE, buffer);
|
||||
Message(HOST_MESSAGE, buffer);
|
||||
break;
|
||||
|
||||
default:
|
||||
// Everything else is unsupported (and probably not used)
|
||||
MessageF(HOST_MESSAGE, "Warning: Unsupported Message call for type %u!\n", type);
|
||||
OutputBuffer::ReleaseAll(buffer);
|
||||
MessageF(HOST_MESSAGE, "Warning: Unsupported Message call for type %u!\n", type);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
@ -1863,20 +1859,20 @@ void Platform::MessageF(MessageType type, const char *fmt, ...)
|
|||
|
||||
bool Platform::AtxPower() const
|
||||
{
|
||||
return (digitalReadNonDue(atxPowerPin) == HIGH);
|
||||
return (digitalReadNonDue(ATX_POWER_PIN) == HIGH);
|
||||
}
|
||||
|
||||
void Platform::SetAtxPower(bool on)
|
||||
{
|
||||
digitalWriteNonDue(atxPowerPin, (on) ? HIGH : LOW);
|
||||
digitalWriteNonDue(ATX_POWER_PIN, (on) ? HIGH : LOW);
|
||||
}
|
||||
|
||||
|
||||
void Platform::SetElasticComp(size_t drive, float factor)
|
||||
void Platform::SetElasticComp(size_t extruder, float factor)
|
||||
{
|
||||
if (drive < DRIVES - AXES)
|
||||
if (extruder < DRIVES - AXES)
|
||||
{
|
||||
elasticComp[drive] = factor;
|
||||
elasticComp[extruder] = factor;
|
||||
}
|
||||
}
|
||||
|
||||
|
|
25
Platform.h
25
Platform.h
|
@ -46,6 +46,7 @@ Licence: GPL
|
|||
|
||||
#include "Arduino.h"
|
||||
#include "SamNonDuePin.h"
|
||||
#include "OutputMemory.h"
|
||||
#include "SD_HSMCI.h"
|
||||
#include "MAX31855.h"
|
||||
#include "MCP4461.h"
|
||||
|
@ -82,14 +83,6 @@ const int8_t INKJET_BITS = 12; // How many nozzles? Set to -1 to disable t
|
|||
const int INKJET_FIRE_MICROSECONDS = 5; // How long to fire a nozzle
|
||||
const int INKJET_DELAY_MICROSECONDS = 800; // How long to wait before the next bit
|
||||
|
||||
// Inkjet control pins
|
||||
|
||||
const int8_t INKJET_SERIAL_OUT = 65; // Serial bitpattern into the shift register
|
||||
const int8_t INKJET_SHIFT_CLOCK = 20; // Shift the register
|
||||
const int8_t INKJET_STORAGE_CLOCK = 67; // Put the pattern in the output register
|
||||
const int8_t INKJET_OUTPUT_ENABLE = 66; // Make the output visible
|
||||
const int8_t INKJET_CLEAR = 36; // Clear the register to 0
|
||||
|
||||
const float MAX_FEEDRATES[DRIVES] = DRIVES_(100.0, 100.0, 3.0, 20.0, 20.0, 20.0, 20.0, 20.0, 20.0); // mm/sec
|
||||
const float ACCELERATIONS[DRIVES] = DRIVES_(500.0, 500.0, 20.0, 250.0, 250.0, 250.0, 250.0, 250.0, 250.0); // mm/sec^2
|
||||
const float DRIVE_STEPS_PER_UNIT[DRIVES] = DRIVES_(87.4890, 87.4890, 4000.0, 420.0, 420.0, 420.0, 420.0, 420.0, 420.0); // steps/mm
|
||||
|
@ -391,7 +384,9 @@ typedef AveragingFilter<Z_PROBE_AVERAGE_READINGS> ZProbeAveragingFilter;
|
|||
enum class ErrorCode : uint32_t
|
||||
{
|
||||
BadTemp = 1 << 0,
|
||||
BadMove = 1 << 1
|
||||
BadMove = 1 << 1,
|
||||
OutputStarvation = 1 << 2,
|
||||
OutputStackOverflow = 1 << 3
|
||||
};
|
||||
|
||||
// Different types of hardware-related input-output
|
||||
|
@ -610,6 +605,12 @@ public:
|
|||
float GetNozzleDiameter() const;
|
||||
void SetNozzleDiameter(float diameter);
|
||||
|
||||
// Fire the inkjet (if any) in the given pattern
|
||||
// If there is no inkjet false is returned; if there is one this returns true
|
||||
// So you can test for inkjet presence with if(platform->Inkjet(0))
|
||||
|
||||
bool Inkjet(int bitPattern);
|
||||
|
||||
// Direct pin operations
|
||||
bool SetPin(int pin, int level);
|
||||
|
||||
|
@ -772,9 +773,9 @@ private:
|
|||
|
||||
uint32_t baudRates[NUM_SERIAL_CHANNELS];
|
||||
uint8_t commsParams[NUM_SERIAL_CHANNELS];
|
||||
OutputBuffer * volatile auxOutputBuffer;
|
||||
OutputBuffer * volatile aux2OutputBuffer;
|
||||
OutputBuffer * volatile usbOutputBuffer;
|
||||
OutputStack *auxOutput;
|
||||
OutputStack *aux2Output;
|
||||
OutputStack *usbOutput;
|
||||
|
||||
// Files
|
||||
|
||||
|
|
|
@ -715,9 +715,8 @@ float PrintMonitor::EstimateTimeLeft(PrintEstimationMethod method) const
|
|||
{
|
||||
case fileBased:
|
||||
{
|
||||
const float fractionPrinted = gCodes->FractionOfFilePrinted();
|
||||
|
||||
// Provide rough estimation only if we haven't collected at least 2 layer samples
|
||||
const float fractionPrinted = gCodes->FractionOfFilePrinted();
|
||||
if (numLayerSamples < 2 || !printingFileParsed || printingFileInfo.objectHeight == 0.0)
|
||||
{
|
||||
return (fractionPrinted < 0.01)
|
||||
|
|
|
@ -25,7 +25,7 @@ const FilePosition GCODE_FOOTER_SIZE = 128000uL; // How many bytes to read from
|
|||
const size_t GCODE_READ_SIZE = 1024; // How many bytes to read in one go in GetFileInfo() (should be a multiple of 4 for read efficiency)
|
||||
const size_t GCODE_OVERLAP_SIZE = 100; // Size of the overlapping buffer for searching (should be a multple of 4 as well)
|
||||
|
||||
const float LAYER_HEIGHT_TOLERANCE = 0.025; // For comparing two Z heights (in mm)
|
||||
const float LAYER_HEIGHT_TOLERANCE = 0.025; // Tolerance for comparing two Z heights (in mm)
|
||||
|
||||
const size_t MAX_LAYER_SAMPLES = 5; // Number of layer samples for end-time estimation (except for first layer)
|
||||
const float ESTIMATION_MIN_FILAMENT_USAGE = 0.01; // Minimum per cent of filament to be printed before the filament-based estimation returns values
|
||||
|
|
Binary file not shown.
|
@ -84,7 +84,7 @@ int StringContains(const char* string, const char* match);
|
|||
|
||||
extern StringRef scratchString;
|
||||
|
||||
#include "OutputBuffer.h"
|
||||
#include "OutputMemory.h"
|
||||
#include "Network.h"
|
||||
#include "Platform.h"
|
||||
#include "Webserver.h"
|
||||
|
|
63
Reprap.cpp
63
Reprap.cpp
|
@ -24,7 +24,7 @@ void RepRap::Init()
|
|||
{
|
||||
debug = 0;
|
||||
|
||||
// zpl thinks it's a bad idea to count the bed as an active heater...
|
||||
// chrishamm thinks it's a bad idea to count the bed as an active heater...
|
||||
activeExtruders = activeHeaters = 0;
|
||||
|
||||
SetPassword(DEFAULT_PASSWORD);
|
||||
|
@ -99,13 +99,14 @@ void RepRap::Init()
|
|||
|
||||
void RepRap::Exit()
|
||||
{
|
||||
active = false;
|
||||
heat->Exit();
|
||||
move->Exit();
|
||||
gCodes->Exit();
|
||||
webserver->Exit();
|
||||
platform->Message(GENERIC_MESSAGE, "RepRap class exited.\n");
|
||||
platform->Exit();
|
||||
active = false;
|
||||
heat->Exit();
|
||||
move->Exit();
|
||||
gCodes->Exit();
|
||||
webserver->Exit();
|
||||
network->Exit();
|
||||
platform->Message(GENERIC_MESSAGE, "RepRap class exited.\n");
|
||||
platform->Exit();
|
||||
}
|
||||
|
||||
void RepRap::Spin()
|
||||
|
@ -251,7 +252,7 @@ void RepRap::PrintDebug()
|
|||
if (debug != 0)
|
||||
{
|
||||
platform->Message(GENERIC_MESSAGE, "Debugging enabled for modules:");
|
||||
for (unsigned int i = 0; i < numModules; i++)
|
||||
for (size_t i = 0; i < numModules; i++)
|
||||
{
|
||||
if ((debug & (1 << i)) != 0)
|
||||
{
|
||||
|
@ -259,7 +260,7 @@ void RepRap::PrintDebug()
|
|||
}
|
||||
}
|
||||
platform->Message(GENERIC_MESSAGE, "\nDebugging disabled for modules:");
|
||||
for (unsigned int i = 0; i < numModules; i++)
|
||||
for (size_t i = 0; i < numModules; i++)
|
||||
{
|
||||
if ((debug & (1 << i)) == 0)
|
||||
{
|
||||
|
@ -591,9 +592,18 @@ OutputBuffer *RepRap::GetStatusResponse(uint8_t type, ResponseSource source)
|
|||
response->catf(",\"params\":{\"atxPower\":%d", platform->AtxPower() ? 1 : 0);
|
||||
|
||||
// Cooling fan value
|
||||
//@TODO T3P3 only reports first PWM fan
|
||||
float fanValue = platform->GetFanValue(0);
|
||||
response->catf(",\"fanPercent\":%.2f", fanValue * 100.0);
|
||||
response->cat(",\"fanPercent\":[");
|
||||
for(size_t i = 0; i < NUM_FANS; i++)
|
||||
{
|
||||
if (i == NUM_FANS - 1)
|
||||
{
|
||||
response->catf("%.2f", platform->GetFanValue(i) * 100.0);
|
||||
}
|
||||
else
|
||||
{
|
||||
response->catf("%.2f,", platform->GetFanValue(i) * 100.0);
|
||||
}
|
||||
}
|
||||
|
||||
// Speed and Extrusion factors
|
||||
response->catf(",\"speedFactor\":%.2f,\"extrFactors\":", gCodes->GetSpeedFactor() * 100.0);
|
||||
|
@ -625,10 +635,10 @@ OutputBuffer *RepRap::GetStatusResponse(uint8_t type, ResponseSource source)
|
|||
switch (platform->GetZProbeSecondaryValues(v1, v2))
|
||||
{
|
||||
case 1:
|
||||
response->catf("\"probeValue\":\%d,\"probeSecondary\":[%d]", v0, v1);
|
||||
response->catf("\"probeValue\":%d,\"probeSecondary\":[%d]", v0, v1);
|
||||
break;
|
||||
case 2:
|
||||
response->catf("\"probeValue\":\%d,\"probeSecondary\":[%d,%d]", v0, v1, v2);
|
||||
response->catf("\"probeValue\":%d,\"probeSecondary\":[%d,%d]", v0, v1, v2);
|
||||
break;
|
||||
default:
|
||||
response->catf("\"probeValue\":%d", v0);
|
||||
|
@ -760,7 +770,7 @@ OutputBuffer *RepRap::GetStatusResponse(uint8_t type, ResponseSource source)
|
|||
for(size_t heater=0; heater<tool->HeaterCount(); heater++)
|
||||
{
|
||||
response->catf("%d", tool->Heater(heater));
|
||||
if (heater < tool->HeaterCount() - 1)
|
||||
if (heater + 1 < tool->HeaterCount())
|
||||
{
|
||||
response->cat(",");
|
||||
}
|
||||
|
@ -771,7 +781,7 @@ OutputBuffer *RepRap::GetStatusResponse(uint8_t type, ResponseSource source)
|
|||
for(size_t drive=0; drive<tool->DriveCount(); drive++)
|
||||
{
|
||||
response->catf("%d", tool->Drive(drive));
|
||||
if (drive < tool->DriveCount() - 1)
|
||||
if (drive + 1 < tool->DriveCount())
|
||||
{
|
||||
response->cat(",");
|
||||
}
|
||||
|
@ -988,7 +998,7 @@ OutputBuffer *RepRap::GetConfigResponse()
|
|||
return response;
|
||||
}
|
||||
|
||||
// Get the JSON status response for the web server or M105 command.
|
||||
// Get the JSON status response for PanelDue or the old web server.
|
||||
// Type 0 was the old-style webserver status response, but is no longer supported.
|
||||
// Type 1 is the new-style webserver status response.
|
||||
// Type 2 is the M105 S2 response, which is like the new-style status response but some fields are omitted.
|
||||
|
@ -1195,23 +1205,6 @@ void RepRap::CopyParameterText(const char* src, char *dst, size_t length)
|
|||
dst[i] = 0;
|
||||
}
|
||||
|
||||
// Get just the machine name in JSON format
|
||||
OutputBuffer *RepRap::GetNameResponse()
|
||||
{
|
||||
// Need something to write to...
|
||||
OutputBuffer *response;
|
||||
if (!OutputBuffer::Allocate(response))
|
||||
{
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
response->copy("{\"myName\":");
|
||||
response->EncodeString(myName, ARRAY_SIZE(myName), false);
|
||||
response->cat("}");
|
||||
|
||||
return response;
|
||||
}
|
||||
|
||||
// Get the list of files in the specified directory in JSON format.
|
||||
// If flagDirs is true then we prefix each directory with a * character.
|
||||
OutputBuffer *RepRap::GetFilesResponse(const char *dir, bool flagsDirs)
|
||||
|
|
1
Reprap.h
1
Reprap.h
|
@ -89,7 +89,6 @@ public:
|
|||
OutputBuffer *GetStatusResponse(uint8_t type, ResponseSource source);
|
||||
OutputBuffer *GetConfigResponse();
|
||||
OutputBuffer *GetLegacyStatusResponse(uint8_t type, int seq);
|
||||
OutputBuffer *GetNameResponse();
|
||||
OutputBuffer *GetFilesResponse(const char* dir, bool flagsDirs);
|
||||
|
||||
void Beep(int freq, int ms);
|
||||
|
|
|
@ -15,7 +15,6 @@ void Roland::Init()
|
|||
pinMode(ROLAND_RTS_PIN, OUTPUT);
|
||||
pinMode(ROLAND_CTS_PIN, INPUT);
|
||||
digitalWrite(ROLAND_RTS_PIN, HIGH);
|
||||
Serial1.begin(ROLAND_BAUD); //For serial comms to mill
|
||||
|
||||
sBuffer = new StringRef(buffer, ARRAY_SIZE(buffer));
|
||||
sBuffer->Clear();
|
||||
|
@ -36,8 +35,8 @@ void Roland::Spin()
|
|||
|
||||
// 'U' is 01010101 in binary (nice for an oscilloscope...)
|
||||
|
||||
//Serial1.write('U');
|
||||
//Serial1.flush();
|
||||
//SERIAL_AUX2_DEVICE.write('U');
|
||||
//SERIAL_AUX2_DEVICE.flush();
|
||||
//return;
|
||||
|
||||
// Are we sending something to the Roland?
|
||||
|
@ -50,8 +49,8 @@ void Roland::Spin()
|
|||
return;
|
||||
}
|
||||
|
||||
Serial1.write(buffer[bufferPointer]);
|
||||
Serial1.flush();
|
||||
SERIAL_AUX2_DEVICE.write(buffer[bufferPointer]);
|
||||
SERIAL_AUX2_DEVICE.flush();
|
||||
bufferPointer++;
|
||||
}
|
||||
else // Not sending.
|
||||
|
|
8
Roland.h
8
Roland.h
|
@ -28,15 +28,11 @@ Licence: GPL
|
|||
#include "Platform.h"
|
||||
|
||||
const float ROLAND_FACTOR = (1.016088061*100.0/2.54); // Roland units are 0.001"
|
||||
const int8_t ROLAND_RTS_PIN = 75; // Expansion pin 29, SPI0_MOSI
|
||||
const int8_t ROLAND_CTS_PIN = 76; // Expansion pin 28, SPI0_SPCK
|
||||
const size_t ROLAND_BUFFER_SIZE = 50;
|
||||
|
||||
// TX and RX
|
||||
// Expansion pin 11, PA13_TXD1
|
||||
// Expansion pin 12, PA12_RXD1
|
||||
|
||||
const uint16_t ROLAND_BAUD = 9600;
|
||||
// Expansion pin 13, PA13_TXD0
|
||||
// Expansion pin 14, PA12_RXD0
|
||||
|
||||
|
||||
class Roland
|
||||
|
|
245
Webserver.cpp
245
Webserver.cpp
|
@ -54,6 +54,9 @@
|
|||
|
||||
rr_reply Returns the last-known G-code reply as plain text (not encapsulated as JSON).
|
||||
|
||||
rr_configfile
|
||||
Sends the config file as plain text (not encapsulated as JSON either).
|
||||
|
||||
rr_upload?name=xxx
|
||||
Upload a specified file using a POST request. The payload of this request has to be
|
||||
the file content. Only one file may be uploaded at once. When the upload has finished,
|
||||
|
@ -106,8 +109,8 @@ static const char* badEscapeResponse = "bad escape";
|
|||
|
||||
|
||||
// Constructor and initialisation
|
||||
Webserver::Webserver(Platform* p, Network *n) : platform(p), network(n),
|
||||
webserverActive(false), readingConnection(nullptr)
|
||||
Webserver::Webserver(Platform* p, Network *n) : platform(p), network(n), webserverActive(false),
|
||||
readingConnection(nullptr)
|
||||
{
|
||||
httpInterpreter = new HttpInterpreter(p, this, n);
|
||||
ftpInterpreter = new FtpInterpreter(p, this, n);
|
||||
|
@ -261,6 +264,9 @@ void Webserver::Exit()
|
|||
void Webserver::Diagnostics()
|
||||
{
|
||||
platform->Message(GENERIC_MESSAGE, "Webserver Diagnostics:\n");
|
||||
httpInterpreter->Diagnostics();
|
||||
ftpInterpreter->Diagnostics();
|
||||
telnetInterpreter->Diagnostics();
|
||||
}
|
||||
|
||||
bool Webserver::GCodeAvailable(const WebSource source) const
|
||||
|
@ -499,12 +505,17 @@ Webserver::HttpInterpreter::HttpInterpreter(Platform *p, Webserver *ws, Network
|
|||
: ProtocolInterpreter(p, ws, n), state(doingCommandWord), numSessions(0), clientsServed(0)
|
||||
{
|
||||
gcodeReadIndex = gcodeWriteIndex = 0;
|
||||
gcodeReply = nullptr;
|
||||
gcodeReply = new OutputStack();
|
||||
uploadingTextData = false;
|
||||
processingDeferredRequest = false;
|
||||
numContinuationBytes = seq = 0;
|
||||
}
|
||||
|
||||
void Webserver::HttpInterpreter::Diagnostics()
|
||||
{
|
||||
platform->MessageF(GENERIC_MESSAGE, "HTTP sessions: %d of %d\n", numSessions, maxHttpSessions);
|
||||
}
|
||||
|
||||
// File Uploads
|
||||
|
||||
bool Webserver::HttpInterpreter::DoFastUpload(NetworkTransaction *transaction)
|
||||
|
@ -699,33 +710,58 @@ void Webserver::HttpInterpreter::SendFile(const char* nameOfFileToSend)
|
|||
transaction->Commit(false);
|
||||
}
|
||||
|
||||
void Webserver::HttpInterpreter::SendGCodeReply(NetworkTransaction *transaction)
|
||||
void Webserver::HttpInterpreter::SendConfigFile(NetworkTransaction *transaction)
|
||||
{
|
||||
// Send G-Code reply as plain text to the client
|
||||
FileStore *configFile = platform->GetFileStore(platform->GetSysDir(), platform->GetConfigFile(), false);
|
||||
|
||||
transaction->Write("HTTP/1.1 200 OK\n");
|
||||
transaction->Write("Content-Type: text/plain\n");
|
||||
transaction->Printf("Content-Length: %u\n", (gcodeReply != nullptr) ? gcodeReply->Length() : 0);
|
||||
transaction->Printf("Content-Length: %u\n", (configFile != nullptr) ? configFile->Length() : 0);
|
||||
transaction->Write("Connection: close\n\n");
|
||||
transaction->Write(gcodeReply);
|
||||
transaction->SetFileToWrite(configFile);
|
||||
transaction->Commit(false);
|
||||
}
|
||||
|
||||
// Check if we need to keep this reply
|
||||
if (gcodeReply != nullptr)
|
||||
void Webserver::HttpInterpreter::SendGCodeReply(NetworkTransaction *transaction)
|
||||
{
|
||||
// Do we need to keep the G-Code reply for other clients?
|
||||
bool clearReply = false;
|
||||
if (!gcodeReply->IsEmpty())
|
||||
{
|
||||
clientsServed++;
|
||||
if (reprap.Debug(moduleWebserver))
|
||||
{
|
||||
platform->MessageF(HOST_MESSAGE, "Served client %d of %d, refs %u\n", clientsServed, numSessions, gcodeReply->References());
|
||||
}
|
||||
if (clientsServed < numSessions)
|
||||
{
|
||||
// Yes - make sure the Network class doesn't discard its buffers yet
|
||||
// NB: This must happen here, because NetworkTransaction::Write() might already release OutputBuffers
|
||||
gcodeReply->IncreaseReferences(1);
|
||||
}
|
||||
else
|
||||
{
|
||||
gcodeReply = nullptr;
|
||||
clientsServed = 0;
|
||||
// No - clean up again later
|
||||
clearReply = true;
|
||||
}
|
||||
|
||||
if (reprap.Debug(moduleWebserver))
|
||||
{
|
||||
platform->MessageF(HOST_MESSAGE, "Serving client %d of %d\n", clientsServed, numSessions);
|
||||
}
|
||||
}
|
||||
|
||||
// Send the whole G-Code reply as plain text to the client
|
||||
transaction->Write("HTTP/1.1 200 OK\n");
|
||||
transaction->Write("Cache-Control: no-cache, no-store, must-revalidate\n");
|
||||
transaction->Write("Pragma: no-cache\n");
|
||||
transaction->Write("Expires: 0\n");
|
||||
transaction->Write("Content-Type: text/plain\n");
|
||||
transaction->Printf("Content-Length: %u\n", gcodeReply->DataLength());
|
||||
transaction->Write("Connection: close\n\n");
|
||||
transaction->Write(gcodeReply);
|
||||
transaction->Commit(false);
|
||||
|
||||
// Possibly clean up the G-code reply once again
|
||||
if (clearReply)
|
||||
{
|
||||
gcodeReply->Clear();
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -746,6 +782,13 @@ void Webserver::HttpInterpreter::SendJsonResponse(const char* command)
|
|||
return;
|
||||
}
|
||||
|
||||
// rr_configfile sends the config as plain text well
|
||||
if (IsAuthenticated() && StringEquals(command, "configfile"))
|
||||
{
|
||||
SendConfigFile(transaction);
|
||||
return;
|
||||
}
|
||||
|
||||
// We need a valid output buffer to process this request...
|
||||
OutputBuffer *jsonResponse;
|
||||
if (!OutputBuffer::Allocate(jsonResponse))
|
||||
|
@ -771,10 +814,7 @@ void Webserver::HttpInterpreter::SendJsonResponse(const char* command)
|
|||
// Check the special case of a deferred request
|
||||
if (processingDeferredRequest)
|
||||
{
|
||||
do {
|
||||
jsonResponse = OutputBuffer::Release(jsonResponse);
|
||||
} while (jsonResponse != nullptr);
|
||||
|
||||
// GetJsonResponse() must free the allocated OutputBuffer before we get here
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -808,6 +848,9 @@ void Webserver::HttpInterpreter::SendJsonResponse(const char* command)
|
|||
}
|
||||
|
||||
transaction->Write("HTTP/1.1 200 OK\n");
|
||||
transaction->Write("Cache-Control: no-cache, no-store, must-revalidate\n");
|
||||
transaction->Write("Pragma: no-cache\n");
|
||||
transaction->Write("Expires: 0\n");
|
||||
transaction->Write("Content-Type: application/json\n");
|
||||
transaction->Printf("Content-Length: %u\n", (jsonResponse != nullptr) ? jsonResponse->Length() : 0);
|
||||
transaction->Printf("Connection: %s\n\n", keepOpen ? "keep-alive" : "close");
|
||||
|
@ -819,14 +862,19 @@ void Webserver::HttpInterpreter::SendJsonResponse(const char* command)
|
|||
bool Webserver::HttpInterpreter::IsReady()
|
||||
{
|
||||
// We want to send a response, but we need memory for that. If there isn't enough available, see if we can truncate the G-Code reply
|
||||
size_t bytesLeft = OutputBuffer::GetBytesLeft(nullptr);
|
||||
if (bytesLeft < minHttpResponseSize && gcodeReply != nullptr)
|
||||
while (OutputBuffer::GetBytesLeft(nullptr) < minHttpResponseSize)
|
||||
{
|
||||
if (bytesLeft + OutputBuffer::Truncate(gcodeReply, minHttpResponseSize) < minHttpResponseSize)
|
||||
if (gcodeReply->IsEmpty())
|
||||
{
|
||||
// There is not enough space available and we cannot free it up. Try again later
|
||||
// We cannot truncate any G-Code reply, so try again later
|
||||
return false;
|
||||
}
|
||||
|
||||
if (OutputBuffer::Truncate(gcodeReply->GetFirstItem(), minHttpResponseSize) == 0)
|
||||
{
|
||||
// Truncating didn't work out, but see if we can free up a few more bytes by releasing the first reply item
|
||||
OutputBuffer::ReleaseAll(gcodeReply->Pop());
|
||||
}
|
||||
}
|
||||
|
||||
// If we're already processing a request, we must not parse its content again
|
||||
|
@ -901,12 +949,14 @@ bool Webserver::HttpInterpreter::GetJsonResponse(const char* request, OutputBuff
|
|||
type = 1;
|
||||
}
|
||||
|
||||
OutputBuffer::Replace(response, reprap.GetStatusResponse(type, ResponseSource::HTTP));
|
||||
OutputBuffer::Release(response);
|
||||
response = reprap.GetStatusResponse(type, ResponseSource::HTTP);
|
||||
}
|
||||
else
|
||||
{
|
||||
// Deprecated
|
||||
OutputBuffer::Replace(response, reprap.GetLegacyStatusResponse(1, 0));
|
||||
OutputBuffer::Release(response);
|
||||
response = reprap.GetLegacyStatusResponse(1, 0);
|
||||
}
|
||||
}
|
||||
else if (StringEquals(request, "gcode") && StringEquals(key, "gcode"))
|
||||
|
@ -968,14 +1018,14 @@ bool Webserver::HttpInterpreter::GetJsonResponse(const char* request, OutputBuff
|
|||
flagDirs = StringEquals(qualifiers[1].value, "1");
|
||||
}
|
||||
}
|
||||
OutputBuffer::Replace(response, reprap.GetFilesResponse(dir, flagDirs));
|
||||
OutputBuffer::Release(response);
|
||||
response = reprap.GetFilesResponse(dir, flagDirs);
|
||||
}
|
||||
else if (StringEquals(request, "fileinfo"))
|
||||
{
|
||||
OutputBuffer *buffer;
|
||||
if (reprap.GetPrintMonitor()->GetFileInfoResponse(StringEquals(key, "name") ? value : nullptr, buffer))
|
||||
OutputBuffer::Release(response);
|
||||
if (reprap.GetPrintMonitor()->GetFileInfoResponse(StringEquals(key, "name") ? value : nullptr, response))
|
||||
{
|
||||
OutputBuffer::Replace(response, buffer);
|
||||
processingDeferredRequest = false;
|
||||
}
|
||||
else
|
||||
|
@ -990,7 +1040,7 @@ bool Webserver::HttpInterpreter::GetJsonResponse(const char* request, OutputBuff
|
|||
{
|
||||
if (StringEquals(key, "old") && StringEquals(qualifiers[1].key, "new"))
|
||||
{
|
||||
response->printf("{\"err\":%d}", platform->GetMassStorage()->Rename(value, qualifiers[1].value) ? 1 : 0);
|
||||
response->printf("{\"err\":%d}", platform->GetMassStorage()->Rename(value, qualifiers[1].value) ? 0 : 1);
|
||||
}
|
||||
else
|
||||
{
|
||||
|
@ -1009,7 +1059,8 @@ bool Webserver::HttpInterpreter::GetJsonResponse(const char* request, OutputBuff
|
|||
}
|
||||
else if (StringEquals(request, "config"))
|
||||
{
|
||||
OutputBuffer::Replace(response, reprap.GetConfigResponse());
|
||||
OutputBuffer::Release(response);
|
||||
response = reprap.GetConfigResponse();
|
||||
}
|
||||
else
|
||||
{
|
||||
|
@ -1435,7 +1486,7 @@ bool Webserver::HttpInterpreter::ProcessMessage()
|
|||
{
|
||||
if (reprap.Debug(moduleWebserver))
|
||||
{
|
||||
platform->Message(HOST_MESSAGE, "HTTP req, command words {");
|
||||
platform->MessageF(HOST_MESSAGE, "HTTP req, command words {", numCommandWords);
|
||||
for (size_t i = 0; i < numCommandWords; ++i)
|
||||
{
|
||||
platform->MessageF(HOST_MESSAGE, " %s", commandWords[i]);
|
||||
|
@ -1537,7 +1588,7 @@ bool Webserver::HttpInterpreter::ProcessMessage()
|
|||
// Align the client pointer on a 32-bit boundary for HSMCI efficiency.
|
||||
// To remain efficient, the browser should send POSTDATA in multiples of 4 bytes.
|
||||
clientPointer += 3;
|
||||
clientPointer -= reinterpret_cast<unsigned int>(clientMessage + clientPointer) & 3;
|
||||
clientPointer -= reinterpret_cast<size_t>(clientMessage + clientPointer) & 3;
|
||||
state = doingPost;
|
||||
|
||||
return false;
|
||||
|
@ -1578,7 +1629,7 @@ bool Webserver::HttpInterpreter::RejectMessage(const char* response, unsigned in
|
|||
// Authenticate current IP and return true on success
|
||||
bool Webserver::HttpInterpreter::Authenticate()
|
||||
{
|
||||
if (numSessions < maxSessions)
|
||||
if (numSessions < maxHttpSessions)
|
||||
{
|
||||
sessions[numSessions].ip = network->GetTransaction()->GetRemoteIP();
|
||||
sessions[numSessions].lastQueryTime = platform->Time();
|
||||
|
@ -1591,7 +1642,7 @@ bool Webserver::HttpInterpreter::Authenticate()
|
|||
|
||||
bool Webserver::HttpInterpreter::IsAuthenticated() const
|
||||
{
|
||||
uint32_t remoteIP = network->GetTransaction()->GetRemoteIP();
|
||||
const uint32_t remoteIP = network->GetTransaction()->GetRemoteIP();
|
||||
for(size_t i = 0; i < numSessions; i++)
|
||||
{
|
||||
if (sessions[i].ip == remoteIP)
|
||||
|
@ -1604,7 +1655,7 @@ bool Webserver::HttpInterpreter::IsAuthenticated() const
|
|||
|
||||
void Webserver::HttpInterpreter::UpdateAuthentication()
|
||||
{
|
||||
uint32_t remoteIP = network->GetTransaction()->GetRemoteIP();
|
||||
const uint32_t remoteIP = network->GetTransaction()->GetRemoteIP();
|
||||
for(size_t i = 0; i < numSessions; i++)
|
||||
{
|
||||
if (sessions[i].ip == remoteIP)
|
||||
|
@ -1617,7 +1668,7 @@ void Webserver::HttpInterpreter::UpdateAuthentication()
|
|||
|
||||
void Webserver::HttpInterpreter::RemoveAuthentication()
|
||||
{
|
||||
uint32_t remoteIP = network->GetTransaction()->GetRemoteIP();
|
||||
const uint32_t remoteIP = network->GetTransaction()->GetRemoteIP();
|
||||
for(int i=(int)numSessions - 1; i>=0; i--)
|
||||
{
|
||||
if (sessions[i].ip == remoteIP)
|
||||
|
@ -1649,12 +1700,12 @@ void Webserver::HttpInterpreter::CheckSessions()
|
|||
}
|
||||
}
|
||||
|
||||
// If there are no clients connected, we can free up some run-time space by dumping the G-Code response
|
||||
// If we cannot send the G-Code reply to anyone, we may free up some run-time space by dumping it
|
||||
if (numSessions == 0 || clientsServed >= numSessions)
|
||||
{
|
||||
while (gcodeReply != nullptr)
|
||||
while (!gcodeReply->IsEmpty())
|
||||
{
|
||||
gcodeReply = OutputBuffer::Release(gcodeReply);
|
||||
OutputBuffer::ReleaseAll(gcodeReply->Pop());
|
||||
}
|
||||
clientsServed = 0;
|
||||
}
|
||||
|
@ -1775,23 +1826,16 @@ void Webserver::HttpInterpreter::HandleGCodeReply(OutputBuffer *reply)
|
|||
{
|
||||
if (numSessions > 0)
|
||||
{
|
||||
if (gcodeReply == nullptr)
|
||||
{
|
||||
gcodeReply = reply;
|
||||
}
|
||||
else
|
||||
{
|
||||
gcodeReply->Append(reply);
|
||||
}
|
||||
// FIXME: This might cause G-code responses to be sent twice to fast HTTP clients, but
|
||||
// I (chrishamm) cannot think of a nicer way to deal with slow clients at the moment...
|
||||
gcodeReply->Push(reply);
|
||||
clientsServed = 0;
|
||||
seq++;
|
||||
}
|
||||
else
|
||||
{
|
||||
// Don't use buffers that may never get released...
|
||||
while (reply != nullptr)
|
||||
{
|
||||
reply = OutputBuffer::Release(reply);
|
||||
}
|
||||
OutputBuffer::ReleaseAll(reply);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -1800,17 +1844,18 @@ void Webserver::HttpInterpreter::HandleGCodeReply(const char *reply)
|
|||
{
|
||||
if (numSessions > 0)
|
||||
{
|
||||
if (gcodeReply == nullptr)
|
||||
OutputBuffer *buffer = gcodeReply->GetLastItem();
|
||||
if (buffer == nullptr || buffer->IsReferenced())
|
||||
{
|
||||
OutputBuffer *buffer;
|
||||
if (!OutputBuffer::Allocate(buffer))
|
||||
{
|
||||
// No more space available
|
||||
// No more space available, stop here
|
||||
return;
|
||||
}
|
||||
gcodeReply = buffer;
|
||||
gcodeReply->Push(buffer);
|
||||
}
|
||||
gcodeReply->cat(reply);
|
||||
|
||||
buffer->cat(reply);
|
||||
seq++;
|
||||
}
|
||||
}
|
||||
|
@ -1829,6 +1874,11 @@ Webserver::FtpInterpreter::FtpInterpreter(Platform *p, Webserver *ws, Network *n
|
|||
strcpy(currentDir, "/");
|
||||
}
|
||||
|
||||
void Webserver::FtpInterpreter::Diagnostics()
|
||||
{
|
||||
platform->MessageF(GENERIC_MESSAGE, "FTP connections: %d, state %d\n", connectedClients, state);
|
||||
}
|
||||
|
||||
void Webserver::FtpInterpreter::ConnectionEstablished()
|
||||
{
|
||||
connectedClients++;
|
||||
|
@ -2100,18 +2150,7 @@ void Webserver::FtpInterpreter::ProcessLine()
|
|||
else if (StringStartsWith(clientMessage, "DELE"))
|
||||
{
|
||||
ReadFilename(4);
|
||||
|
||||
bool ok;
|
||||
if (filename[0] == '/')
|
||||
{
|
||||
ok = platform->GetMassStorage()->Delete(nullptr, filename);
|
||||
}
|
||||
else
|
||||
{
|
||||
ok = platform->GetMassStorage()->Delete(currentDir, filename);
|
||||
}
|
||||
|
||||
if (ok)
|
||||
if (platform->GetMassStorage()->Delete(currentDir, filename))
|
||||
{
|
||||
SendReply(250, "Delete operation successful.");
|
||||
}
|
||||
|
@ -2124,18 +2163,7 @@ void Webserver::FtpInterpreter::ProcessLine()
|
|||
else if (StringStartsWith(clientMessage, "RMD"))
|
||||
{
|
||||
ReadFilename(3);
|
||||
|
||||
bool ok;
|
||||
if (filename[0] == '/')
|
||||
{
|
||||
ok = platform->GetMassStorage()->Delete(nullptr, filename);
|
||||
}
|
||||
else
|
||||
{
|
||||
ok = platform->GetMassStorage()->Delete(currentDir, filename);
|
||||
}
|
||||
|
||||
if (ok)
|
||||
if (platform->GetMassStorage()->Delete(currentDir, filename))
|
||||
{
|
||||
SendReply(250, "Remove directory operation successful.");
|
||||
}
|
||||
|
@ -2190,29 +2218,14 @@ void Webserver::FtpInterpreter::ProcessLine()
|
|||
oldFilename[FILENAME_LENGTH - 1] = 0;
|
||||
ReadFilename(4);
|
||||
|
||||
// See where this file needs to be moved to
|
||||
if (filename[0] == '/')
|
||||
const char *newFilename = platform->GetMassStorage()->CombineName(currentDir, filename);
|
||||
if (platform->GetMassStorage()->Rename(oldFilename, newFilename))
|
||||
{
|
||||
if (platform->GetMassStorage()->Rename(oldFilename, filename))
|
||||
{
|
||||
SendReply(250, "Rename successful.");
|
||||
}
|
||||
else
|
||||
{
|
||||
SendReply(550, "Could not rename file or directory.");
|
||||
}
|
||||
SendReply(250, "Rename successful.");
|
||||
}
|
||||
else
|
||||
{
|
||||
const char *newFilename = platform->GetMassStorage()->CombineName(currentDir, filename);
|
||||
if (platform->GetMassStorage()->Rename(oldFilename, newFilename))
|
||||
{
|
||||
SendReply(250, "Rename successful.");
|
||||
}
|
||||
else
|
||||
{
|
||||
SendReply(500, "Could not rename file or directory.");
|
||||
}
|
||||
SendReply(500, "Could not rename file or directory.");
|
||||
}
|
||||
}
|
||||
// no op
|
||||
|
@ -2300,8 +2313,8 @@ void Webserver::FtpInterpreter::ProcessLine()
|
|||
else if (StringStartsWith(clientMessage, "STOR"))
|
||||
{
|
||||
ReadFilename(4);
|
||||
FileStore *file = platform->GetFileStore(currentDir, filename, true);
|
||||
|
||||
FileStore *file = platform->GetFileStore(currentDir, filename, true);
|
||||
if (StartUpload(file))
|
||||
{
|
||||
strncpy(filenameBeingUploaded, filename, ARRAY_SIZE(filenameBeingUploaded));
|
||||
|
@ -2321,8 +2334,8 @@ void Webserver::FtpInterpreter::ProcessLine()
|
|||
else if (StringStartsWith(clientMessage, "RETR"))
|
||||
{
|
||||
ReadFilename(4);
|
||||
FileStore *file = platform->GetFileStore(currentDir, filename, false);
|
||||
|
||||
FileStore *file = platform->GetFileStore(currentDir, filename, false);
|
||||
if (file == nullptr)
|
||||
{
|
||||
SendReply(550, "Failed to open file.");
|
||||
|
@ -2519,6 +2532,11 @@ Webserver::TelnetInterpreter::TelnetInterpreter(Platform *p, Webserver *ws, Netw
|
|||
ResetState();
|
||||
}
|
||||
|
||||
void Webserver::TelnetInterpreter::Diagnostics()
|
||||
{
|
||||
platform->MessageF(GENERIC_MESSAGE, "Telnet connections: %d\n", connectedClients);
|
||||
}
|
||||
|
||||
void Webserver::TelnetInterpreter::ConnectionEstablished()
|
||||
{
|
||||
connectedClients++;
|
||||
|
@ -2557,10 +2575,8 @@ void Webserver::TelnetInterpreter::ConnectionLost(uint32_t remoteIP, uint16_t re
|
|||
ResetState();
|
||||
|
||||
// Don't save up output buffers if they can't be sent
|
||||
while (gcodeReply != nullptr)
|
||||
{
|
||||
OutputBuffer::Release(gcodeReply);
|
||||
}
|
||||
OutputBuffer::ReleaseAll(gcodeReply);
|
||||
gcodeReply = nullptr;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -2741,11 +2757,11 @@ void Webserver::TelnetInterpreter::HandleGCodeReply(OutputBuffer *reply)
|
|||
OutputBuffer *buffer;
|
||||
if (!OutputBuffer::Allocate(buffer))
|
||||
{
|
||||
OutputBuffer::Truncate(reply, 1);
|
||||
if (!OutputBuffer::Allocate(buffer, false))
|
||||
OutputBuffer::Truncate(reply, OUTPUT_BUFFER_SIZE);
|
||||
if (!OutputBuffer::Allocate(buffer))
|
||||
{
|
||||
// If we're really short on memory, just skip the conversion
|
||||
gcodeReply = reply;
|
||||
// If we're really short on memory, release the G-Code reply instantly
|
||||
OutputBuffer::ReleaseAll(reply);
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
@ -2771,10 +2787,7 @@ void Webserver::TelnetInterpreter::HandleGCodeReply(OutputBuffer *reply)
|
|||
else
|
||||
{
|
||||
// Don't use buffers that may never get released...
|
||||
while (reply != nullptr)
|
||||
{
|
||||
reply = OutputBuffer::Release(reply);
|
||||
}
|
||||
OutputBuffer::ReleaseAll(reply);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -2788,14 +2801,14 @@ void Webserver::TelnetInterpreter::HandleGCodeReply(const char *reply)
|
|||
OutputBuffer *buffer;
|
||||
if (!OutputBuffer::Allocate(buffer))
|
||||
{
|
||||
// No more space available to store this reply
|
||||
// No more space available to store this reply, stop here
|
||||
return;
|
||||
}
|
||||
gcodeReply = buffer;
|
||||
}
|
||||
|
||||
// Write entire content to new output buffers, but this time with \r\n instead of \n
|
||||
while (*reply)
|
||||
while (*reply != 0)
|
||||
{
|
||||
if (*reply == '\n' && gcodeReply->cat('\r') == 0)
|
||||
{
|
||||
|
|
12
Webserver.h
12
Webserver.h
|
@ -45,7 +45,7 @@ const size_t maxCommandWords = 4; // max number of space-separated words in t
|
|||
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 maxSessions = 8; // maximum number of simultaneous HTTP sessions
|
||||
const size_t maxHttpSessions = 8; // maximum number of simultaneous HTTP sessions
|
||||
const float httpSessionTimeout = 8.0; // HTTP session timeout in seconds
|
||||
|
||||
/* FTP */
|
||||
|
@ -143,6 +143,7 @@ class Webserver
|
|||
public:
|
||||
|
||||
HttpInterpreter(Platform *p, Webserver *ws, Network *n);
|
||||
void Diagnostics();
|
||||
void ConnectionLost(uint32_t remoteIP, uint16_t remotePort, uint16_t localPort) override;
|
||||
bool CharFromClient(const char c) override;
|
||||
void ResetState() override;
|
||||
|
@ -195,6 +196,7 @@ class Webserver
|
|||
};
|
||||
|
||||
void SendFile(const char* nameOfFileToSend);
|
||||
void SendConfigFile(NetworkTransaction *transaction);
|
||||
void SendGCodeReply(NetworkTransaction *transaction);
|
||||
void SendJsonResponse(const char* command);
|
||||
bool GetJsonResponse(const char* request, OutputBuffer *&response, const char* key, const char* value, size_t valueLength, bool& keepOpen);
|
||||
|
@ -223,7 +225,7 @@ class Webserver
|
|||
uint16_t postPort;
|
||||
};
|
||||
|
||||
HttpSession sessions[maxSessions];
|
||||
HttpSession sessions[maxHttpSessions];
|
||||
size_t numSessions, clientsServed;
|
||||
|
||||
bool Authenticate();
|
||||
|
@ -243,7 +245,7 @@ class Webserver
|
|||
|
||||
// Response from GCodes class
|
||||
|
||||
OutputBuffer * volatile gcodeReply;
|
||||
OutputStack *gcodeReply;
|
||||
|
||||
protected:
|
||||
bool processingDeferredRequest; // it's no good idea to parse 128kB of text in one go...
|
||||
|
@ -263,6 +265,7 @@ class Webserver
|
|||
public:
|
||||
|
||||
FtpInterpreter(Platform *p, Webserver *ws, Network *n);
|
||||
void Diagnostics();
|
||||
void ConnectionEstablished() override;
|
||||
void ConnectionLost(uint32_t remoteIP, uint16_t remotePort, uint16_t localPort) override;
|
||||
bool CharFromClient(const char c) override;
|
||||
|
@ -307,6 +310,7 @@ class Webserver
|
|||
public:
|
||||
|
||||
TelnetInterpreter(Platform *p, Webserver *ws, Network *n);
|
||||
void Diagnostics();
|
||||
void ConnectionEstablished() override;
|
||||
void ConnectionLost(uint32_t remoteIP, uint16_t remotePort, uint16_t local_port) override;
|
||||
bool CharFromClient(const char c) override;
|
||||
|
@ -348,7 +352,7 @@ class Webserver
|
|||
void ProcessGcode(const char* gc);
|
||||
void StoreGcodeData(const char* data, uint16_t len);
|
||||
|
||||
// Response from GCodes class
|
||||
// Converted response from GCodes class (NL -> CRNL)
|
||||
|
||||
OutputBuffer * volatile gcodeReply;
|
||||
};
|
||||
|
|
Reference in a new issue