Removed interrupt nesting in the stepper ISR.

Add serial checkRx in stepper ISR.
Copied HardwareSerial to MarlinSerial (Needed for checkRx).
This commit is contained in:
Erik van der Zalm 2011-11-27 21:12:55 +01:00
parent aad4b75b94
commit f75f426dfa
16 changed files with 1007 additions and 754 deletions

View file

@ -232,7 +232,7 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th
// minimum time in microseconds that a movement needs to take if the buffer is emptied. Increase this number if you see blobs while printing high speed & high detail. It will slowdown on the detailed stuff. // minimum time in microseconds that a movement needs to take if the buffer is emptied. Increase this number if you see blobs while printing high speed & high detail. It will slowdown on the detailed stuff.
#define DEFAULT_MINSEGMENTTIME 20000 // Obsolete delete this #define DEFAULT_MINSEGMENTTIME 20000 // Obsolete delete this
#define DEFAULT_XYJERK 30.0 // (mm/sec) #define DEFAULT_XYJERK 20.0 // (mm/sec)
#define DEFAULT_ZJERK 0.4 // (mm/sec) #define DEFAULT_ZJERK 0.4 // (mm/sec)

View file

@ -4,6 +4,7 @@
#include "Marlin.h" #include "Marlin.h"
#include "planner.h" #include "planner.h"
#include "temperature.h" #include "temperature.h"
#include <EEPROM.h> #include <EEPROM.h>
template <class T> int EEPROM_writeAnything(int &ee, const T& value) template <class T> int EEPROM_writeAnything(int &ee, const T& value)

View file

@ -3,10 +3,12 @@
// Tonokip RepRap firmware rewrite based off of Hydra-mmm firmware. // Tonokip RepRap firmware rewrite based off of Hydra-mmm firmware.
// Licence: GPL // Licence: GPL
#define HardwareSerial_h // trick to disable the standard HWserial
#include <WProgram.h> #include <WProgram.h>
#include "fastio.h" #include "fastio.h"
#include <avr/pgmspace.h> #include <avr/pgmspace.h>
#include "Configuration.h" #include "Configuration.h"
#include "MarlinSerial.h"
//#define SERIAL_ECHO(x) Serial << "echo: " << x; //#define SERIAL_ECHO(x) Serial << "echo: " << x;
//#define SERIAL_ECHOLN(x) Serial << "echo: "<<x<<endl; //#define SERIAL_ECHOLN(x) Serial << "echo: "<<x<<endl;
@ -17,10 +19,10 @@
#define SERIAL_PROTOCOL(x) Serial.print(x); #define SERIAL_PROTOCOL(x) MSerial.print(x);
#define SERIAL_PROTOCOLPGM(x) serialprintPGM(PSTR(x)); #define SERIAL_PROTOCOLPGM(x) serialprintPGM(PSTR(x));
#define SERIAL_PROTOCOLLN(x) {Serial.print(x);Serial.write('\n');} #define SERIAL_PROTOCOLLN(x) {MSerial.print(x);MSerial.write('\n');}
#define SERIAL_PROTOCOLLNPGM(x) {serialprintPGM(PSTR(x));Serial.write('\n');} #define SERIAL_PROTOCOLLNPGM(x) {serialprintPGM(PSTR(x));MSerial.write('\n');}
const char errormagic[] PROGMEM ="Error:"; const char errormagic[] PROGMEM ="Error:";
const char echomagic[] PROGMEM ="echo:"; const char echomagic[] PROGMEM ="echo:";
@ -46,7 +48,7 @@ inline void serialprintPGM(const char *str)
char ch=pgm_read_byte(str); char ch=pgm_read_byte(str);
while(ch) while(ch)
{ {
Serial.write(ch); MSerial.write(ch);
ch=pgm_read_byte(++str); ch=pgm_read_byte(++str);
} }
} }

View file

@ -176,6 +176,7 @@ static unsigned long stoptime=0;
static uint8_t tmp_extruder; static uint8_t tmp_extruder;
//=========================================================================== //===========================================================================
//=============================ROUTINES============================= //=============================ROUTINES=============================
//=========================================================================== //===========================================================================
@ -199,13 +200,6 @@ extern "C"{
} }
} }
//adds an command to the main command buffer //adds an command to the main command buffer
//thats really done in a non-safe way. //thats really done in a non-safe way.
//needs overworking someday //needs overworking someday
@ -226,7 +220,7 @@ void enquecommand(const char *cmd)
void setup() void setup()
{ {
Serial.begin(BAUDRATE); MSerial.begin(BAUDRATE);
SERIAL_ECHO_START; SERIAL_ECHO_START;
SERIAL_ECHOLNPGM(VERSION_STRING); SERIAL_ECHOLNPGM(VERSION_STRING);
SERIAL_PROTOCOLLNPGM("start"); SERIAL_PROTOCOLLNPGM("start");
@ -289,15 +283,14 @@ void loop()
manage_heater(); manage_heater();
manage_inactivity(1); manage_inactivity(1);
checkHitEndstops(); checkHitEndstops();
checkStepperErrors();
LCD_STATUS; LCD_STATUS;
} }
inline void get_command() inline void get_command()
{ {
while( Serial.available() > 0 && buflen < BUFSIZE) { while( MSerial.available() > 0 && buflen < BUFSIZE) {
serial_char = Serial.read(); serial_char = MSerial.read();
if(serial_char == '\n' || serial_char == '\r' || serial_char == ':' || serial_count >= (MAX_CMD_SIZE - 1) ) if(serial_char == '\n' || serial_char == '\r' || serial_char == ':' || serial_count >= (MAX_CMD_SIZE - 1) )
{ {
if(!serial_count) return; //if empty line if(!serial_count) return; //if empty line
@ -1039,7 +1032,7 @@ inline void process_commands()
void FlushSerialRequestResend() void FlushSerialRequestResend()
{ {
//char cmdbuffer[bufindr][100]="Resend:"; //char cmdbuffer[bufindr][100]="Resend:";
Serial.flush(); MSerial.flush();
SERIAL_PROTOCOLPGM("Resend:"); SERIAL_PROTOCOLPGM("Resend:");
SERIAL_PROTOCOLLN(gcode_LastN + 1); SERIAL_PROTOCOLLN(gcode_LastN + 1);
ClearToSend(); ClearToSend();
@ -1088,7 +1081,7 @@ void prepare_move()
if (destination[Z_AXIS] > Z_MAX_LENGTH) destination[Z_AXIS] = Z_MAX_LENGTH; if (destination[Z_AXIS] > Z_MAX_LENGTH) destination[Z_AXIS] = Z_MAX_LENGTH;
} }
plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate*feedmultiply/60/100.0); plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate*feedmultiply/60/100.0, active_extruder);
for(int8_t i=0; i < NUM_AXIS; i++) { for(int8_t i=0; i < NUM_AXIS; i++) {
current_position[i] = destination[i]; current_position[i] = destination[i];
} }
@ -1098,7 +1091,7 @@ void prepare_arc_move(char isclockwise) {
float r = hypot(offset[X_AXIS], offset[Y_AXIS]); // Compute arc radius for mc_arc float r = hypot(offset[X_AXIS], offset[Y_AXIS]); // Compute arc radius for mc_arc
// Trace the arc // Trace the arc
mc_arc(current_position, destination, offset, X_AXIS, Y_AXIS, Z_AXIS, feedrate*feedmultiply/60/100.0, r, isclockwise); mc_arc(current_position, destination, offset, X_AXIS, Y_AXIS, Z_AXIS, feedrate*feedmultiply/60/100.0, r, isclockwise, active_extruder);
// As far as the parser is concerned, the position is now == target. In reality the // As far as the parser is concerned, the position is now == target. In reality the
// motion control system might still be processing the action and the real tool position // motion control system might still be processing the action and the real tool position
@ -1108,10 +1101,6 @@ void prepare_arc_move(char isclockwise) {
} }
} }
void manage_inactivity(byte debug) void manage_inactivity(byte debug)
{ {
if( (millis()-previous_millis_cmd) > max_inactive_time ) if( (millis()-previous_millis_cmd) > max_inactive_time )

213
Marlin/MarlinSerial.cpp Normal file
View file

@ -0,0 +1,213 @@
/*
HardwareSerial.cpp - Hardware serial library for Wiring
Copyright (c) 2006 Nicholas Zambetti. 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
Modified 23 November 2006 by David A. Mellis
Modified 28 September 2010 by Mark Sproul
*/
#include <stdlib.h>
#include <stdio.h>
#include <string.h>
#include <inttypes.h>
#include "wiring.h"
#include "wiring_private.h"
// this next line disables the entire HardwareSerial.cpp,
// this is so I can support Attiny series and any other chip without a uart
#if defined(UBRRH) || defined(UBRR0H) || defined(UBRR1H) || defined(UBRR2H) || defined(UBRR3H)
#include "MarlinSerial.h"
// Define constants and variables for buffering incoming serial data. We're
// using a ring buffer (I think), in which rx_buffer_head is the index of the
// location to which to write the next incoming character and rx_buffer_tail
// is the index of the location from which to read.
#define RX_BUFFER_SIZE 128
struct ring_buffer
{
unsigned char buffer[RX_BUFFER_SIZE];
int head;
int tail;
};
#if defined(UBRRH) || defined(UBRR0H)
ring_buffer rx_buffer = { { 0 }, 0, 0 };
#endif
inline void store_char(unsigned char c, ring_buffer *rx_buffer)
{
int i = (unsigned int)(rx_buffer->head + 1) % RX_BUFFER_SIZE;
// if we should be storing the received character into the location
// just before the tail (meaning that the head would advance to the
// current location of the tail), we're about to overflow the buffer
// and so we don't write the character or advance the head.
if (i != rx_buffer->tail) {
rx_buffer->buffer[rx_buffer->head] = c;
rx_buffer->head = i;
}
}
//#elif defined(SIG_USART_RECV)
#if defined(USART0_RX_vect)
// fixed by Mark Sproul this is on the 644/644p
//SIGNAL(SIG_USART_RECV)
SIGNAL(USART0_RX_vect)
{
#if defined(UDR0)
unsigned char c = UDR0;
#elif defined(UDR)
unsigned char c = UDR; // atmega8, atmega32
#else
#error UDR not defined
#endif
store_char(c, &rx_buffer);
}
#endif
// Constructors ////////////////////////////////////////////////////////////////
MarlinSerial::MarlinSerial(ring_buffer *rx_buffer,
volatile uint8_t *ubrrh, volatile uint8_t *ubrrl,
volatile uint8_t *ucsra, volatile uint8_t *ucsrb,
volatile uint8_t *udr,
uint8_t rxen, uint8_t txen, uint8_t rxcie, uint8_t udre, uint8_t u2x)
{
_rx_buffer = rx_buffer;
_ubrrh = ubrrh;
_ubrrl = ubrrl;
_ucsra = ucsra;
_ucsrb = ucsrb;
_udr = udr;
_rxen = rxen;
_txen = txen;
_rxcie = rxcie;
_udre = udre;
_u2x = u2x;
}
// Public Methods //////////////////////////////////////////////////////////////
void MarlinSerial::begin(long baud)
{
uint16_t baud_setting;
bool use_u2x = true;
#if F_CPU == 16000000UL
// hardcoded exception for compatibility with the bootloader shipped
// with the Duemilanove and previous boards and the firmware on the 8U2
// on the Uno and Mega 2560.
if (baud == 57600) {
use_u2x = false;
}
#endif
if (use_u2x) {
*_ucsra = 1 << _u2x;
baud_setting = (F_CPU / 4 / baud - 1) / 2;
} else {
*_ucsra = 0;
baud_setting = (F_CPU / 8 / baud - 1) / 2;
}
// assign the baud_setting, a.k.a. ubbr (USART Baud Rate Register)
*_ubrrh = baud_setting >> 8;
*_ubrrl = baud_setting;
sbi(*_ucsrb, _rxen);
sbi(*_ucsrb, _txen);
sbi(*_ucsrb, _rxcie);
}
void MarlinSerial::end()
{
cbi(*_ucsrb, _rxen);
cbi(*_ucsrb, _txen);
cbi(*_ucsrb, _rxcie);
}
int MarlinSerial::available(void)
{
return (unsigned int)(RX_BUFFER_SIZE + _rx_buffer->head - _rx_buffer->tail) % RX_BUFFER_SIZE;
}
int MarlinSerial::peek(void)
{
if (_rx_buffer->head == _rx_buffer->tail) {
return -1;
} else {
return _rx_buffer->buffer[_rx_buffer->tail];
}
}
int MarlinSerial::read(void)
{
// if the head isn't ahead of the tail, we don't have any characters
if (_rx_buffer->head == _rx_buffer->tail) {
return -1;
} else {
unsigned char c = _rx_buffer->buffer[_rx_buffer->tail];
_rx_buffer->tail = (unsigned int)(_rx_buffer->tail + 1) % RX_BUFFER_SIZE;
return c;
}
}
void MarlinSerial::flush()
{
// don't reverse this or there may be problems if the RX interrupt
// occurs after reading the value of rx_buffer_head but before writing
// the value to rx_buffer_tail; the previous value of rx_buffer_head
// may be written to rx_buffer_tail, making it appear as if the buffer
// don't reverse this or there may be problems if the RX interrupt
// occurs after reading the value of rx_buffer_head but before writing
// the value to rx_buffer_tail; the previous value of rx_buffer_head
// may be written to rx_buffer_tail, making it appear as if the buffer
// were full, not empty.
_rx_buffer->head = _rx_buffer->tail;
}
void MarlinSerial::write(uint8_t c)
{
while (!((*_ucsra) & (1 << _udre)))
;
*_udr = c;
}
void MarlinSerial::checkRx()
{
if((UCSR0A & (1<<RXC0)) != 0) {
unsigned char c = UDR0;
store_char(c, &rx_buffer);
}
}
// Preinstantiate Objects //////////////////////////////////////////////////////
#if defined(UBRR0H) && defined(UBRR0L)
MarlinSerial MSerial(&rx_buffer, &UBRR0H, &UBRR0L, &UCSR0A, &UCSR0B, &UDR0, RXEN0, TXEN0, RXCIE0, UDRE0, U2X0);
#else
#error no serial port defined (port 0)
#endif
#endif // whole file

66
Marlin/MarlinSerial.h Normal file
View file

@ -0,0 +1,66 @@
/*
HardwareSerial.h - Hardware serial library for Wiring
Copyright (c) 2006 Nicholas Zambetti. 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
Modified 28 September 2010 by Mark Sproul
*/
#ifndef MarlinSerial_h
#define MarlinSerial_h
#include <inttypes.h>
#include "Stream.h"
struct ring_buffer;
class MarlinSerial : public Stream
{
private:
ring_buffer *_rx_buffer;
volatile uint8_t *_ubrrh;
volatile uint8_t *_ubrrl;
volatile uint8_t *_ucsra;
volatile uint8_t *_ucsrb;
volatile uint8_t *_udr;
uint8_t _rxen;
uint8_t _txen;
uint8_t _rxcie;
uint8_t _udre;
uint8_t _u2x;
public:
MarlinSerial(ring_buffer *rx_buffer,
volatile uint8_t *ubrrh, volatile uint8_t *ubrrl,
volatile uint8_t *ucsra, volatile uint8_t *ucsrb,
volatile uint8_t *udr,
uint8_t rxen, uint8_t txen, uint8_t rxcie, uint8_t udre, uint8_t u2x);
void begin(long);
void end();
virtual int available(void);
virtual int peek(void);
virtual int read(void);
virtual void flush(void);
virtual void write(uint8_t);
virtual void checkRx(void);
using Print::write; // pull in write(str) and write(buf, size) from Print
};
#if defined(UBRRH) || defined(UBRR0H)
extern MarlinSerial MSerial;
#endif
#endif

View file

@ -18,6 +18,7 @@
* <http://www.gnu.org/licenses/>. * <http://www.gnu.org/licenses/>.
*/ */
#if ARDUINO < 100 #if ARDUINO < 100
#define HardwareSerial_h // trick to disable the standard HWserial
#include <WProgram.h> #include <WProgram.h>
#else // ARDUINO #else // ARDUINO
#include <Arduino.h> #include <Arduino.h>

View file

@ -306,7 +306,7 @@ void SdBaseFile::getpos(fpos_t* pos) {
* LS_R - Recursive list of subdirectories. * LS_R - Recursive list of subdirectories.
*/ */
void SdBaseFile::ls(uint8_t flags) { void SdBaseFile::ls(uint8_t flags) {
ls(&Serial, flags, 0); ls(&MSerial, flags, 0);
} }
//------------------------------------------------------------------------------ //------------------------------------------------------------------------------
/** List directory contents. /** List directory contents.
@ -949,7 +949,7 @@ int SdBaseFile::peek() {
*/ */
void SdBaseFile::printDirName(const dir_t& dir, void SdBaseFile::printDirName(const dir_t& dir,
uint8_t width, bool printSlash) { uint8_t width, bool printSlash) {
printDirName(&Serial, dir, width, printSlash); printDirName(&MSerial, dir, width, printSlash);
} }
//------------------------------------------------------------------------------ //------------------------------------------------------------------------------
/** %Print the name field of a directory entry in 8.3 format. /** %Print the name field of a directory entry in 8.3 format.
@ -993,7 +993,7 @@ static void print2u(Print* pr, uint8_t v) {
* \param[in] fatDate The date field from a directory entry. * \param[in] fatDate The date field from a directory entry.
*/ */
void SdBaseFile::printFatDate(uint16_t fatDate) { void SdBaseFile::printFatDate(uint16_t fatDate) {
printFatDate(&Serial, fatDate); printFatDate(&MSerial, fatDate);
} }
//------------------------------------------------------------------------------ //------------------------------------------------------------------------------
/** %Print a directory date field. /** %Print a directory date field.
@ -1018,7 +1018,7 @@ void SdBaseFile::printFatDate(Print* pr, uint16_t fatDate) {
* \param[in] fatTime The time field from a directory entry. * \param[in] fatTime The time field from a directory entry.
*/ */
void SdBaseFile::printFatTime(uint16_t fatTime) { void SdBaseFile::printFatTime(uint16_t fatTime) {
printFatTime(&Serial, fatTime); printFatTime(&MSerial, fatTime);
} }
//------------------------------------------------------------------------------ //------------------------------------------------------------------------------
/** %Print a directory time field. /** %Print a directory time field.
@ -1044,7 +1044,7 @@ void SdBaseFile::printFatTime(Print* pr, uint16_t fatTime) {
bool SdBaseFile::printName() { bool SdBaseFile::printName() {
char name[13]; char name[13];
if (!getFilename(name)) return false; if (!getFilename(name)) return false;
Serial.print(name); MSerial.print(name);
return true; return true;
} }
//------------------------------------------------------------------------------ //------------------------------------------------------------------------------

View file

@ -25,7 +25,9 @@
*/ */
#include <avr/pgmspace.h> #include <avr/pgmspace.h>
#if ARDUINO < 100 #if ARDUINO < 100
#define HardwareSerial_h // trick to disable the standard HWserial
#include <WProgram.h> #include <WProgram.h>
#include "MarlinSerial.h"
#else // ARDUINO #else // ARDUINO
#include <Arduino.h> #include <Arduino.h>
#endif // ARDUINO #endif // ARDUINO

View file

@ -62,7 +62,7 @@ void SdFatUtil::println_P(Print* pr, PGM_P str) {
* \param[in] str Pointer to string stored in flash memory. * \param[in] str Pointer to string stored in flash memory.
*/ */
void SdFatUtil::SerialPrint_P(PGM_P str) { void SdFatUtil::SerialPrint_P(PGM_P str) {
print_P(&Serial, str); print_P(&MSerial, str);
} }
//------------------------------------------------------------------------------ //------------------------------------------------------------------------------
/** %Print a string in flash memory to Serial followed by a CR/LF. /** %Print a string in flash memory to Serial followed by a CR/LF.
@ -70,5 +70,5 @@ void SdFatUtil::SerialPrint_P(PGM_P str) {
* \param[in] str Pointer to string stored in flash memory. * \param[in] str Pointer to string stored in flash memory.
*/ */
void SdFatUtil::SerialPrintln_P(PGM_P str) { void SdFatUtil::SerialPrintln_P(PGM_P str) {
println_P(&Serial, str); println_P(&MSerial, str);
} }

View file

@ -25,7 +25,9 @@
*/ */
#include <avr/pgmspace.h> #include <avr/pgmspace.h>
#if ARDUINO < 100 #if ARDUINO < 100
#define HardwareSerial_h // trick to disable the standard HWserial
#include <WProgram.h> #include <WProgram.h>
#include "MarlinSerial.h"
#else // ARDUINO #else // ARDUINO
#include <Arduino.h> #include <Arduino.h>
#endif // ARDUINO #endif // ARDUINO

View file

@ -27,7 +27,7 @@
// The arc is approximated by generating a huge number of tiny, linear segments. The length of each // The arc is approximated by generating a huge number of tiny, linear segments. The length of each
// segment is configured in settings.mm_per_arc_segment. // segment is configured in settings.mm_per_arc_segment.
void mc_arc(float *position, float *target, float *offset, uint8_t axis_0, uint8_t axis_1, void mc_arc(float *position, float *target, float *offset, uint8_t axis_0, uint8_t axis_1,
uint8_t axis_linear, float feed_rate, float radius, uint8_t isclockwise) uint8_t axis_linear, float feed_rate, float radius, uint8_t isclockwise, uint8_t extruder)
{ {
// int acceleration_manager_was_enabled = plan_is_acceleration_manager_enabled(); // int acceleration_manager_was_enabled = plan_is_acceleration_manager_enabled();
// plan_set_acceleration_manager_enabled(false); // disable acceleration management for the duration of the arc // plan_set_acceleration_manager_enabled(false); // disable acceleration management for the duration of the arc
@ -123,11 +123,11 @@ void mc_arc(float *position, float *target, float *offset, uint8_t axis_0, uint8
arc_target[axis_1] = center_axis1 + r_axis1; arc_target[axis_1] = center_axis1 + r_axis1;
arc_target[axis_linear] += linear_per_segment; arc_target[axis_linear] += linear_per_segment;
arc_target[E_AXIS] += extruder_per_segment; arc_target[E_AXIS] += extruder_per_segment;
plan_buffer_line(arc_target[X_AXIS], arc_target[Y_AXIS], arc_target[Z_AXIS], arc_target[E_AXIS], feed_rate); plan_buffer_line(arc_target[X_AXIS], arc_target[Y_AXIS], arc_target[Z_AXIS], arc_target[E_AXIS], feed_rate, extruder);
} }
// Ensure last segment arrives at target location. // Ensure last segment arrives at target location.
plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], feed_rate); plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], feed_rate, extruder);
// plan_set_acceleration_manager_enabled(acceleration_manager_was_enabled); // plan_set_acceleration_manager_enabled(acceleration_manager_was_enabled);
} }

View file

@ -27,6 +27,6 @@
// the direction of helical travel, radius == circle radius, isclockwise boolean. Used // the direction of helical travel, radius == circle radius, isclockwise boolean. Used
// for vector transformation direction. // for vector transformation direction.
void mc_arc(float *position, float *target, float *offset, unsigned char axis_0, unsigned char axis_1, void mc_arc(float *position, float *target, float *offset, unsigned char axis_0, unsigned char axis_1,
unsigned char axis_linear, float feed_rate, float radius, unsigned char isclockwise); unsigned char axis_linear, float feed_rate, float radius, unsigned char isclockwise, uint8_t extruder);
#endif #endif

View file

@ -451,7 +451,7 @@ float junction_deviation = 0.1;
// Add a new linear movement to the buffer. steps_x, _y and _z is the absolute position in // Add a new linear movement to the buffer. steps_x, _y and _z is the absolute position in
// mm. Microseconds specify how many microseconds the move should take to perform. To aid acceleration // mm. Microseconds specify how many microseconds the move should take to perform. To aid acceleration
// calculation the caller must also provide the physical length of the line in millimeters. // calculation the caller must also provide the physical length of the line in millimeters.
void plan_buffer_line(const float &x, const float &y, const float &z, const float &e, float feed_rate) void plan_buffer_line(const float &x, const float &y, const float &z, const float &e, float feed_rate, const uint8_t &extruder)
{ {
// Calculate the buffer head after we push this byte // Calculate the buffer head after we push this byte
int next_buffer_head = next_block_index(block_buffer_head); int next_buffer_head = next_block_index(block_buffer_head);
@ -532,7 +532,7 @@ void plan_buffer_line(const float &x, const float &y, const float &z, const floa
// slow down when de buffer starts to empty, rather than wait at the corner for a buffer refill // slow down when de buffer starts to empty, rather than wait at the corner for a buffer refill
int moves_queued=(block_buffer_head-block_buffer_tail + BLOCK_BUFFER_SIZE) & (BLOCK_BUFFER_SIZE - 1); int moves_queued=(block_buffer_head-block_buffer_tail + BLOCK_BUFFER_SIZE) & (BLOCK_BUFFER_SIZE - 1);
if(moves_queued < (BLOCK_BUFFER_SIZE * 0.5)) feed_rate = feed_rate*moves_queued / (BLOCK_BUFFER_SIZE * 0.5); if(moves_queued < (BLOCK_BUFFER_SIZE * 0.5) && moves_queued > 1) feed_rate = feed_rate*moves_queued / (BLOCK_BUFFER_SIZE * 0.5);
#endif #endif
/* /*

View file

@ -66,7 +66,7 @@ void plan_init();
// Add a new linear movement to the buffer. x, y and z is the signed, absolute target position in // Add a new linear movement to the buffer. x, y and z is the signed, absolute target position in
// millimaters. Feed rate specifies the speed of the motion. // millimaters. Feed rate specifies the speed of the motion.
void plan_buffer_line(const float &x, const float &y, const float &z, const float &e, float feed_rate); void plan_buffer_line(const float &x, const float &y, const float &z, const float &e, float feed_rate, const uint8_t &extruder);
// Set position. Used for G92 instructions. // Set position. Used for G92 instructions.
void plan_set_position(const float &x, const float &y, const float &z, const float &e); void plan_set_position(const float &x, const float &y, const float &z, const float &e);

View file

@ -52,7 +52,7 @@ static long counter_x, // Counter variables for the bresenham line tracer
counter_y, counter_y,
counter_z, counter_z,
counter_e; counter_e;
static unsigned long step_events_completed; // The number of step events executed in the current block volatile static unsigned long step_events_completed; // The number of step events executed in the current block
#ifdef ADVANCE #ifdef ADVANCE
static long advance_rate, advance, final_advance = 0; static long advance_rate, advance, final_advance = 0;
static short old_advance = 0; static short old_advance = 0;
@ -63,6 +63,7 @@ static long acceleration_time, deceleration_time;
//static unsigned long accelerate_until, decelerate_after, acceleration_rate, initial_rate, final_rate, nominal_rate; //static unsigned long accelerate_until, decelerate_after, acceleration_rate, initial_rate, final_rate, nominal_rate;
static unsigned short acc_step_rate; // needed for deccelaration start point static unsigned short acc_step_rate; // needed for deccelaration start point
static char step_loops; static char step_loops;
static unsigned short OCR1A_nominal;
volatile long endstops_trigsteps[3]={0,0,0}; volatile long endstops_trigsteps[3]={0,0,0};
volatile long endstops_stepsTotal,endstops_stepsDone; volatile long endstops_stepsTotal,endstops_stepsDone;
@ -77,10 +78,6 @@ static bool old_y_max_endstop=false;
static bool old_z_min_endstop=false; static bool old_z_min_endstop=false;
static bool old_z_max_endstop=false; static bool old_z_max_endstop=false;
static bool busy_error=false;
unsigned short OCR1A_error=12345;
unsigned short OCR1A_nominal;
volatile long count_position[NUM_AXIS] = { 0, 0, 0, 0}; volatile long count_position[NUM_AXIS] = { 0, 0, 0, 0};
volatile char count_direction[NUM_AXIS] = { 1, 1, 1, 1}; volatile char count_direction[NUM_AXIS] = { 1, 1, 1, 1};
@ -164,15 +161,6 @@ asm volatile ( \
#define ENABLE_STEPPER_DRIVER_INTERRUPT() TIMSK1 |= (1<<OCIE1A) #define ENABLE_STEPPER_DRIVER_INTERRUPT() TIMSK1 |= (1<<OCIE1A)
#define DISABLE_STEPPER_DRIVER_INTERRUPT() TIMSK1 &= ~(1<<OCIE1A) #define DISABLE_STEPPER_DRIVER_INTERRUPT() TIMSK1 &= ~(1<<OCIE1A)
void checkStepperErrors()
{
if(busy_error) {
SERIAL_ERROR_START
SERIAL_ERROR(OCR1A_error);
SERIAL_ERRORLNPGM(" ISR overtaking itself.");
busy_error = false;
}
}
void checkHitEndstops() void checkHitEndstops()
{ {
@ -255,7 +243,7 @@ inline unsigned short calc_timer(unsigned short step_rate) {
timer = (unsigned short)pgm_read_word_near(table_address); timer = (unsigned short)pgm_read_word_near(table_address);
timer -= (((unsigned short)pgm_read_word_near(table_address+2) * (unsigned char)(step_rate & 0x0007))>>3); timer -= (((unsigned short)pgm_read_word_near(table_address+2) * (unsigned char)(step_rate & 0x0007))>>3);
} }
if(timer < 100) { timer = 100; Serial.print("Steprate to high : "); Serial.println(step_rate); }//(20kHz this should never happen) if(timer < 100) { timer = 100; MSerial.print("Steprate to high : "); MSerial.println(step_rate); }//(20kHz this should never happen)
return timer; return timer;
} }
@ -278,16 +266,6 @@ inline void trapezoid_generator_reset() {
// It pops blocks from the block_buffer and executes them by pulsing the stepper pins appropriately. // It pops blocks from the block_buffer and executes them by pulsing the stepper pins appropriately.
ISR(TIMER1_COMPA_vect) ISR(TIMER1_COMPA_vect)
{ {
if(busy){
OCR1A_error = OCR1A;
busy_error = true;
OCR1A = 30000;
return;
} // The busy-flag is used to avoid reentering this interrupt
busy = true;
sei(); // Re enable interrupts (normally disabled while inside an interrupt handler)
// If there is no current block, attempt to pop one from the buffer // If there is no current block, attempt to pop one from the buffer
if (current_block == NULL) { if (current_block == NULL) {
// Anything in the buffer? // Anything in the buffer?
@ -304,7 +282,7 @@ ISR(TIMER1_COMPA_vect)
// #endif // #endif
} }
else { else {
// DISABLE_STEPPER_DRIVER_INTERRUPT(); OCR1A=2000; // 1kHz.
} }
} }
@ -404,8 +382,8 @@ ISR(TIMER1_COMPA_vect)
count_direction[E_AXIS]=-1; count_direction[E_AXIS]=-1;
} }
#endif //!ADVANCE #endif //!ADVANCE
for(int8_t i=0; i < step_loops; i++) { // Take multiple steps per interrupt (For high speed moves) for(int8_t i=0; i < step_loops; i++) { // Take multiple steps per interrupt (For high speed moves)
MSerial.checkRx();
/* /*
counter_e += current_block->steps_e; counter_e += current_block->steps_e;
if (counter_e > 0) { if (counter_e > 0) {
@ -470,6 +448,7 @@ ISR(TIMER1_COMPA_vect)
unsigned short timer; unsigned short timer;
unsigned short step_rate; unsigned short step_rate;
if (step_events_completed <= current_block->accelerate_until) { if (step_events_completed <= current_block->accelerate_until) {
MultiU24X24toH16(acc_step_rate, acceleration_time, current_block->acceleration_rate); MultiU24X24toH16(acc_step_rate, acceleration_time, current_block->acceleration_rate);
acc_step_rate += current_block->initial_rate; acc_step_rate += current_block->initial_rate;
@ -519,8 +498,6 @@ ISR(TIMER1_COMPA_vect)
plan_discard_current_block(); plan_discard_current_block();
} }
} }
cli(); // disable interrupts
busy=false;
} }
#ifdef ADVANCE #ifdef ADVANCE