Removed interrupt nesting in the stepper ISR.

Add serial checkRx in stepper ISR.
Copied HardwareSerial to MarlinSerial (Needed for checkRx).
master
Erik van der Zalm 13 years ago
parent aad4b75b94
commit f75f426dfa

@ -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)

@ -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)

@ -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);
} }
} }

@ -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 )

@ -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

@ -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

@ -1,642 +1,643 @@
/* Arduino Sd2Card Library /* Arduino Sd2Card Library
* Copyright (C) 2009 by William Greiman * Copyright (C) 2009 by William Greiman
* *
* This file is part of the Arduino Sd2Card Library * This file is part of the Arduino Sd2Card Library
* *
* This Library is free software: you can redistribute it and/or modify * This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by * it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or * the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version. * (at your option) any later version.
* *
* This Library is distributed in the hope that it will be useful, * This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of * but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details. * GNU General Public License for more details.
* *
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with the Arduino Sd2Card Library. If not, see * along with the Arduino Sd2Card Library. If not, see
* <http://www.gnu.org/licenses/>. * <http://www.gnu.org/licenses/>.
*/ */
#if ARDUINO < 100 #if ARDUINO < 100
#include <WProgram.h> #define HardwareSerial_h // trick to disable the standard HWserial
#else // ARDUINO #include <WProgram.h>
#include <Arduino.h> #else // ARDUINO
#endif // ARDUINO #include <Arduino.h>
#include "Sd2Card.h" #endif // ARDUINO
//------------------------------------------------------------------------------ #include "Sd2Card.h"
#ifndef SOFTWARE_SPI //------------------------------------------------------------------------------
// functions for hardware SPI #ifndef SOFTWARE_SPI
//------------------------------------------------------------------------------ // functions for hardware SPI
// make sure SPCR rate is in expected bits //------------------------------------------------------------------------------
#if (SPR0 != 0 || SPR1 != 1) // make sure SPCR rate is in expected bits
#error unexpected SPCR bits #if (SPR0 != 0 || SPR1 != 1)
#endif #error unexpected SPCR bits
/** #endif
* Initialize hardware SPI /**
* Set SCK rate to F_CPU/pow(2, 1 + spiRate) for spiRate [0,6] * Initialize hardware SPI
*/ * Set SCK rate to F_CPU/pow(2, 1 + spiRate) for spiRate [0,6]
static void spiInit(uint8_t spiRate) { */
// See avr processor documentation static void spiInit(uint8_t spiRate) {
SPCR = (1 << SPE) | (1 << MSTR) | (spiRate >> 1); // See avr processor documentation
SPSR = spiRate & 1 || spiRate == 6 ? 0 : 1 << SPI2X; SPCR = (1 << SPE) | (1 << MSTR) | (spiRate >> 1);
} SPSR = spiRate & 1 || spiRate == 6 ? 0 : 1 << SPI2X;
//------------------------------------------------------------------------------ }
/** SPI receive a byte */ //------------------------------------------------------------------------------
static uint8_t spiRec() { /** SPI receive a byte */
SPDR = 0XFF; static uint8_t spiRec() {
while (!(SPSR & (1 << SPIF))); SPDR = 0XFF;
return SPDR; while (!(SPSR & (1 << SPIF)));
} return SPDR;
//------------------------------------------------------------------------------ }
/** SPI read data - only one call so force inline */ //------------------------------------------------------------------------------
static inline __attribute__((always_inline)) /** SPI read data - only one call so force inline */
void spiRead(uint8_t* buf, uint16_t nbyte) { static inline __attribute__((always_inline))
if (nbyte-- == 0) return; void spiRead(uint8_t* buf, uint16_t nbyte) {
SPDR = 0XFF; if (nbyte-- == 0) return;
for (uint16_t i = 0; i < nbyte; i++) { SPDR = 0XFF;
while (!(SPSR & (1 << SPIF))); for (uint16_t i = 0; i < nbyte; i++) {
buf[i] = SPDR; while (!(SPSR & (1 << SPIF)));
SPDR = 0XFF; buf[i] = SPDR;
} SPDR = 0XFF;
while (!(SPSR & (1 << SPIF))); }
buf[nbyte] = SPDR; while (!(SPSR & (1 << SPIF)));
} buf[nbyte] = SPDR;
//------------------------------------------------------------------------------ }
/** SPI send a byte */ //------------------------------------------------------------------------------
static void spiSend(uint8_t b) { /** SPI send a byte */
SPDR = b; static void spiSend(uint8_t b) {
while (!(SPSR & (1 << SPIF))); SPDR = b;
} while (!(SPSR & (1 << SPIF)));
//------------------------------------------------------------------------------ }
/** SPI send block - only one call so force inline */ //------------------------------------------------------------------------------
static inline __attribute__((always_inline)) /** SPI send block - only one call so force inline */
void spiSendBlock(uint8_t token, const uint8_t* buf) { static inline __attribute__((always_inline))
SPDR = token; void spiSendBlock(uint8_t token, const uint8_t* buf) {
for (uint16_t i = 0; i < 512; i += 2) { SPDR = token;
while (!(SPSR & (1 << SPIF))); for (uint16_t i = 0; i < 512; i += 2) {
SPDR = buf[i]; while (!(SPSR & (1 << SPIF)));
while (!(SPSR & (1 << SPIF))); SPDR = buf[i];
SPDR = buf[i + 1]; while (!(SPSR & (1 << SPIF)));
} SPDR = buf[i + 1];
while (!(SPSR & (1 << SPIF))); }
} while (!(SPSR & (1 << SPIF)));
//------------------------------------------------------------------------------ }
#else // SOFTWARE_SPI //------------------------------------------------------------------------------
//------------------------------------------------------------------------------ #else // SOFTWARE_SPI
/** nop to tune soft SPI timing */ //------------------------------------------------------------------------------
#define nop asm volatile ("nop\n\t") /** nop to tune soft SPI timing */
//------------------------------------------------------------------------------ #define nop asm volatile ("nop\n\t")
/** Soft SPI receive byte */ //------------------------------------------------------------------------------
static uint8_t spiRec() { /** Soft SPI receive byte */
uint8_t data = 0; static uint8_t spiRec() {
// no interrupts during byte receive - about 8 us uint8_t data = 0;
cli(); // no interrupts during byte receive - about 8 us
// output pin high - like sending 0XFF cli();
fastDigitalWrite(SPI_MOSI_PIN, HIGH); // output pin high - like sending 0XFF
fastDigitalWrite(SPI_MOSI_PIN, HIGH);
for (uint8_t i = 0; i < 8; i++) {
fastDigitalWrite(SPI_SCK_PIN, HIGH); for (uint8_t i = 0; i < 8; i++) {
fastDigitalWrite(SPI_SCK_PIN, HIGH);
// adjust so SCK is nice
nop; // adjust so SCK is nice
nop; nop;
nop;
data <<= 1;
data <<= 1;
if (fastDigitalRead(SPI_MISO_PIN)) data |= 1;
if (fastDigitalRead(SPI_MISO_PIN)) data |= 1;
fastDigitalWrite(SPI_SCK_PIN, LOW);
} fastDigitalWrite(SPI_SCK_PIN, LOW);
// enable interrupts }
sei(); // enable interrupts
return data; sei();
} return data;
//------------------------------------------------------------------------------ }
/** Soft SPI read data */ //------------------------------------------------------------------------------
static void spiRead(uint8_t* buf, uint16_t nbyte) { /** Soft SPI read data */
for (uint16_t i = 0; i < nbyte; i++) { static void spiRead(uint8_t* buf, uint16_t nbyte) {
buf[i] = spiRec(); for (uint16_t i = 0; i < nbyte; i++) {
} buf[i] = spiRec();
} }
//------------------------------------------------------------------------------ }
/** Soft SPI send byte */ //------------------------------------------------------------------------------
static void spiSend(uint8_t data) { /** Soft SPI send byte */
// no interrupts during byte send - about 8 us static void spiSend(uint8_t data) {
cli(); // no interrupts during byte send - about 8 us
for (uint8_t i = 0; i < 8; i++) { cli();
fastDigitalWrite(SPI_SCK_PIN, LOW); for (uint8_t i = 0; i < 8; i++) {
fastDigitalWrite(SPI_SCK_PIN, LOW);
fastDigitalWrite(SPI_MOSI_PIN, data & 0X80);
fastDigitalWrite(SPI_MOSI_PIN, data & 0X80);
data <<= 1;
data <<= 1;
fastDigitalWrite(SPI_SCK_PIN, HIGH);
} fastDigitalWrite(SPI_SCK_PIN, HIGH);
// hold SCK high for a few ns }
nop; // hold SCK high for a few ns
nop; nop;
nop; nop;
nop; nop;
nop;
fastDigitalWrite(SPI_SCK_PIN, LOW);
// enable interrupts fastDigitalWrite(SPI_SCK_PIN, LOW);
sei(); // enable interrupts
} sei();
//------------------------------------------------------------------------------ }
/** Soft SPI send block */ //------------------------------------------------------------------------------
void spiSendBlock(uint8_t token, const uint8_t* buf) { /** Soft SPI send block */
spiSend(token); void spiSendBlock(uint8_t token, const uint8_t* buf) {
for (uint16_t i = 0; i < 512; i++) { spiSend(token);
spiSend(buf[i]); for (uint16_t i = 0; i < 512; i++) {
} spiSend(buf[i]);
} }
#endif // SOFTWARE_SPI }
//------------------------------------------------------------------------------ #endif // SOFTWARE_SPI
// send command and return error code. Return zero for OK //------------------------------------------------------------------------------
uint8_t Sd2Card::cardCommand(uint8_t cmd, uint32_t arg) { // send command and return error code. Return zero for OK
// select card uint8_t Sd2Card::cardCommand(uint8_t cmd, uint32_t arg) {
chipSelectLow(); // select card
chipSelectLow();
// wait up to 300 ms if busy
waitNotBusy(300); // wait up to 300 ms if busy
waitNotBusy(300);
// send command
spiSend(cmd | 0x40); // send command
spiSend(cmd | 0x40);
// send argument
for (int8_t s = 24; s >= 0; s -= 8) spiSend(arg >> s); // send argument
for (int8_t s = 24; s >= 0; s -= 8) spiSend(arg >> s);
// send CRC
uint8_t crc = 0XFF; // send CRC
if (cmd == CMD0) crc = 0X95; // correct crc for CMD0 with arg 0 uint8_t crc = 0XFF;
if (cmd == CMD8) crc = 0X87; // correct crc for CMD8 with arg 0X1AA if (cmd == CMD0) crc = 0X95; // correct crc for CMD0 with arg 0
spiSend(crc); if (cmd == CMD8) crc = 0X87; // correct crc for CMD8 with arg 0X1AA
spiSend(crc);
// skip stuff byte for stop read
if (cmd == CMD12) spiRec(); // skip stuff byte for stop read
if (cmd == CMD12) spiRec();
// wait for response
for (uint8_t i = 0; ((status_ = spiRec()) & 0X80) && i != 0XFF; i++); // wait for response
return status_; for (uint8_t i = 0; ((status_ = spiRec()) & 0X80) && i != 0XFF; i++);
} return status_;
//------------------------------------------------------------------------------ }
/** //------------------------------------------------------------------------------
* Determine the size of an SD flash memory card. /**
* * Determine the size of an SD flash memory card.
* \return The number of 512 byte data blocks in the card *
* or zero if an error occurs. * \return The number of 512 byte data blocks in the card
*/ * or zero if an error occurs.
uint32_t Sd2Card::cardSize() { */
csd_t csd; uint32_t Sd2Card::cardSize() {
if (!readCSD(&csd)) return 0; csd_t csd;
if (csd.v1.csd_ver == 0) { if (!readCSD(&csd)) return 0;
uint8_t read_bl_len = csd.v1.read_bl_len; if (csd.v1.csd_ver == 0) {
uint16_t c_size = (csd.v1.c_size_high << 10) uint8_t read_bl_len = csd.v1.read_bl_len;
| (csd.v1.c_size_mid << 2) | csd.v1.c_size_low; uint16_t c_size = (csd.v1.c_size_high << 10)
uint8_t c_size_mult = (csd.v1.c_size_mult_high << 1) | (csd.v1.c_size_mid << 2) | csd.v1.c_size_low;
| csd.v1.c_size_mult_low; uint8_t c_size_mult = (csd.v1.c_size_mult_high << 1)
return (uint32_t)(c_size + 1) << (c_size_mult + read_bl_len - 7); | csd.v1.c_size_mult_low;
} else if (csd.v2.csd_ver == 1) { return (uint32_t)(c_size + 1) << (c_size_mult + read_bl_len - 7);
uint32_t c_size = ((uint32_t)csd.v2.c_size_high << 16) } else if (csd.v2.csd_ver == 1) {
| (csd.v2.c_size_mid << 8) | csd.v2.c_size_low; uint32_t c_size = ((uint32_t)csd.v2.c_size_high << 16)
return (c_size + 1) << 10; | (csd.v2.c_size_mid << 8) | csd.v2.c_size_low;
} else { return (c_size + 1) << 10;
error(SD_CARD_ERROR_BAD_CSD); } else {
return 0; error(SD_CARD_ERROR_BAD_CSD);
} return 0;
} }
//------------------------------------------------------------------------------ }
void Sd2Card::chipSelectHigh() { //------------------------------------------------------------------------------
digitalWrite(chipSelectPin_, HIGH); void Sd2Card::chipSelectHigh() {
} digitalWrite(chipSelectPin_, HIGH);
//------------------------------------------------------------------------------ }
void Sd2Card::chipSelectLow() { //------------------------------------------------------------------------------
#ifndef SOFTWARE_SPI void Sd2Card::chipSelectLow() {
spiInit(spiRate_); #ifndef SOFTWARE_SPI
#endif // SOFTWARE_SPI spiInit(spiRate_);
digitalWrite(chipSelectPin_, LOW); #endif // SOFTWARE_SPI
} digitalWrite(chipSelectPin_, LOW);
//------------------------------------------------------------------------------ }
/** Erase a range of blocks. //------------------------------------------------------------------------------
* /** Erase a range of blocks.
* \param[in] firstBlock The address of the first block in the range. *
* \param[in] lastBlock The address of the last block in the range. * \param[in] firstBlock The address of the first block in the range.
* * \param[in] lastBlock The address of the last block in the range.
* \note This function requests the SD card to do a flash erase for a *
* range of blocks. The data on the card after an erase operation is * \note This function requests the SD card to do a flash erase for a
* either 0 or 1, depends on the card vendor. The card must support * range of blocks. The data on the card after an erase operation is
* single block erase. * either 0 or 1, depends on the card vendor. The card must support
* * single block erase.
* \return The value one, true, is returned for success and *
* the value zero, false, is returned for failure. * \return The value one, true, is returned for success and
*/ * the value zero, false, is returned for failure.
bool Sd2Card::erase(uint32_t firstBlock, uint32_t lastBlock) { */
csd_t csd; bool Sd2Card::erase(uint32_t firstBlock, uint32_t lastBlock) {
if (!readCSD(&csd)) goto fail; csd_t csd;
// check for single block erase if (!readCSD(&csd)) goto fail;
if (!csd.v1.erase_blk_en) { // check for single block erase
// erase size mask if (!csd.v1.erase_blk_en) {
uint8_t m = (csd.v1.sector_size_high << 1) | csd.v1.sector_size_low; // erase size mask
if ((firstBlock & m) != 0 || ((lastBlock + 1) & m) != 0) { uint8_t m = (csd.v1.sector_size_high << 1) | csd.v1.sector_size_low;
// error card can't erase specified area if ((firstBlock & m) != 0 || ((lastBlock + 1) & m) != 0) {
error(SD_CARD_ERROR_ERASE_SINGLE_BLOCK); // error card can't erase specified area
goto fail; error(SD_CARD_ERROR_ERASE_SINGLE_BLOCK);
} goto fail;
} }
if (type_ != SD_CARD_TYPE_SDHC) { }
firstBlock <<= 9; if (type_ != SD_CARD_TYPE_SDHC) {
lastBlock <<= 9; firstBlock <<= 9;
} lastBlock <<= 9;
if (cardCommand(CMD32, firstBlock) }
|| cardCommand(CMD33, lastBlock) if (cardCommand(CMD32, firstBlock)
|| cardCommand(CMD38, 0)) { || cardCommand(CMD33, lastBlock)
error(SD_CARD_ERROR_ERASE); || cardCommand(CMD38, 0)) {
goto fail; error(SD_CARD_ERROR_ERASE);
} goto fail;
if (!waitNotBusy(SD_ERASE_TIMEOUT)) { }
error(SD_CARD_ERROR_ERASE_TIMEOUT); if (!waitNotBusy(SD_ERASE_TIMEOUT)) {
goto fail; error(SD_CARD_ERROR_ERASE_TIMEOUT);
} goto fail;
chipSelectHigh(); }
return true; chipSelectHigh();
return true;
fail:
chipSelectHigh(); fail:
return false; chipSelectHigh();
} return false;
//------------------------------------------------------------------------------ }
/** Determine if card supports single block erase. //------------------------------------------------------------------------------
* /** Determine if card supports single block erase.
* \return The value one, true, is returned if single block erase is supported. *
* The value zero, false, is returned if single block erase is not supported. * \return The value one, true, is returned if single block erase is supported.
*/ * The value zero, false, is returned if single block erase is not supported.
bool Sd2Card::eraseSingleBlockEnable() { */
csd_t csd; bool Sd2Card::eraseSingleBlockEnable() {
return readCSD(&csd) ? csd.v1.erase_blk_en : false; csd_t csd;
} return readCSD(&csd) ? csd.v1.erase_blk_en : false;
//------------------------------------------------------------------------------ }
/** //------------------------------------------------------------------------------
* Initialize an SD flash memory card. /**
* * Initialize an SD flash memory card.
* \param[in] sckRateID SPI clock rate selector. See setSckRate(). *
* \param[in] chipSelectPin SD chip select pin number. * \param[in] sckRateID SPI clock rate selector. See setSckRate().
* * \param[in] chipSelectPin SD chip select pin number.
* \return The value one, true, is returned for success and *
* the value zero, false, is returned for failure. The reason for failure * \return The value one, true, is returned for success and
* can be determined by calling errorCode() and errorData(). * the value zero, false, is returned for failure. The reason for failure
*/ * can be determined by calling errorCode() and errorData().
bool Sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin) { */
errorCode_ = type_ = 0; bool Sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin) {
chipSelectPin_ = chipSelectPin; errorCode_ = type_ = 0;
// 16-bit init start time allows over a minute chipSelectPin_ = chipSelectPin;
uint16_t t0 = (uint16_t)millis(); // 16-bit init start time allows over a minute
uint32_t arg; uint16_t t0 = (uint16_t)millis();
uint32_t arg;
// set pin modes
pinMode(chipSelectPin_, OUTPUT); // set pin modes
chipSelectHigh(); pinMode(chipSelectPin_, OUTPUT);
pinMode(SPI_MISO_PIN, INPUT); chipSelectHigh();
pinMode(SPI_MOSI_PIN, OUTPUT); pinMode(SPI_MISO_PIN, INPUT);
pinMode(SPI_SCK_PIN, OUTPUT); pinMode(SPI_MOSI_PIN, OUTPUT);
pinMode(SPI_SCK_PIN, OUTPUT);
#ifndef SOFTWARE_SPI
// SS must be in output mode even it is not chip select #ifndef SOFTWARE_SPI
pinMode(SS_PIN, OUTPUT); // SS must be in output mode even it is not chip select
// set SS high - may be chip select for another SPI device pinMode(SS_PIN, OUTPUT);
#if SET_SPI_SS_HIGH // set SS high - may be chip select for another SPI device
digitalWrite(SS_PIN, HIGH); #if SET_SPI_SS_HIGH
#endif // SET_SPI_SS_HIGH digitalWrite(SS_PIN, HIGH);
// set SCK rate for initialization commands #endif // SET_SPI_SS_HIGH
spiRate_ = SPI_SD_INIT_RATE; // set SCK rate for initialization commands
spiInit(spiRate_); spiRate_ = SPI_SD_INIT_RATE;
#endif // SOFTWARE_SPI spiInit(spiRate_);
#endif // SOFTWARE_SPI
// must supply min of 74 clock cycles with CS high.
for (uint8_t i = 0; i < 10; i++) spiSend(0XFF); // must supply min of 74 clock cycles with CS high.
for (uint8_t i = 0; i < 10; i++) spiSend(0XFF);
// command to go idle in SPI mode
while ((status_ = cardCommand(CMD0, 0)) != R1_IDLE_STATE) { // command to go idle in SPI mode
if (((uint16_t)millis() - t0) > SD_INIT_TIMEOUT) { while ((status_ = cardCommand(CMD0, 0)) != R1_IDLE_STATE) {
error(SD_CARD_ERROR_CMD0); if (((uint16_t)millis() - t0) > SD_INIT_TIMEOUT) {
goto fail; error(SD_CARD_ERROR_CMD0);
} goto fail;
} }
// check SD version }
if ((cardCommand(CMD8, 0x1AA) & R1_ILLEGAL_COMMAND)) { // check SD version
type(SD_CARD_TYPE_SD1); if ((cardCommand(CMD8, 0x1AA) & R1_ILLEGAL_COMMAND)) {
} else { type(SD_CARD_TYPE_SD1);
// only need last byte of r7 response } else {
for (uint8_t i = 0; i < 4; i++) status_ = spiRec(); // only need last byte of r7 response
if (status_ != 0XAA) { for (uint8_t i = 0; i < 4; i++) status_ = spiRec();
error(SD_CARD_ERROR_CMD8); if (status_ != 0XAA) {
goto fail; error(SD_CARD_ERROR_CMD8);
} goto fail;
type(SD_CARD_TYPE_SD2); }
} type(SD_CARD_TYPE_SD2);
// initialize card and send host supports SDHC if SD2 }
arg = type() == SD_CARD_TYPE_SD2 ? 0X40000000 : 0; // initialize card and send host supports SDHC if SD2
arg = type() == SD_CARD_TYPE_SD2 ? 0X40000000 : 0;
while ((status_ = cardAcmd(ACMD41, arg)) != R1_READY_STATE) {
// check for timeout while ((status_ = cardAcmd(ACMD41, arg)) != R1_READY_STATE) {
if (((uint16_t)millis() - t0) > SD_INIT_TIMEOUT) { // check for timeout
error(SD_CARD_ERROR_ACMD41); if (((uint16_t)millis() - t0) > SD_INIT_TIMEOUT) {
goto fail; error(SD_CARD_ERROR_ACMD41);
} goto fail;
} }
// if SD2 read OCR register to check for SDHC card }
if (type() == SD_CARD_TYPE_SD2) { // if SD2 read OCR register to check for SDHC card
if (cardCommand(CMD58, 0)) { if (type() == SD_CARD_TYPE_SD2) {
error(SD_CARD_ERROR_CMD58); if (cardCommand(CMD58, 0)) {
goto fail; error(SD_CARD_ERROR_CMD58);
} goto fail;
if ((spiRec() & 0XC0) == 0XC0) type(SD_CARD_TYPE_SDHC); }
// discard rest of ocr - contains allowed voltage range if ((spiRec() & 0XC0) == 0XC0) type(SD_CARD_TYPE_SDHC);
for (uint8_t i = 0; i < 3; i++) spiRec(); // discard rest of ocr - contains allowed voltage range
} for (uint8_t i = 0; i < 3; i++) spiRec();
chipSelectHigh(); }
chipSelectHigh();
#ifndef SOFTWARE_SPI
return setSckRate(sckRateID); #ifndef SOFTWARE_SPI
#else // SOFTWARE_SPI return setSckRate(sckRateID);
return true; #else // SOFTWARE_SPI
#endif // SOFTWARE_SPI return true;
#endif // SOFTWARE_SPI
fail:
chipSelectHigh(); fail:
return false; chipSelectHigh();
} return false;
//------------------------------------------------------------------------------ }
/** //------------------------------------------------------------------------------
* Read a 512 byte block from an SD card. /**
* * Read a 512 byte block from an SD card.
* \param[in] blockNumber Logical block to be read. *
* \param[out] dst Pointer to the location that will receive the data. * \param[in] blockNumber Logical block to be read.
* \param[out] dst Pointer to the location that will receive the data.
* \return The value one, true, is returned for success and
* the value zero, false, is returned for failure. * \return The value one, true, is returned for success and
*/ * the value zero, false, is returned for failure.
bool Sd2Card::readBlock(uint32_t blockNumber, uint8_t* dst) { */
// use address if not SDHC card bool Sd2Card::readBlock(uint32_t blockNumber, uint8_t* dst) {
if (type()!= SD_CARD_TYPE_SDHC) blockNumber <<= 9; // use address if not SDHC card
if (cardCommand(CMD17, blockNumber)) { if (type()!= SD_CARD_TYPE_SDHC) blockNumber <<= 9;
error(SD_CARD_ERROR_CMD17); if (cardCommand(CMD17, blockNumber)) {
goto fail; error(SD_CARD_ERROR_CMD17);
} goto fail;
return readData(dst, 512); }
return readData(dst, 512);
fail:
chipSelectHigh(); fail:
return false; chipSelectHigh();
} return false;
//------------------------------------------------------------------------------ }
/** Read one data block in a multiple block read sequence //------------------------------------------------------------------------------
* /** Read one data block in a multiple block read sequence
* \param[in] dst Pointer to the location for the data to be read. *
* * \param[in] dst Pointer to the location for the data to be read.
* \return The value one, true, is returned for success and *
* the value zero, false, is returned for failure. * \return The value one, true, is returned for success and
*/ * the value zero, false, is returned for failure.
bool Sd2Card::readData(uint8_t *dst) { */
chipSelectLow(); bool Sd2Card::readData(uint8_t *dst) {
return readData(dst, 512); chipSelectLow();
} return readData(dst, 512);
//------------------------------------------------------------------------------ }
bool Sd2Card::readData(uint8_t* dst, uint16_t count) { //------------------------------------------------------------------------------
// wait for start block token bool Sd2Card::readData(uint8_t* dst, uint16_t count) {
uint16_t t0 = millis(); // wait for start block token
while ((status_ = spiRec()) == 0XFF) { uint16_t t0 = millis();
if (((uint16_t)millis() - t0) > SD_READ_TIMEOUT) { while ((status_ = spiRec()) == 0XFF) {
error(SD_CARD_ERROR_READ_TIMEOUT); if (((uint16_t)millis() - t0) > SD_READ_TIMEOUT) {
goto fail; error(SD_CARD_ERROR_READ_TIMEOUT);
} goto fail;
} }
if (status_ != DATA_START_BLOCK) { }
error(SD_CARD_ERROR_READ); if (status_ != DATA_START_BLOCK) {
goto fail; error(SD_CARD_ERROR_READ);
} goto fail;
// transfer data }
spiRead(dst, count); // transfer data
spiRead(dst, count);
// discard CRC
spiRec(); // discard CRC
spiRec(); spiRec();
chipSelectHigh(); spiRec();
return true; chipSelectHigh();
return true;
fail:
chipSelectHigh(); fail:
return false; chipSelectHigh();
} return false;
//------------------------------------------------------------------------------ }
/** read CID or CSR register */ //------------------------------------------------------------------------------
bool Sd2Card::readRegister(uint8_t cmd, void* buf) { /** read CID or CSR register */
uint8_t* dst = reinterpret_cast<uint8_t*>(buf); bool Sd2Card::readRegister(uint8_t cmd, void* buf) {
if (cardCommand(cmd, 0)) { uint8_t* dst = reinterpret_cast<uint8_t*>(buf);
error(SD_CARD_ERROR_READ_REG); if (cardCommand(cmd, 0)) {
goto fail; error(SD_CARD_ERROR_READ_REG);
} goto fail;
return readData(dst, 16); }
return readData(dst, 16);
fail:
chipSelectHigh(); fail:
return false; chipSelectHigh();
} return false;
//------------------------------------------------------------------------------ }
/** Start a read multiple blocks sequence. //------------------------------------------------------------------------------
* /** Start a read multiple blocks sequence.
* \param[in] blockNumber Address of first block in sequence. *
* * \param[in] blockNumber Address of first block in sequence.
* \note This function is used with readData() and readStop() for optimized *
* multiple block reads. SPI chipSelect must be low for the entire sequence. * \note This function is used with readData() and readStop() for optimized
* * multiple block reads. SPI chipSelect must be low for the entire sequence.
* \return The value one, true, is returned for success and *
* the value zero, false, is returned for failure. * \return The value one, true, is returned for success and
*/ * the value zero, false, is returned for failure.
bool Sd2Card::readStart(uint32_t blockNumber) { */
if (type()!= SD_CARD_TYPE_SDHC) blockNumber <<= 9; bool Sd2Card::readStart(uint32_t blockNumber) {
if (cardCommand(CMD18, blockNumber)) { if (type()!= SD_CARD_TYPE_SDHC) blockNumber <<= 9;
error(SD_CARD_ERROR_CMD18); if (cardCommand(CMD18, blockNumber)) {
goto fail; error(SD_CARD_ERROR_CMD18);
} goto fail;
chipSelectHigh(); }
return true; chipSelectHigh();
return true;
fail:
chipSelectHigh(); fail:
return false; chipSelectHigh();
} return false;
//------------------------------------------------------------------------------ }
/** End a read multiple blocks sequence. //------------------------------------------------------------------------------
* /** End a read multiple blocks sequence.
* \return The value one, true, is returned for success and *
* the value zero, false, is returned for failure. * \return The value one, true, is returned for success and
*/ * the value zero, false, is returned for failure.
bool Sd2Card::readStop() { */
chipSelectLow(); bool Sd2Card::readStop() {
if (cardCommand(CMD12, 0)) { chipSelectLow();
error(SD_CARD_ERROR_CMD12); if (cardCommand(CMD12, 0)) {
goto fail; error(SD_CARD_ERROR_CMD12);
} goto fail;
chipSelectHigh(); }
return true; chipSelectHigh();
return true;
fail:
chipSelectHigh(); fail:
return false; chipSelectHigh();
} return false;
//------------------------------------------------------------------------------ }
/** //------------------------------------------------------------------------------
* Set the SPI clock rate. /**
* * Set the SPI clock rate.
* \param[in] sckRateID A value in the range [0, 6]. *
* * \param[in] sckRateID A value in the range [0, 6].
* The SPI clock will be set to F_CPU/pow(2, 1 + sckRateID). The maximum *
* SPI rate is F_CPU/2 for \a sckRateID = 0 and the minimum rate is F_CPU/128 * The SPI clock will be set to F_CPU/pow(2, 1 + sckRateID). The maximum
* for \a scsRateID = 6. * SPI rate is F_CPU/2 for \a sckRateID = 0 and the minimum rate is F_CPU/128
* * for \a scsRateID = 6.
* \return The value one, true, is returned for success and the value zero, *
* false, is returned for an invalid value of \a sckRateID. * \return The value one, true, is returned for success and the value zero,
*/ * false, is returned for an invalid value of \a sckRateID.
bool Sd2Card::setSckRate(uint8_t sckRateID) { */
if (sckRateID > 6) { bool Sd2Card::setSckRate(uint8_t sckRateID) {
error(SD_CARD_ERROR_SCK_RATE); if (sckRateID > 6) {
return false; error(SD_CARD_ERROR_SCK_RATE);
} return false;
spiRate_ = sckRateID; }
return true; spiRate_ = sckRateID;
} return true;
//------------------------------------------------------------------------------ }
// wait for card to go not busy //------------------------------------------------------------------------------
bool Sd2Card::waitNotBusy(uint16_t timeoutMillis) { // wait for card to go not busy
uint16_t t0 = millis(); bool Sd2Card::waitNotBusy(uint16_t timeoutMillis) {
while (spiRec() != 0XFF) { uint16_t t0 = millis();
if (((uint16_t)millis() - t0) >= timeoutMillis) goto fail; while (spiRec() != 0XFF) {
} if (((uint16_t)millis() - t0) >= timeoutMillis) goto fail;
return true; }
return true;
fail:
return false; fail:
} return false;
//------------------------------------------------------------------------------ }
/** //------------------------------------------------------------------------------
* Writes a 512 byte block to an SD card. /**
* * Writes a 512 byte block to an SD card.
* \param[in] blockNumber Logical block to be written. *
* \param[in] src Pointer to the location of the data to be written. * \param[in] blockNumber Logical block to be written.
* \return The value one, true, is returned for success and * \param[in] src Pointer to the location of the data to be written.
* the value zero, false, is returned for failure. * \return The value one, true, is returned for success and
*/ * the value zero, false, is returned for failure.
bool Sd2Card::writeBlock(uint32_t blockNumber, const uint8_t* src) { */
// use address if not SDHC card bool Sd2Card::writeBlock(uint32_t blockNumber, const uint8_t* src) {
if (type() != SD_CARD_TYPE_SDHC) blockNumber <<= 9; // use address if not SDHC card
if (cardCommand(CMD24, blockNumber)) { if (type() != SD_CARD_TYPE_SDHC) blockNumber <<= 9;
error(SD_CARD_ERROR_CMD24); if (cardCommand(CMD24, blockNumber)) {
goto fail; error(SD_CARD_ERROR_CMD24);
} goto fail;
if (!writeData(DATA_START_BLOCK, src)) goto fail; }
if (!writeData(DATA_START_BLOCK, src)) goto fail;
// wait for flash programming to complete
if (!waitNotBusy(SD_WRITE_TIMEOUT)) { // wait for flash programming to complete
error(SD_CARD_ERROR_WRITE_TIMEOUT); if (!waitNotBusy(SD_WRITE_TIMEOUT)) {
goto fail; error(SD_CARD_ERROR_WRITE_TIMEOUT);
} goto fail;
// response is r2 so get and check two bytes for nonzero }
if (cardCommand(CMD13, 0) || spiRec()) { // response is r2 so get and check two bytes for nonzero
error(SD_CARD_ERROR_WRITE_PROGRAMMING); if (cardCommand(CMD13, 0) || spiRec()) {
goto fail; error(SD_CARD_ERROR_WRITE_PROGRAMMING);
} goto fail;
chipSelectHigh(); }
return true; chipSelectHigh();
return true;
fail:
chipSelectHigh(); fail:
return false; chipSelectHigh();
} return false;
//------------------------------------------------------------------------------ }
/** Write one data block in a multiple block write sequence //------------------------------------------------------------------------------
* \param[in] src Pointer to the location of the data to be written. /** Write one data block in a multiple block write sequence
* \return The value one, true, is returned for success and * \param[in] src Pointer to the location of the data to be written.
* the value zero, false, is returned for failure. * \return The value one, true, is returned for success and
*/ * the value zero, false, is returned for failure.
bool Sd2Card::writeData(const uint8_t* src) { */
chipSelectLow(); bool Sd2Card::writeData(const uint8_t* src) {
// wait for previous write to finish chipSelectLow();
if (!waitNotBusy(SD_WRITE_TIMEOUT)) goto fail; // wait for previous write to finish
if (!writeData(WRITE_MULTIPLE_TOKEN, src)) goto fail; if (!waitNotBusy(SD_WRITE_TIMEOUT)) goto fail;
chipSelectHigh(); if (!writeData(WRITE_MULTIPLE_TOKEN, src)) goto fail;
return true; chipSelectHigh();
return true;
fail:
error(SD_CARD_ERROR_WRITE_MULTIPLE); fail:
chipSelectHigh(); error(SD_CARD_ERROR_WRITE_MULTIPLE);
return false; chipSelectHigh();
} return false;
//------------------------------------------------------------------------------ }
// send one block of data for write block or write multiple blocks //------------------------------------------------------------------------------
bool Sd2Card::writeData(uint8_t token, const uint8_t* src) { // send one block of data for write block or write multiple blocks
spiSendBlock(token, src); bool Sd2Card::writeData(uint8_t token, const uint8_t* src) {
spiSendBlock(token, src);
spiSend(0xff); // dummy crc
spiSend(0xff); // dummy crc spiSend(0xff); // dummy crc
spiSend(0xff); // dummy crc
status_ = spiRec();
if ((status_ & DATA_RES_MASK) != DATA_RES_ACCEPTED) { status_ = spiRec();
error(SD_CARD_ERROR_WRITE); if ((status_ & DATA_RES_MASK) != DATA_RES_ACCEPTED) {
goto fail; error(SD_CARD_ERROR_WRITE);
} goto fail;
return true; }
return true;
fail:
chipSelectHigh(); fail:
return false; chipSelectHigh();
} return false;
//------------------------------------------------------------------------------ }
/** Start a write multiple blocks sequence. //------------------------------------------------------------------------------
* /** Start a write multiple blocks sequence.
* \param[in] blockNumber Address of first block in sequence. *
* \param[in] eraseCount The number of blocks to be pre-erased. * \param[in] blockNumber Address of first block in sequence.
* * \param[in] eraseCount The number of blocks to be pre-erased.
* \note This function is used with writeData() and writeStop() *
* for optimized multiple block writes. * \note This function is used with writeData() and writeStop()
* * for optimized multiple block writes.
* \return The value one, true, is returned for success and *
* the value zero, false, is returned for failure. * \return The value one, true, is returned for success and
*/ * the value zero, false, is returned for failure.
bool Sd2Card::writeStart(uint32_t blockNumber, uint32_t eraseCount) { */
// send pre-erase count bool Sd2Card::writeStart(uint32_t blockNumber, uint32_t eraseCount) {
if (cardAcmd(ACMD23, eraseCount)) { // send pre-erase count
error(SD_CARD_ERROR_ACMD23); if (cardAcmd(ACMD23, eraseCount)) {
goto fail; error(SD_CARD_ERROR_ACMD23);
} goto fail;
// use address if not SDHC card }
if (type() != SD_CARD_TYPE_SDHC) blockNumber <<= 9; // use address if not SDHC card
if (cardCommand(CMD25, blockNumber)) { if (type() != SD_CARD_TYPE_SDHC) blockNumber <<= 9;
error(SD_CARD_ERROR_CMD25); if (cardCommand(CMD25, blockNumber)) {
goto fail; error(SD_CARD_ERROR_CMD25);
} goto fail;
chipSelectHigh(); }
return true; chipSelectHigh();
return true;
fail:
chipSelectHigh(); fail:
return false; chipSelectHigh();
} return false;
//------------------------------------------------------------------------------ }
/** End a write multiple blocks sequence. //------------------------------------------------------------------------------
* /** End a write multiple blocks sequence.
* \return The value one, true, is returned for success and *
* the value zero, false, is returned for failure. * \return The value one, true, is returned for success and
*/ * the value zero, false, is returned for failure.
bool Sd2Card::writeStop() { */
chipSelectLow(); bool Sd2Card::writeStop() {
if (!waitNotBusy(SD_WRITE_TIMEOUT)) goto fail; chipSelectLow();
spiSend(STOP_TRAN_TOKEN); if (!waitNotBusy(SD_WRITE_TIMEOUT)) goto fail;
if (!waitNotBusy(SD_WRITE_TIMEOUT)) goto fail; spiSend(STOP_TRAN_TOKEN);
chipSelectHigh(); if (!waitNotBusy(SD_WRITE_TIMEOUT)) goto fail;
return true; chipSelectHigh();
return true;
fail:
error(SD_CARD_ERROR_STOP_TRAN); fail:
chipSelectHigh(); error(SD_CARD_ERROR_STOP_TRAN);
return false; chipSelectHigh();
return false;
} }

@ -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;
} }
//------------------------------------------------------------------------------ //------------------------------------------------------------------------------

@ -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

@ -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);
} }

@ -1,46 +1,48 @@
/* Arduino SdFat Library /* Arduino SdFat Library
* Copyright (C) 2008 by William Greiman * Copyright (C) 2008 by William Greiman
* *
* This file is part of the Arduino SdFat Library * This file is part of the Arduino SdFat Library
* *
* This Library is free software: you can redistribute it and/or modify * This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by * it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or * the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version. * (at your option) any later version.
* *
* This Library is distributed in the hope that it will be useful, * This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of * but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details. * GNU General Public License for more details.
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with the Arduino SdFat Library. If not, see * along with the Arduino SdFat Library. If not, see
* <http://www.gnu.org/licenses/>. * <http://www.gnu.org/licenses/>.
*/ */
#ifndef SdFatUtil_h #ifndef SdFatUtil_h
#define SdFatUtil_h #define SdFatUtil_h
/** /**
* \file * \file
* \brief Useful utility functions. * \brief Useful utility functions.
*/ */
#include <avr/pgmspace.h> #include <avr/pgmspace.h>
#if ARDUINO < 100 #if ARDUINO < 100
#include <WProgram.h> #define HardwareSerial_h // trick to disable the standard HWserial
#else // ARDUINO #include <WProgram.h>
#include <Arduino.h> #include "MarlinSerial.h"
#endif // ARDUINO #else // ARDUINO
/** Store and print a string in flash memory.*/ #include <Arduino.h>
#define PgmPrint(x) SerialPrint_P(PSTR(x)) #endif // ARDUINO
/** Store and print a string in flash memory followed by a CR/LF.*/ /** Store and print a string in flash memory.*/
#define PgmPrintln(x) SerialPrintln_P(PSTR(x)) #define PgmPrint(x) SerialPrint_P(PSTR(x))
/** Store and print a string in flash memory followed by a CR/LF.*/
namespace SdFatUtil { #define PgmPrintln(x) SerialPrintln_P(PSTR(x))
int FreeRam();
void print_P(Print* pr, PGM_P str); namespace SdFatUtil {
void println_P(Print* pr, PGM_P str); int FreeRam();
void SerialPrint_P(PGM_P str); void print_P(Print* pr, PGM_P str);
void SerialPrintln_P(PGM_P str); void println_P(Print* pr, PGM_P str);
} void SerialPrint_P(PGM_P str);
void SerialPrintln_P(PGM_P str);
using namespace SdFatUtil; // NOLINT }
using namespace SdFatUtil; // NOLINT
#endif // #define SdFatUtil_h #endif // #define SdFatUtil_h

@ -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);
} }

@ -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

@ -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);
@ -527,12 +527,12 @@ void plan_buffer_line(const float &x, const float &y, const float &z, const floa
else { else {
if(feed_rate<minimumfeedrate) feed_rate=minimumfeedrate; if(feed_rate<minimumfeedrate) feed_rate=minimumfeedrate;
} }
#ifdef SLOWDOWN #ifdef SLOWDOWN
// 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
/* /*

@ -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);

@ -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;
} }
@ -277,17 +265,7 @@ inline void trapezoid_generator_reset() {
// "The Stepper Driver Interrupt" - This timer interrupt is the workhorse. // "The Stepper Driver Interrupt" - This timer interrupt is the workhorse.
// 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

Loading…
Cancel
Save