Version 0.78s alpha

Added support for nozzle offsets in G10 command
Disable heater timeout if the time limit is set to zero or negative
Don't send non-error responses to the web interface unless the
corresponding command also came from the web interface
Added support for aux input from serial. Need to finish this by making
serial transmission interrupt-driven.
This commit is contained in:
David Crocker 2014-09-12 17:55:33 +01:00
parent cc15d83ca4
commit 09943e1cb7
12 changed files with 522 additions and 89 deletions

View file

@ -0,0 +1,97 @@
/*
Stream.h - base class for character-based streams.
Copyright (c) 2010 David A. Mellis. All right reserved.
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
parsing functions based on TextFinder library by Michael Margolis
*/
#ifndef Stream_h
#define Stream_h
#include <inttypes.h>
#include "Print.h"
// compatability macros for testing
/*
#define getInt() parseInt()
#define getInt(skipChar) parseInt(skipchar)
#define getFloat() parseFloat()
#define getFloat(skipChar) parseFloat(skipChar)
#define getString( pre_string, post_string, buffer, length)
readBytesBetween( pre_string, terminator, buffer, length)
*/
class Stream : public Print
{
protected:
unsigned long _timeout; // number of milliseconds to wait for the next char before aborting timed read
unsigned long _startMillis; // used for timeout measurement
int timedRead(); // private method to read stream with timeout
int timedPeek(); // private method to peek stream with timeout
int peekNextDigit(); // returns the next numeric digit in the stream or -1 if timeout
public:
virtual int available() = 0;
virtual int read() = 0;
virtual int peek() = 0;
virtual void flush() = 0;
virtual size_t canWrite() const { return 1; } // DC42 added
Stream() {_timeout=1000;}
// parsing methods
void setTimeout(unsigned long timeout); // sets maximum milliseconds to wait for stream data, default is 1 second
bool find(char *target); // reads data from the stream until the target string is found
// returns true if target string is found, false if timed out (see setTimeout)
bool find(char *target, size_t length); // reads data from the stream until the target string of given length is found
// returns true if target string is found, false if timed out
bool findUntil(char *target, char *terminator); // as find but search ends if the terminator string is found
bool findUntil(char *target, size_t targetLen, char *terminate, size_t termLen); // as above but search ends if the terminate string is found
long parseInt(); // returns the first valid (long) integer value from the current position.
// initial characters that are not digits (or the minus sign) are skipped
// integer is terminated by the first character that is not a digit.
float parseFloat(); // float version of parseInt
size_t readBytes( char *buffer, size_t length); // read chars from stream into buffer
// terminates if length characters have been read or timeout (see setTimeout)
// returns the number of characters placed in the buffer (0 means no valid data found)
size_t readBytesUntil( char terminator, char *buffer, size_t length); // as readBytes with terminator character
// terminates if length characters have been read, timeout, or if the terminator character detected
// returns the number of characters placed in the buffer (0 means no valid data found)
// Arduino String functions to be added here
String readString();
String readStringUntil(char terminator);
protected:
long parseInt(char skipChar); // as above but the given skipChar is ignored
// as above but the given skipChar is ignored
// this allows format characters (typically commas) in values to be ignored
float parseFloat(char skipChar); // as above but the given skipChar is ignored
};
#endif

View file

@ -0,0 +1,142 @@
/*
Copyright (c) 2011 Arduino. All right reserved.
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
See the GNU Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#include <stdlib.h>
#include <stdio.h>
#include <string.h>
#include "UARTClass.h"
// Constructors ////////////////////////////////////////////////////////////////
UARTClass::UARTClass( Uart* pUart, IRQn_Type dwIrq, uint32_t dwId, RingBuffer* pRx_buffer )
{
_rx_buffer = pRx_buffer ;
_pUart=pUart ;
_dwIrq=dwIrq ;
_dwId=dwId ;
}
// Public Methods //////////////////////////////////////////////////////////////
void UARTClass::begin( const uint32_t dwBaudRate )
{
// Configure PMC
pmc_enable_periph_clk( _dwId ) ;
// Disable PDC channel
_pUart->UART_PTCR = UART_PTCR_RXTDIS | UART_PTCR_TXTDIS ;
// Reset and disable receiver and transmitter
_pUart->UART_CR = UART_CR_RSTRX | UART_CR_RSTTX | UART_CR_RXDIS | UART_CR_TXDIS ;
// Configure mode
_pUart->UART_MR = UART_MR_PAR_NO | UART_MR_CHMODE_NORMAL ;
// Configure baudrate (asynchronous, no oversampling)
_pUart->UART_BRGR = (SystemCoreClock / dwBaudRate) >> 4 ;
// Configure interrupts
_pUart->UART_IDR = 0xFFFFFFFF;
_pUart->UART_IER = UART_IER_RXRDY | UART_IER_OVRE | UART_IER_FRAME;
// Enable UART interrupt in NVIC
NVIC_EnableIRQ(_dwIrq);
// Enable receiver and transmitter
_pUart->UART_CR = UART_CR_RXEN | UART_CR_TXEN ;
}
void UARTClass::end( void )
{
// clear any received data
_rx_buffer->_iHead = _rx_buffer->_iTail ;
// Disable UART interrupt in NVIC
NVIC_DisableIRQ( _dwIrq ) ;
// Wait for any outstanding data to be sent
flush();
pmc_disable_periph_clk( _dwId ) ;
}
int UARTClass::available( void )
{
return (uint32_t)(SERIAL_BUFFER_SIZE + _rx_buffer->_iHead - _rx_buffer->_iTail) % SERIAL_BUFFER_SIZE ;
}
int UARTClass::peek( void )
{
if ( _rx_buffer->_iHead == _rx_buffer->_iTail )
return -1 ;
return _rx_buffer->_aucBuffer[_rx_buffer->_iTail] ;
}
int UARTClass::read( void )
{
// if the head isn't ahead of the tail, we don't have any characters
if ( _rx_buffer->_iHead == _rx_buffer->_iTail )
return -1 ;
uint8_t uc = _rx_buffer->_aucBuffer[_rx_buffer->_iTail] ;
_rx_buffer->_iTail = (unsigned int)(_rx_buffer->_iTail + 1) % SERIAL_BUFFER_SIZE ;
return uc ;
}
void UARTClass::flush( void )
{
// Wait for transmission to complete
while ((_pUart->UART_SR & UART_SR_TXRDY) != UART_SR_TXRDY)
;
}
size_t UARTClass::write( const uint8_t uc_data )
{
// Check if the transmitter is ready
while ((_pUart->UART_SR & UART_SR_TXRDY) != UART_SR_TXRDY)
;
// Send character
_pUart->UART_THR = uc_data;
return 1;
}
size_t UARTClass::canWrite( void ) const //***** DC42 added
{
return (_pUart->UART_SR & UART_SR_TXRDY) ? 1 : 0;
}
void UARTClass::IrqHandler( void )
{
uint32_t status = _pUart->UART_SR;
// Did we receive data ?
if ((status & UART_SR_RXRDY) == UART_SR_RXRDY)
_rx_buffer->store_char(_pUart->UART_RHR);
// Acknowledge errors
if ((status & UART_SR_OVRE) == UART_SR_OVRE ||
(status & UART_SR_FRAME) == UART_SR_FRAME)
{
// TODO: error reporting outside ISR
_pUart->UART_CR |= UART_CR_RSTSTA;
}
}

View file

@ -0,0 +1,63 @@
/*
Copyright (c) 2011 Arduino. All right reserved.
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
See the GNU Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#ifndef _UART_CLASS_
#define _UART_CLASS_
#include "HardwareSerial.h"
#include "RingBuffer.h"
// Includes Atmel CMSIS
#include <chip.h>
class UARTClass : public HardwareSerial
{
protected:
RingBuffer *_rx_buffer ;
protected:
Uart* _pUart ;
IRQn_Type _dwIrq ;
uint32_t _dwId ;
public:
UARTClass( Uart* pUart, IRQn_Type dwIrq, uint32_t dwId, RingBuffer* pRx_buffer ) ;
void begin( const uint32_t dwBaudRate ) ;
void end( void ) ;
int available( void ) ;
int peek( void ) ;
int read( void ) ;
void flush( void ) ;
size_t write( const uint8_t c ) ;
size_t canWrite( void ) const /*override*/; //***** DC42 added
void IrqHandler( void ) ;
#if defined __GNUC__ /* GCC CS3 */
using Print::write ; // pull in write(str) and write(buf, size) from Print
#elif defined __ICCARM__ /* IAR Ewarm 5.41+ */
// virtual void write( const char *str ) ;
// virtual void write( const uint8_t *buffer, size_t size ) ;
#endif
operator bool() { return true; }; // UART always active
};
#endif // _UART_CLASS_

View file

@ -24,8 +24,8 @@ Licence: GPL
#define CONFIGURATION_H
#define NAME "RepRapFirmware"
#define VERSION "0.78r-dc42"
#define DATE "2014-09-06"
#define VERSION "0.78s-alpha-dc42"
#define DATE "2014-09-10"
#define AUTHORS "reprappro, dc42, zpl"
// Other firmware that we might switch to be compatible with.

View file

@ -35,6 +35,7 @@ GCodes::GCodes(Platform* p, Webserver* w)
webGCode = new GCodeBuffer(platform, "web: ");
fileGCode = new GCodeBuffer(platform, "file: ");
serialGCode = new GCodeBuffer(platform, "serial: ");
auxGCode = new GCodeBuffer(platform, "aux: ");
cannedCycleGCode = new GCodeBuffer(platform, "macro: ");
}
@ -79,6 +80,7 @@ void GCodes::Reset()
webGCode->Init();
fileGCode->Init();
serialGCode->Init();
auxGCode->Init();
cannedCycleGCode->Init();
moveAvailable = false;
fileBeingPrinted.Close();
@ -151,6 +153,13 @@ void GCodes::Spin()
return;
}
if (auxGCode->Active())
{
auxGCode->SetFinished(ActOnCode(auxGCode));
platform->ClassReport("GCodes", longWait);
return;
}
if (fileGCode->Active())
{
fileGCode->SetFinished(ActOnCode(fileGCode));
@ -230,6 +239,25 @@ void GCodes::Spin()
}
}
if (platform->GetAux()->Status() & byteAvailable)
{
int8_t i = 0;
do
{
char b;
platform->GetAux()->Read(b);
if (auxGCode->Put(b)) // add char to buffer and test whether the gcode is complete
{
auxGCode->SetFinished(ActOnCode(serialGCode));
break; // stop after receiving a complete gcode in case we haven't finished processing it
}
++i;
} while (i < 16 && (platform->GetAux()->Status() & byteAvailable));
platform->ClassReport("GCodes", longWait);
return;
}
// Else see if there is anything to print from file
DoFilePrint(fileGCode);
platform->ClassReport("GCodes", longWait);
@ -380,30 +408,39 @@ bool GCodes::LoadMoveBufferFromGCode(GCodeBuffer *gb, bool doingG92, bool applyL
// Now the movement axes
const Tool *currentTool = reprap.GetCurrentTool();
for(uint8_t axis = 0; axis < AXES; axis++)
{
if(gb->Seen(axisLetters[axis]))
{
float moveArg = gb->GetFValue() * distanceScale;
if (axesRelative && !doingG92)
{
moveArg += moveBuffer[axis];
}
if (applyLimits && axis < 2 && axisIsHomed[axis] && !doingG92) // limit X & Y moves unless doing G92. FIXME: No Z for the moment as we often need to move -ve to set the origin
{
if (moveArg < platform->AxisMinimum(axis))
{
moveArg = platform->AxisMinimum(axis);
} else if (moveArg > platform->AxisMaximum(axis))
{
moveArg = platform->AxisMaximum(axis);
}
}
moveBuffer[axis] = moveArg;
if (doingG92)
{
axisIsHomed[axis] = true; // doing a G92 defines the absolute axis position
}
else
{
if (axesRelative)
{
moveArg += moveBuffer[axis];
}
else if (currentTool != NULL)
{
moveArg -= currentTool->GetOffset()[axis]; // adjust requested position to compensate for tool offset
}
if (applyLimits && axis < 2 && axisIsHomed[axis]) // limit X & Y moves unless doing G92
{
if (moveArg < platform->AxisMinimum(axis))
{
moveArg = platform->AxisMinimum(axis);
}
else if (moveArg > platform->AxisMaximum(axis))
{
moveArg = platform->AxisMaximum(axis);
}
}
}
moveBuffer[axis] = moveArg;
}
}
@ -990,11 +1027,20 @@ const char* GCodes::GetCurrentCoordinates() const
{
float liveCoordinates[DRIVES + 1];
reprap.GetMove()->LiveCoordinates(liveCoordinates);
const Tool *currentTool = reprap.GetCurrentTool();
if (currentTool != NULL)
{
const float *offset = currentTool->GetOffset();
for (size_t i = 0; i < AXES; ++i)
{
liveCoordinates[i] += offset[i];
}
}
scratchString.printf("X:%.2f Y:%.2f Z:%.2f ", liveCoordinates[X_AXIS], liveCoordinates[Y_AXIS], liveCoordinates[Z_AXIS]);
for(int i = AXES; i< DRIVES; i++)
for(unsigned int i = AXES; i< DRIVES; i++)
{
scratchString.catf("E%d:%.1f ", i-AXES, liveCoordinates[i]);
scratchString.catf("E%u:%.1f ", i-AXES, liveCoordinates[i]);
}
return scratchString.Pointer();
}
@ -1041,7 +1087,7 @@ void GCodes::WriteHTMLToFile(char b, GCodeBuffer *gb)
fileBeingWritten = NULL;
gb->SetWritingFileDirectory(NULL);
const char* r = (platform->Emulating() == marlin) ? "Done saving file." : "";
HandleReply(false, gb == serialGCode, r, 'M', 560, false);
HandleReply(false, gb, r, 'M', 560, false);
return;
}
}
@ -1069,7 +1115,7 @@ void GCodes::WriteGCodeToFile(GCodeBuffer *gb)
fileBeingWritten = NULL;
gb->SetWritingFileDirectory(NULL);
const char* r = (platform->Emulating() == marlin) ? "Done saving file." : "";
HandleReply(false, gb == serialGCode, r, 'M', 29, false);
HandleReply(false, gb, r, 'M', 29, false);
return;
}
}
@ -1083,7 +1129,7 @@ void GCodes::WriteGCodeToFile(GCodeBuffer *gb)
if (gb->Seen('P'))
{
scratchString.printf("%d", gb->GetIValue());
HandleReply(false, gb == serialGCode, scratchString.Pointer(), 'G', 998, true);
HandleReply(false, gb, scratchString.Pointer(), 'G', 998, true);
return;
}
}
@ -1091,7 +1137,7 @@ void GCodes::WriteGCodeToFile(GCodeBuffer *gb)
fileBeingWritten->Write(gb->Buffer());
fileBeingWritten->Write('\n');
HandleReply(false, gb == serialGCode, "", 'G', 1, false);
HandleReply(false, gb, "", 'G', 1, false);
}
// Set up a file to print, but don't print it yet.
@ -1198,8 +1244,7 @@ bool GCodes::DoDwellTime(float dwell)
return false;
}
// Set working and standby temperatures for
// a tool. I.e. handle a G10.
// Set offset, working and standby temperatures for a tool. I.e. handle a G10.
void GCodes::SetOrReportOffsets(StringRef& reply, GCodeBuffer *gb)
{
@ -1213,33 +1258,70 @@ void GCodes::SetOrReportOffsets(StringRef& reply, GCodeBuffer *gb)
reply.printf("Attempt to set/report offsets and temperatures for non-existent tool: %d\n", toolNumber);
return;
}
// Deal with setting offsets
float offset[AXES];
for (size_t i = 0; i < AXES; ++i)
{
offset[i] = tool->GetOffset()[i];
}
bool settingOffset = false;
if (gb->Seen('X'))
{
offset[X_AXIS] = gb->GetFValue();
settingOffset = true;
}
if (gb->Seen('Y'))
{
offset[Y_AXIS] = gb->GetFValue();
settingOffset = true;
}
if (gb->Seen('Z'))
{
offset[Z_AXIS] = gb->GetFValue();
settingOffset = true;
}
if (settingOffset)
{
tool->SetOffset(offset);
}
// Deal with setting temperatures
bool settingTemps = false;
int hCount = tool->HeaterCount();
float standby[HEATERS];
float active[HEATERS];
tool->GetVariables(standby, active);
int hCount = tool->HeaterCount();
if(hCount > 0)
{
bool setting = false;
tool->GetVariables(standby, active);
if(gb->Seen('R'))
{
gb->GetFloatArray(standby, hCount);
setting = true;
settingTemps = true;
}
if(gb->Seen('S'))
{
gb->GetFloatArray(active, hCount);
setting = true;
settingTemps = true;
}
if(setting)
if(settingTemps)
{
tool->SetVariables(standby, active);
}
else
}
if (!settingOffset && !settingTemps)
{
reply.printf("Tool %d - Active/standby temperature(s): ", toolNumber);
// Print offsets and temperatures
reply.printf("Tool %d offsets: X%.1f Y%.1f Z%.1f", toolNumber, offset[X_AXIS], offset[Y_AXIS], offset[Z_AXIS]);
if (hCount != 0)
{
reply.cat(", active/standby temperature(s):");
for(int8_t heater = 0; heater < hCount; heater++)
{
reply.catf("%.1f/%.1f ", active[heater], standby[heater]);
reply.catf(" %.1f/%.1f", active[heater], standby[heater]);
}
}
}
@ -1403,19 +1485,28 @@ void GCodes::SetMACAddress(GCodeBuffer *gb)
// platform->Message(HOST_MESSAGE, scratchString);
}
void GCodes::HandleReply(bool error, bool fromLine, const char* reply, char gMOrT, int code, bool resend)
void GCodes::HandleReply(bool error, const GCodeBuffer *gb, const char* reply, char gMOrT, int code, bool resend)
{
if (gMOrT != 'M' || (code != 111 && code != 122)) // web server reply for M111 and M122 is handled before we get here
if (gb == auxGCode)
{
// Command was received from the aux interface (LCD display), so send the response only to the aux interface.
platform->GetAux()->Write(reply);
platform->GetAux()->Write('\n');
return;
}
// Deal with sending a reply to the web interface.
// The browser only fetches replies once a second or so. Therefore, when we send a web command in the middle of an SD card print,
// in order to be sure that we see the reply in the web interface, we must not send empty responses to the web interface unless
// the corresponding command also came from the web interface.
if ( (gMOrT != 'M' || (code != 111 && code != 122)) // web server reply for M111 and M122 is handled before we get here
&& (gb == webGCode || error)
)
{
platform->Message((error) ? WEB_ERROR_MESSAGE : WEB_MESSAGE, reply);
}
Compatibility c = platform->Emulating();
if (!fromLine)
{
c = me;
}
Compatibility c = (gb == serialGCode) ? platform->Emulating() : me;
const char* response = "ok";
if (resend)
{
@ -1435,7 +1526,7 @@ void GCodes::HandleReply(bool error, bool fromLine, const char* reply, char gMOr
platform->GetLine()->Write("Error: ");
}
platform->GetLine()->Write(reply);
platform->GetLine()->Write("\n");
platform->GetLine()->Write('\n');
return;
case marlin:
@ -1445,16 +1536,16 @@ void GCodes::HandleReply(bool error, bool fromLine, const char* reply, char gMOr
platform->GetLine()->Write(reply);
platform->GetLine()->Write("\nEnd file list\n");
platform->GetLine()->Write(response);
platform->GetLine()->Write("\n");
platform->GetLine()->Write('\n');
return;
}
if (gMOrT == 'M' && code == 28)
{
platform->GetLine()->Write(response);
platform->GetLine()->Write("\n");
platform->GetLine()->Write('\n');
platform->GetLine()->Write(reply);
platform->GetLine()->Write("\n");
platform->GetLine()->Write('\n');
return;
}
@ -1491,7 +1582,7 @@ void GCodes::HandleReply(bool error, bool fromLine, const char* reply, char gMOr
if (s != 0)
{
platform->Message(BOTH_ERROR_MESSAGE, "Emulation of %s is not yet supported.\n", s);
platform->Message(HOST_MESSAGE, "Emulation of %s is not yet supported.\n", s); // don't send this one to the web as well, it concerns only the USB interface
}
}
@ -1664,7 +1755,7 @@ bool GCodes::ActOnCode(GCodeBuffer *gb)
}
// An empty buffer gets discarded
HandleReply(false, gb == serialGCode, "", 'X', 0, false);
HandleReply(false, gb, "", 'X', 0, false);
return true;
}
@ -1779,7 +1870,7 @@ bool GCodes::HandleGcode(GCodeBuffer* gb)
}
if (result)
{
HandleReply(error, gb == serialGCode, reply.Pointer(), 'G', code, resend);
HandleReply(error, gb, reply.Pointer(), 'G', code, resend);
}
return result;
}
@ -2940,7 +3031,7 @@ bool GCodes::HandleMcode(GCodeBuffer* gb)
}
if (result)
{
HandleReply(error, gb == serialGCode, reply.Pointer(), 'M', code, resend);
HandleReply(error, gb, reply.Pointer(), 'M', code, resend);
}
return result;
}
@ -2952,7 +3043,7 @@ bool GCodes::HandleTcode(GCodeBuffer* gb)
bool result = ChangeTool(code);
if(result)
{
HandleReply(false, gb == serialGCode, "", 'T', code, false);
HandleReply(false, gb, "", 'T', code, false);
}
return result;
}

View file

@ -132,8 +132,8 @@ class GCodes
bool DisableDrives(); // Turn the motors off
void SetEthernetAddress(GCodeBuffer *gb, int mCode); // Does what it says
void SetMACAddress(GCodeBuffer *gb); // Deals with an M540
void HandleReply(bool error, bool fromLine, const char* reply, // If the GCode is from the serial interface, reply to it
char gMOrT, int code, bool resend);
void HandleReply(bool error, const GCodeBuffer *gb, // Reply to a gcode
const char* reply, char gMOrT, int code, bool resend);
bool OpenFileToWrite(const char* directory, // Start saving GCodes in a file
const char* fileName, GCodeBuffer *gb);
void WriteGCodeToFile(GCodeBuffer *gb); // Write this GCode into a file
@ -156,6 +156,7 @@ class GCodes
GCodeBuffer* webGCode; // The sources...
GCodeBuffer* fileGCode; // ...
GCodeBuffer* serialGCode; // ...
GCodeBuffer* auxGCode; // this one is for the LCD display on the async serial interface
GCodeBuffer* cannedCycleGCode; // ... of G Codes
bool moveAvailable; // Have we seen a move G Code and set it up?
float moveBuffer[DRIVES+1]; // Move coordinates; last is feed rate

View file

@ -175,21 +175,17 @@ void PID::Spin()
if(heatingUp && heater != HOT_BED) // FIXME - also check bed warmup time?
{
float tmp = standbyTemperature;
if(active)
{
tmp = activeTemperature;
}
tmp -= TEMPERATURE_CLOSE_ENOUGH;
if(temperature < tmp)
float tmp = (active) ? activeTemperature : standbyTemperature;
if(temperature < tmp - TEMPERATURE_CLOSE_ENOUGH)
{
float tim = platform->Time() - timeSetHeating;
if(tim > platform->TimeToHot())
float limit = platform->TimeToHot();
if(tim > limit && limit > 0.0)
{
platform->SetHeater(heater, 0.0);
temperatureFault = true;
switchedOff = true;
platform->Message(BOTH_MESSAGE, "Heating fault on heater %d, T = %.1f C; still not at temperature after %f seconds.\n", heater, temperature, tim);
platform->Message(BOTH_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);
}
}

View file

@ -99,7 +99,10 @@ Platform::Platform() :
tickState(0), fileStructureInitialised(false), active(false), errorCodeBits(0), debugCode(0),
messageString(messageStringBuffer, ARRAY_SIZE(messageStringBuffer))
{
line = new Line();
SerialUSB.begin(BAUD_RATE);
line = new Line(SerialUSB);
Serial.begin(BAUD_RATE);
aux = new Line(Serial);
// Files
@ -168,6 +171,7 @@ void Platform::Init()
}
line->Init();
aux->Init();
messageIndent = 0;
massStorage->Init();
@ -578,6 +582,7 @@ void Platform::Spin()
}
line->Spin();
aux->Spin();
ClassReport("Platform", longWait);
@ -587,10 +592,14 @@ void Platform::SoftwareReset(uint16_t reason)
{
if (reason != 0)
{
if (line->inUsbWrite)
if (line->inWrite)
{
reason |= SoftwareResetReason::inUsbOutput; // if we are resetting because we are stuck in a Spin function, record whether we are trying to send to USB
}
if (aux->inWrite)
{
reason |= SoftwareResetReason::inAuxOutput; // if we are resetting because we are stuck in a Spin function, record whether we are trying to send to aux
}
if (reprap.GetNetwork()->InLwip())
{
reason |= SoftwareResetReason::inLwipSpin;
@ -1838,7 +1847,8 @@ uint32_t FileStore::longestWriteTime = 0;
// Serial/USB class
Line::Line()
Line::Line(Stream& p_iface)
: iface(p_iface)
{
}
@ -1865,9 +1875,6 @@ void Line::InjectString(char* string)
int Line::Read(char& b)
{
// if(alternateInput != NULL)
// return alternateInput->Read(b);
if (inputNumChars == 0)
return 0;
b = inBuffer[inputGetIndex];
@ -1883,8 +1890,7 @@ void Line::Init()
outputGetIndex = 0;
outputNumChars = 0;
ignoringOutputLine = false;
SerialUSB.begin(BAUD_RATE);
inUsbWrite = false;
inWrite = false;
outputColumn = 0;
}
@ -1893,14 +1899,14 @@ void Line::Spin()
// Read the serial data in blocks to avoid excessive flow control
if (inputNumChars <= lineInBufsize / 2)
{
int16_t target = SerialUSB.available() + (int16_t) inputNumChars;
int16_t target = iface.available() + (int16_t) inputNumChars;
if (target > lineInBufsize)
{
target = lineInBufsize;
}
while ((int16_t) inputNumChars < target)
{
int incomingByte = SerialUSB.read();
int incomingByte = iface.read();
if (incomingByte < 0)
break;
inBuffer[(inputGetIndex + inputNumChars) % lineInBufsize] = (char) incomingByte;
@ -1949,15 +1955,15 @@ void Line::Write(char b, bool block)
TryFlushOutput();
if (block)
{
SerialUSB.flush();
iface.flush();
}
if (outputNumChars == 0 && SerialUSB.canWrite() != 0)
if (outputNumChars == 0 && iface.canWrite() != 0)
{
// We can write the character directly into the USB output buffer
++inUsbWrite;
SerialUSB.write(b);
--inUsbWrite;
// We can write the character directly into the output buffer
++inWrite;
iface.write(b);
--inWrite;
break;
}
else if ( outputNumChars + 2 < lineOutBufSize // save 2 spaces in the output buffer
@ -1991,7 +1997,7 @@ void Line::Write(char b, bool block)
TryFlushOutput();
if (block)
{
SerialUSB.flush();
iface.flush();
}
}
// else discard the character
@ -2011,11 +2017,11 @@ void Line::TryFlushOutput()
//while (SerialUSB.canWrite() == 0) {}
//end debug
while (outputNumChars != 0 && SerialUSB.canWrite() != 0)
while (outputNumChars != 0 && iface.canWrite() != 0)
{
++inUsbWrite;
SerialUSB.write(outBuffer[outputGetIndex]);
--inUsbWrite;
++inWrite;
iface.write(outBuffer[outputGetIndex]);
--inWrite;
outputGetIndex = (outputGetIndex + 1) % lineOutBufSize;
--outputNumChars;
}

View file

@ -163,7 +163,7 @@ const float defaultThermistor25RS[HEATERS] = {10000.0, 100000.0, 100000.0, 10000
const float defaultPidKis[HEATERS] = {5.0, 0.1, 0.1, 0.1, 0.1, 0.1}; // Integral PID constants
const float defaultPidKds[HEATERS] = {500.0, 100.0, 100.0, 100.0, 100.0, 100.0}; // Derivative PID constants
const float defaultPidKps[HEATERS] = {-1.0, 10.0, 10.0, 10.0, 10.0, 10.0}; // Proportional PID constants, negative values indicate use bang-bang instead of PID
const float defaultPidKts[HEATERS] = {2.7, 0.25, 0.25, 0.25, 0.25, 0.25}; // approximate PWM value needed to maintain temperature, per degC above room temperature
const float defaultPidKts[HEATERS] = {2.7, 0.4, 0.4, 0.4, 0.4, 0.4}; // approximate PWM value needed to maintain temperature, per degC above room temperature
const float defaultPidKss[HEATERS] = {1.0, 1.0, 1.0, 1.0, 1.0, 1.0}; // PWM scaling factor, to allow for variation in heater power and supply voltage
const float defaultFullBand[HEATERS] = {5.0, 30.0, 30.0, 30.0, 30.0, 30.0}; // errors larger than this cause heater to be on or off
const float defaultPidMin[HEATERS] = {0.0, 0.0, 0.0, 0.0, 0.0, 0.0}; // minimum value of I-term
@ -253,9 +253,10 @@ namespace SoftwareResetReason
enum
{
user = 0, // M999 command
inAuxOutput = 0x0800, // this bit is or'ed in if we were in aux output at the time
stuckInSpin = 0x1000, // we got stuck in a Spin() function for too long
inLwipSpin = 0x2000, // we got stuck in a call to lwip for too long
inUsbOutput = 0x4000 // this bit is or'ed in if we were in USB otuput at the time
inUsbOutput = 0x4000 // this bit is or'ed in if we were in USB output at the time
};
}
@ -286,7 +287,7 @@ friend class RepRap;
protected:
Line();
Line(Stream& p_iface);
void Init();
void Spin();
void InjectString(char* string);
@ -304,9 +305,10 @@ private:
uint16_t outputGetIndex;
uint16_t outputNumChars;
uint8_t inUsbWrite;
uint8_t inWrite;
bool ignoringOutputLine;
unsigned int outputColumn;
Stream& iface;
};
// Info returned by FindFirst/FindNext calls
@ -565,6 +567,7 @@ public:
// Communications and data storage
Line* GetLine() const;
Line* GetAux() const;
void SetIPAddress(byte ip[]);
const byte* IPAddress() const;
void SetNetMask(byte nm[]);
@ -764,6 +767,7 @@ private:
// Serial/USB
Line* line;
Line* aux;
uint8_t messageIndent;
// Files
@ -1106,6 +1110,11 @@ inline Line* Platform::GetLine() const
return line;
}
inline Line* Platform::GetAux() const
{
return aux;
}
inline void Platform::PushMessageIndent()
{
messageIndent += 2;

View file

@ -34,6 +34,10 @@ Tool::Tool(int toolNumber, long d[], int dCount, long h[], int hCount)
heaterCount = hCount;
heaterFault = false;
mixing = false;
for(size_t i = 0; i < AXES; ++i)
{
offset[i] = 0.0;
}
if(driveCount > 0)
{

18
Tool.h
View file

@ -31,7 +31,8 @@ class Tool
public:
Tool(int toolNumber, long d[], int dCount, long h[], int hCount);
void GetOffset(float& xx, float& yy, float& zz) const;
const float *GetOffset() const;
void SetOffset(const float offs[AXES]);
int DriveCount() const;
int Drive(int driveNumber) const;
bool ToolCanDrive() const;
@ -78,6 +79,7 @@ private:
Tool* next;
bool active;
bool heaterFault;
float offset[AXES];
};
inline int Tool::Drive(int driveNumber) const
@ -138,4 +140,18 @@ inline int Tool::DriveCount() const
return driveCount;
}
inline const float *Tool::GetOffset() const
{
return offset;
}
inline void Tool::SetOffset(const float offs[AXES])
{
for(size_t i = 0; i < AXES; ++i)
{
offset[i] = offs[i];
}
}
#endif /* TOOL_H_ */

View file

@ -1062,6 +1062,15 @@ void Webserver::HttpInterpreter::GetStatusResponse(StringRef& response, uint8_t
// Send XYZ positions
float liveCoordinates[DRIVES + 1];
reprap.GetMove()->LiveCoordinates(liveCoordinates);
const Tool* currentTool = reprap.GetCurrentTool();
if (currentTool != NULL)
{
const float *offset = currentTool->GetOffset();
for (size_t i = 0; i < AXES; ++i)
{
liveCoordinates[i] += offset[i];
}
}
response.catf("],\"pos\":"); // announce the XYZ position
ch = '[';
for (int8_t drive = 0; drive < AXES; drive++)
@ -1090,7 +1099,6 @@ void Webserver::HttpInterpreter::GetStatusResponse(StringRef& response, uint8_t
response.cat("]");
// Send the current tool number
Tool* currentTool = reprap.GetCurrentTool();
int toolNumber = (currentTool == NULL) ? 0 : currentTool->Number();
response.catf(",\"tool\":%d", toolNumber);
}