parent
fb04dfcda8
commit
4b16fa3272
@ -0,0 +1,108 @@
|
||||
/***************************************************************
|
||||
*
|
||||
* External DAC for Alligator Board
|
||||
*
|
||||
****************************************************************/
|
||||
#include "Marlin.h"
|
||||
|
||||
#if MB(ALLIGATOR)
|
||||
#include "stepper.h"
|
||||
#include "dac_dac084s085.h"
|
||||
|
||||
dac084s085::dac084s085() {
|
||||
return ;
|
||||
}
|
||||
|
||||
void dac084s085::begin() {
|
||||
uint8_t externalDac_buf[2] = {0x20,0x00};//all off
|
||||
|
||||
// All SPI chip-select HIGH
|
||||
pinMode (DAC0_SYNC, OUTPUT);
|
||||
digitalWrite( DAC0_SYNC , HIGH );
|
||||
#if EXTRUDERS > 1
|
||||
pinMode (DAC1_SYNC, OUTPUT);
|
||||
digitalWrite( DAC1_SYNC , HIGH );
|
||||
#endif
|
||||
digitalWrite( SPI_EEPROM1_CS , HIGH );
|
||||
digitalWrite( SPI_EEPROM2_CS , HIGH );
|
||||
digitalWrite( SPI_FLASH_CS , HIGH );
|
||||
digitalWrite( SS_PIN , HIGH );
|
||||
spiBegin();
|
||||
|
||||
//init onboard DAC
|
||||
delayMicroseconds(2U);
|
||||
digitalWrite( DAC0_SYNC , LOW );
|
||||
delayMicroseconds(2U);
|
||||
digitalWrite( DAC0_SYNC , HIGH );
|
||||
delayMicroseconds(2U);
|
||||
digitalWrite( DAC0_SYNC , LOW );
|
||||
|
||||
spiSend(SPI_CHAN_DAC,externalDac_buf , 2);
|
||||
digitalWrite( DAC0_SYNC , HIGH );
|
||||
|
||||
#if EXTRUDERS > 1
|
||||
//init Piggy DAC
|
||||
delayMicroseconds(2U);
|
||||
digitalWrite( DAC1_SYNC , LOW );
|
||||
delayMicroseconds(2U);
|
||||
digitalWrite( DAC1_SYNC , HIGH );
|
||||
delayMicroseconds(2U);
|
||||
digitalWrite( DAC1_SYNC , LOW );
|
||||
|
||||
spiSend(SPI_CHAN_DAC,externalDac_buf , 2);
|
||||
digitalWrite( DAC1_SYNC , HIGH );
|
||||
#endif
|
||||
|
||||
return;
|
||||
}
|
||||
|
||||
void dac084s085::setValue(uint8_t channel, uint8_t value) {
|
||||
if(channel >= 7) // max channel (X,Y,Z,E0,E1,E2,E3)
|
||||
return;
|
||||
if(value > 255) value = 255;
|
||||
|
||||
uint8_t externalDac_buf[2] = {0x10,0x00};
|
||||
|
||||
if(channel > 3)
|
||||
externalDac_buf[0] |= (7 - channel << 6);
|
||||
else
|
||||
externalDac_buf[0] |= (3 - channel << 6);
|
||||
|
||||
externalDac_buf[0] |= (value>>4);
|
||||
externalDac_buf[1] |= (value<<4);
|
||||
|
||||
// All SPI chip-select HIGH
|
||||
digitalWrite( DAC0_SYNC , HIGH );
|
||||
#if EXTRUDERS > 1
|
||||
digitalWrite( DAC1_SYNC , HIGH );
|
||||
#endif
|
||||
digitalWrite( SPI_EEPROM1_CS , HIGH );
|
||||
digitalWrite( SPI_EEPROM2_CS , HIGH );
|
||||
digitalWrite( SPI_FLASH_CS , HIGH );
|
||||
digitalWrite( SS_PIN , HIGH );
|
||||
|
||||
if(channel > 3) { // DAC Piggy E1,E2,E3
|
||||
|
||||
digitalWrite(DAC1_SYNC , LOW);
|
||||
delayMicroseconds(2U);
|
||||
digitalWrite(DAC1_SYNC , HIGH);
|
||||
delayMicroseconds(2U);
|
||||
digitalWrite(DAC1_SYNC , LOW);
|
||||
}
|
||||
|
||||
else { // DAC onboard X,Y,Z,E0
|
||||
|
||||
digitalWrite(DAC0_SYNC , LOW);
|
||||
delayMicroseconds(2U);
|
||||
digitalWrite(DAC0_SYNC , HIGH);
|
||||
delayMicroseconds(2U);
|
||||
digitalWrite(DAC0_SYNC , LOW);
|
||||
}
|
||||
|
||||
delayMicroseconds(2U);
|
||||
spiSend(SPI_CHAN_DAC,externalDac_buf , 2);
|
||||
|
||||
return;
|
||||
}
|
||||
|
||||
#endif
|
@ -0,0 +1,11 @@
|
||||
#ifndef dac084s085_h
|
||||
#define dac084s085_h
|
||||
|
||||
class dac084s085 {
|
||||
public:
|
||||
dac084s085();
|
||||
static void begin(void);
|
||||
static void setValue(uint8_t channel, uint8_t value);
|
||||
};
|
||||
|
||||
#endif //dac084s085_h
|
@ -0,0 +1,94 @@
|
||||
/* **************************************************************************
|
||||
|
||||
Marlin 3D Printer Firmware
|
||||
Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
|
||||
|
||||
This program is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
This program 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 General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* Description: HAL wrapper
|
||||
*
|
||||
* Supports platforms :
|
||||
* ARDUINO_ARCH_SAM : For Arduino Due and other boards based on Atmel SAM3X8E
|
||||
* ARDUINO_ARCH_AVR : For all Atmel AVR boards
|
||||
*/
|
||||
|
||||
#ifndef _HAL_H
|
||||
#define _HAL_H
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
/**
|
||||
* SPI speed where 0 <= index <= 6
|
||||
*
|
||||
* Approximate rates :
|
||||
*
|
||||
* 0 : 8 - 10 MHz
|
||||
* 1 : 4 - 5 MHz
|
||||
* 2 : 2 - 2.5 MHz
|
||||
* 3 : 1 - 1.25 MHz
|
||||
* 4 : 500 - 625 kHz
|
||||
* 5 : 250 - 312 kHz
|
||||
* 6 : 125 - 156 kHz
|
||||
*
|
||||
* On AVR, actual speed is F_CPU/2^(1 + index).
|
||||
* On other platforms, speed should be in range given above where possible.
|
||||
*/
|
||||
|
||||
/** Set SCK to max rate */
|
||||
uint8_t const SPI_FULL_SPEED = 0;
|
||||
/** Set SCK rate to half max rate. */
|
||||
uint8_t const SPI_HALF_SPEED = 1;
|
||||
/** Set SCK rate to quarter max rate. */
|
||||
uint8_t const SPI_QUARTER_SPEED = 2;
|
||||
/** Set SCK rate to 1/8 max rate. */
|
||||
uint8_t const SPI_EIGHTH_SPEED = 3;
|
||||
/** Set SCK rate to 1/16 of max rate. */
|
||||
uint8_t const SPI_SIXTEENTH_SPEED = 4;
|
||||
/** Set SCK rate to 1/32 of max rate. */
|
||||
uint8_t const SPI_SPEED_5 = 5;
|
||||
/** Set SCK rate to 1/64 of max rate. */
|
||||
uint8_t const SPI_SPEED_6 = 6;
|
||||
|
||||
// Standard SPI functions
|
||||
/** Initialise SPI bus */
|
||||
void spiBegin(void);
|
||||
/** Configure SPI for specified SPI speed */
|
||||
void spiInit(uint8_t spiRate);
|
||||
/** Write single byte to SPI */
|
||||
void spiSend(uint8_t b);
|
||||
/** Read single byte from SPI */
|
||||
uint8_t spiRec(void);
|
||||
/** Read from SPI into buffer */
|
||||
void spiRead(uint8_t* buf, uint16_t nbyte);
|
||||
/** Write token and then write from 512 byte buffer to SPI (for SD card) */
|
||||
void spiSendBlock(uint8_t token, const uint8_t* buf);
|
||||
|
||||
#ifdef ARDUINO_ARCH_AVR
|
||||
#include "HAL_AVR/HAL_AVR.h"
|
||||
#elif defined(ARDUINO_ARCH_SAM)
|
||||
#define CPU_32_BIT
|
||||
#include "HAL_DUE/HAL_Due.h"
|
||||
#include "math_32bit.h"
|
||||
#elif defined(__MK64FX512__) || defined(__MK66FX1M0__)
|
||||
#define CPU_32_BIT
|
||||
#include "HAL_TEENSY35_36/HAL_Teensy.h"
|
||||
#include "math_32bit.h"
|
||||
#else
|
||||
#error Unsupported Platform!
|
||||
#endif
|
||||
|
||||
#endif /* HAL_H_ */
|
@ -0,0 +1,100 @@
|
||||
/* **************************************************************************
|
||||
|
||||
Marlin 3D Printer Firmware
|
||||
Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
|
||||
Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
|
||||
|
||||
This program is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
This program 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 General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* Description: HAL for AVR
|
||||
*
|
||||
* For ARDUINO_ARCH_AVR
|
||||
*/
|
||||
|
||||
|
||||
#ifdef ARDUINO_ARCH_AVR
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Includes
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
#include "../HAL.h"
|
||||
#include "../../../macros.h"
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Externals
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Local defines
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Types
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Variables
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Public Variables
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
//uint8_t MCUSR;
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Private Variables
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Function prototypes
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Private functions
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Public functions
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
#if ENABLED(SDSUPPORT)
|
||||
#include "../../../SdFatUtil.h"
|
||||
int freeMemory() { return SdFatUtil::FreeRam(); }
|
||||
#else
|
||||
|
||||
extern "C" {
|
||||
extern char __bss_end;
|
||||
extern char __heap_start;
|
||||
extern void* __brkval;
|
||||
|
||||
int freeMemory() {
|
||||
int free_memory;
|
||||
if ((int)__brkval == 0)
|
||||
free_memory = ((int)&free_memory) - ((int)&__bss_end);
|
||||
else
|
||||
free_memory = ((int)&free_memory) - ((int)__brkval);
|
||||
return free_memory;
|
||||
}
|
||||
}
|
||||
|
||||
#endif //!SDSUPPORT
|
||||
|
||||
#endif
|
||||
|
@ -0,0 +1,160 @@
|
||||
/* **************************************************************************
|
||||
|
||||
Marlin 3D Printer Firmware
|
||||
Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
|
||||
Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
|
||||
|
||||
This program is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
This program 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 General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* Description: HAL for AVR
|
||||
*
|
||||
* For ARDUINO_ARCH_AVR
|
||||
*/
|
||||
|
||||
|
||||
#ifndef _HAL_AVR_H
|
||||
#define _HAL_AVR_H
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Includes
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include "Arduino.h"
|
||||
|
||||
#include <util/delay.h>
|
||||
#include <avr/eeprom.h>
|
||||
#include <avr/pgmspace.h>
|
||||
#include <avr/interrupt.h>
|
||||
#include <avr/io.h>
|
||||
|
||||
#include "fastio_AVR.h"
|
||||
#include "watchdog_AVR.h"
|
||||
#include "math_AVR.h"
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Defines
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
//#define analogInputToDigitalPin(IO) IO
|
||||
|
||||
#ifndef CRITICAL_SECTION_START
|
||||
#define CRITICAL_SECTION_START unsigned char _sreg = SREG; cli();
|
||||
#define CRITICAL_SECTION_END SREG = _sreg;
|
||||
#endif
|
||||
|
||||
|
||||
// On AVR this is in math.h?
|
||||
//#define square(x) ((x)*(x))
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Types
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
#define HAL_TIMER_TYPE uint16_t
|
||||
#define HAL_TIMER_TYPE_MAX 0xFFFF
|
||||
|
||||
#define HAL_SERVO_LIB Servo
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Public Variables
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
//extern uint8_t MCUSR;
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Public functions
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
//void cli(void);
|
||||
|
||||
//void _delay_ms(int delay);
|
||||
|
||||
inline void HAL_clear_reset_source(void) { MCUSR = 0; }
|
||||
inline uint8_t HAL_get_reset_source(void) { return MCUSR; }
|
||||
|
||||
extern "C" {
|
||||
int freeMemory(void);
|
||||
}
|
||||
|
||||
// eeprom
|
||||
//void eeprom_write_byte(unsigned char *pos, unsigned char value);
|
||||
//unsigned char eeprom_read_byte(unsigned char *pos);
|
||||
|
||||
|
||||
// timers
|
||||
#define STEP_TIMER_NUM OCR1A
|
||||
#define TEMP_TIMER_NUM 0
|
||||
#define TEMP_TIMER_FREQUENCY (F_CPU / 64.0 / 256.0)
|
||||
|
||||
#define HAL_TIMER_RATE ((F_CPU) / 8.0)
|
||||
#define HAL_STEPPER_TIMER_RATE HAL_TIMER_RATE
|
||||
#define STEPPER_TIMER_PRESCALE INT0_PRESCALER
|
||||
|
||||
#define ENABLE_STEPPER_DRIVER_INTERRUPT() SBI(TIMSK1, OCIE1A)
|
||||
#define DISABLE_STEPPER_DRIVER_INTERRUPT() CBI(TIMSK1, OCIE1A)
|
||||
|
||||
#define ENABLE_TEMPERATURE_INTERRUPT() SBI(TIMSK0, OCIE0B)
|
||||
#define DISABLE_TEMPERATURE_INTERRUPT() CBI(TIMSK0, OCIE0B)
|
||||
|
||||
//void HAL_timer_start (uint8_t timer_num, uint32_t frequency);
|
||||
#define HAL_timer_start (timer_num,frequency)
|
||||
|
||||
//void HAL_timer_set_count (uint8_t timer_num, uint16_t count);
|
||||
#define HAL_timer_set_count(timer,count) timer = (count)
|
||||
|
||||
#define HAL_timer_get_current_count(timer) timer
|
||||
|
||||
//void HAL_timer_isr_prologue (uint8_t timer_num);
|
||||
#define HAL_timer_isr_prologue(timer_num)
|
||||
|
||||
#define HAL_STEP_TIMER_ISR ISR(TIMER1_COMPA_vect)
|
||||
#define HAL_TEMP_TIMER_ISR ISR(TIMER0_COMPB_vect)
|
||||
|
||||
#define HAL_ENABLE_ISRs() do { cli(); if (thermalManager.in_temp_isr)DISABLE_TEMPERATURE_INTERRUPT(); else ENABLE_TEMPERATURE_INTERRUPT(); ENABLE_STEPPER_DRIVER_INTERRUPT(); } while(0)
|
||||
|
||||
// ADC
|
||||
#ifdef DIDR2
|
||||
#define HAL_ANALOG_SELECT(pin) do{ if (pin < 8) SBI(DIDR0, pin); else SBI(DIDR2, pin - 8); }while(0)
|
||||
#else
|
||||
#define HAL_ANALOG_SELECT(pin) do{ SBI(DIDR0, pin); }while(0)
|
||||
#endif
|
||||
|
||||
inline void HAL_adc_init(void) {
|
||||
ADCSRA = _BV(ADEN) | _BV(ADSC) | _BV(ADIF) | 0x07;
|
||||
DIDR0 = 0;
|
||||
#ifdef DIDR2
|
||||
DIDR2 = 0;
|
||||
#endif
|
||||
}
|
||||
|
||||
#define SET_ADMUX_ADCSRA(pin) ADMUX = _BV(REFS0) | (pin & 0x07); SBI(ADCSRA, ADSC)
|
||||
#ifdef MUX5
|
||||
#define HAL_START_ADC(pin) if (pin > 7) ADCSRB = _BV(MUX5); else ADCSRB = 0; SET_ADMUX_ADCSRA(pin)
|
||||
#else
|
||||
#define HAL_START_ADC(pin) ADCSRB = 0; SET_ADMUX_ADCSRA(pin)
|
||||
#endif
|
||||
|
||||
#define HAL_READ_ADC ADC
|
||||
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
//
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
#endif // _HAL_AVR_H
|
@ -0,0 +1,213 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program 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 General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* Originally from Arduino Sd2Card Library
|
||||
* Copyright (C) 2009 by William Greiman
|
||||
*/
|
||||
|
||||
/**
|
||||
* Description: HAL for AVR - SPI functions
|
||||
*
|
||||
* For ARDUINO_ARCH_AVR
|
||||
*/
|
||||
|
||||
#ifdef ARDUINO_ARCH_AVR
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Includes
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
#include "../../../MarlinConfig.h"
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Public Variables
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Public functions
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
void spiBegin (void) {
|
||||
SET_OUTPUT(SS_PIN);
|
||||
WRITE(SS_PIN, HIGH);
|
||||
SET_OUTPUT(SCK_PIN);
|
||||
SET_INPUT(MISO_PIN);
|
||||
SET_OUTPUT(MOSI_PIN);
|
||||
|
||||
#if DISABLED(SOFTWARE_SPI)
|
||||
// SS must be in output mode even it is not chip select
|
||||
SET_OUTPUT(SS_PIN);
|
||||
// set SS high - may be chip select for another SPI device
|
||||
#if SET_SPI_SS_HIGH
|
||||
WRITE(SS_PIN, HIGH);
|
||||
#endif // SET_SPI_SS_HIGH
|
||||
// set a default rate
|
||||
spiInit(1);
|
||||
#endif // SOFTWARE_SPI
|
||||
}
|
||||
|
||||
|
||||
//------------------------------------------------------------------------------
|
||||
#if DISABLED(SOFTWARE_SPI)
|
||||
// functions for hardware SPI
|
||||
//------------------------------------------------------------------------------
|
||||
// make sure SPCR rate is in expected bits
|
||||
#if (SPR0 != 0 || SPR1 != 1)
|
||||
#error "unexpected SPCR bits"
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Initialize hardware SPI
|
||||
* Set SCK rate to F_CPU/pow(2, 1 + spiRate) for spiRate [0,6]
|
||||
*/
|
||||
void spiInit(uint8_t spiRate) {
|
||||
// See avr processor documentation
|
||||
CBI(
|
||||
#ifdef PRR
|
||||
PRR
|
||||
#elif defined(PRR0)
|
||||
PRR0
|
||||
#endif
|
||||
, PRSPI);
|
||||
|
||||
SPCR = _BV(SPE) | _BV(MSTR) | (spiRate >> 1);
|
||||
SPSR = spiRate & 1 || spiRate == 6 ? 0 : _BV(SPI2X);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** SPI receive a byte */
|
||||
uint8_t spiRec(void) {
|
||||
SPDR = 0XFF;
|
||||
while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
|
||||
return SPDR;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** SPI read data */
|
||||
void spiRead(uint8_t* buf, uint16_t nbyte) {
|
||||
if (nbyte-- == 0) return;
|
||||
SPDR = 0XFF;
|
||||
for (uint16_t i = 0; i < nbyte; i++) {
|
||||
while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
|
||||
buf[i] = SPDR;
|
||||
SPDR = 0XFF;
|
||||
}
|
||||
while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
|
||||
buf[nbyte] = SPDR;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** SPI send a byte */
|
||||
void spiSend(uint8_t b) {
|
||||
SPDR = b;
|
||||
while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** SPI send block */
|
||||
void spiSendBlock(uint8_t token, const uint8_t* buf) {
|
||||
SPDR = token;
|
||||
for (uint16_t i = 0; i < 512; i += 2) {
|
||||
while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
|
||||
SPDR = buf[i];
|
||||
while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
|
||||
SPDR = buf[i + 1];
|
||||
}
|
||||
while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
#else // SOFTWARE_SPI
|
||||
//------------------------------------------------------------------------------
|
||||
/** nop to tune soft SPI timing */
|
||||
#define nop asm volatile ("\tnop\n")
|
||||
|
||||
/** Set SPI rate */
|
||||
void spiInit(uint8_t spiRate) {
|
||||
// nothing to do
|
||||
UNUSED(spiRate);
|
||||
}
|
||||
|
||||
//------------------------------------------------------------------------------
|
||||
/** Soft SPI receive byte */
|
||||
uint8_t spiRec() {
|
||||
uint8_t data = 0;
|
||||
// no interrupts during byte receive - about 8 us
|
||||
cli();
|
||||
// output pin high - like sending 0XFF
|
||||
WRITE(MOSI_PIN, HIGH);
|
||||
|
||||
for (uint8_t i = 0; i < 8; i++) {
|
||||
WRITE(SCK_PIN, HIGH);
|
||||
|
||||
// adjust so SCK is nice
|
||||
nop;
|
||||
nop;
|
||||
|
||||
data <<= 1;
|
||||
|
||||
if (READ(MISO_PIN)) data |= 1;
|
||||
|
||||
WRITE(SCK_PIN, LOW);
|
||||
}
|
||||
// enable interrupts
|
||||
sei();
|
||||
return data;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** Soft SPI read data */
|
||||
void spiRead(uint8_t* buf, uint16_t nbyte) {
|
||||
for (uint16_t i = 0; i < nbyte; i++)
|
||||
buf[i] = spiRec();
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** Soft SPI send byte */
|
||||
void spiSend(uint8_t data) {
|
||||
// no interrupts during byte send - about 8 us
|
||||
cli();
|
||||
for (uint8_t i = 0; i < 8; i++) {
|
||||
WRITE(SCK_PIN, LOW);
|
||||
|
||||
WRITE(MOSI_PIN, data & 0X80);
|
||||
|
||||
data <<= 1;
|
||||
|
||||
WRITE(SCK_PIN, HIGH);
|
||||
}
|
||||
// hold SCK high for a few ns
|
||||
nop;
|
||||
nop;
|
||||
nop;
|
||||
nop;
|
||||
|
||||
WRITE(SCK_PIN, LOW);
|
||||
// enable interrupts
|
||||
sei();
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** Soft SPI send block */
|
||||
void spiSendBlock(uint8_t token, const uint8_t* buf) {
|
||||
spiSend(token);
|
||||
for (uint16_t i = 0; i < 512; i++)
|
||||
spiSend(buf[i]);
|
||||
}
|
||||
#endif // SOFTWARE_SPI
|
||||
|
||||
|
||||
#endif // ARDUINO_ARCH_AVR
|
@ -0,0 +1,90 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program 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 General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/*
|
||||
Servo.h - Interrupt driven Servo library for Arduino using 16 bit timers- Version 2
|
||||
Copyright (c) 2009 Michael Margolis. 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
|
||||
*/
|
||||
|
||||
/*
|
||||
* Defines for 16 bit timers used with Servo library
|
||||
*
|
||||
* If _useTimerX is defined then TimerX is a 16 bit timer on the current board
|
||||
* timer16_Sequence_t enumerates the sequence that the timers should be allocated
|
||||
* _Nbr_16timers indicates how many 16 bit timers are available.
|
||||
*/
|
||||
|
||||
/**
|
||||
* AVR Only definitions
|
||||
* --------------------
|
||||
*/
|
||||
|
||||
#define TRIM_DURATION 2 // compensation ticks to trim adjust for digitalWrite delays
|
||||
#define PRESCALER 8 // timer prescaler
|
||||
|
||||
// Say which 16 bit timers can be used and in what order
|
||||
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
|
||||
//#define _useTimer1
|
||||
#define _useTimer3
|
||||
#define _useTimer4
|
||||
#if !HAS_MOTOR_CURRENT_PWM
|
||||
#define _useTimer5 // Timer 5 is used for motor current PWM and can't be used for servos.
|
||||
#endif
|
||||
#elif defined(__AVR_ATmega32U4__)
|
||||
#define _useTimer3
|
||||
#elif defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB1286__)
|
||||
#define _useTimer3
|
||||
#elif defined(__AVR_ATmega128__) || defined(__AVR_ATmega1281__) || defined(__AVR_ATmega1284P__) || defined(__AVR_ATmega2561__)
|
||||
#define _useTimer3
|
||||
#else
|
||||
// everything else
|
||||
#endif
|
||||
|
||||
typedef enum {
|
||||
#if ENABLED(_useTimer1)
|
||||
_timer1,
|
||||
#endif
|
||||
#if ENABLED(_useTimer3)
|
||||
_timer3,
|
||||
#endif
|
||||
#if ENABLED(_useTimer4)
|
||||
_timer4,
|
||||
#endif
|
||||
#if ENABLED(_useTimer5)
|
||||
_timer5,
|
||||
#endif
|
||||
_Nbr_16timers
|
||||
} timer16_Sequence_t;
|
@ -0,0 +1,112 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program 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 General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef MATH_AVR_H
|
||||
#define MATH_AVR_H
|
||||
|
||||
/**
|
||||
* Optimized math functions for AVR
|
||||
*/
|
||||
|
||||
// intRes = longIn1 * longIn2 >> 24
|
||||
// uses:
|
||||
// r26 to store 0
|
||||
// r27 to store bits 16-23 of the 48bit result. The top bit is used to round the two byte result.
|
||||
// note that the lower two bytes and the upper byte of the 48bit result are not calculated.
|
||||
// this can cause the result to be out by one as the lower bytes may cause carries into the upper ones.
|
||||
// B0 A0 are bits 24-39 and are the returned value
|
||||
// C1 B1 A1 is longIn1
|
||||
// D2 C2 B2 A2 is longIn2
|
||||
//
|
||||
#define MultiU24X32toH16(intRes, longIn1, longIn2) \
|
||||
asm volatile ( \
|
||||
"clr r26 \n\t" \
|
||||
"mul %A1, %B2 \n\t" \
|
||||
"mov r27, r1 \n\t" \
|
||||
"mul %B1, %C2 \n\t" \
|
||||
"movw %A0, r0 \n\t" \
|
||||
"mul %C1, %C2 \n\t" \
|
||||
"add %B0, r0 \n\t" \
|
||||
"mul %C1, %B2 \n\t" \
|
||||
"add %A0, r0 \n\t" \
|
||||
"adc %B0, r1 \n\t" \
|
||||
"mul %A1, %C2 \n\t" \
|
||||
"add r27, r0 \n\t" \
|
||||
"adc %A0, r1 \n\t" \
|
||||
"adc %B0, r26 \n\t" \
|
||||
"mul %B1, %B2 \n\t" \
|
||||
"add r27, r0 \n\t" \
|
||||
"adc %A0, r1 \n\t" \
|
||||
"adc %B0, r26 \n\t" \
|
||||
"mul %C1, %A2 \n\t" \
|
||||
"add r27, r0 \n\t" \
|
||||
"adc %A0, r1 \n\t" \
|
||||
"adc %B0, r26 \n\t" \
|
||||
"mul %B1, %A2 \n\t" \
|
||||
"add r27, r1 \n\t" \
|
||||
"adc %A0, r26 \n\t" \
|
||||
"adc %B0, r26 \n\t" \
|
||||
"lsr r27 \n\t" \
|
||||
"adc %A0, r26 \n\t" \
|
||||
"adc %B0, r26 \n\t" \
|
||||
"mul %D2, %A1 \n\t" \
|
||||
"add %A0, r0 \n\t" \
|
||||
"adc %B0, r1 \n\t" \
|
||||
"mul %D2, %B1 \n\t" \
|
||||
"add %B0, r0 \n\t" \
|
||||
"clr r1 \n\t" \
|
||||
: \
|
||||
"=&r" (intRes) \
|
||||
: \
|
||||
"d" (longIn1), \
|
||||
"d" (longIn2) \
|
||||
: \
|
||||
"r26" , "r27" \
|
||||
)
|
||||
|
||||
// intRes = intIn1 * intIn2 >> 16
|
||||
// uses:
|
||||
// r26 to store 0
|
||||
// r27 to store the byte 1 of the 24 bit result
|
||||
#define MultiU16X8toH16(intRes, charIn1, intIn2) \
|
||||
asm volatile ( \
|
||||
"clr r26 \n\t" \
|
||||
"mul %A1, %B2 \n\t" \
|
||||
"movw %A0, r0 \n\t" \
|
||||
"mul %A1, %A2 \n\t" \
|
||||
"add %A0, r1 \n\t" \
|
||||
"adc %B0, r26 \n\t" \
|
||||
"lsr r0 \n\t" \
|
||||
"adc %A0, r26 \n\t" \
|
||||
"adc %B0, r26 \n\t" \
|
||||
"clr r1 \n\t" \
|
||||
: \
|
||||
"=&r" (intRes) \
|
||||
: \
|
||||
"d" (charIn1), \
|
||||
"d" (intIn2) \
|
||||
: \
|
||||
"r26" \
|
||||
)
|
||||
|
||||
|
||||
#endif
|
@ -0,0 +1,57 @@
|
||||
#include "../persistent_store_api.h"
|
||||
|
||||
#include "../../../types.h"
|
||||
#include "../../../language.h"
|
||||
#include "../../../serial.h"
|
||||
#include "../../../utility.h"
|
||||
|
||||
#ifdef ARDUINO_ARCH_AVR
|
||||
#if ENABLED(EEPROM_SETTINGS)
|
||||
|
||||
namespace HAL {
|
||||
namespace PersistentStore {
|
||||
|
||||
bool access_start() {
|
||||
return true;
|
||||
}
|
||||
|
||||
bool access_finish(){
|
||||
return true;
|
||||
}
|
||||
|
||||
bool write_data(int &pos, const uint8_t *value, uint16_t size, uint16_t *crc) {
|
||||
while (size--) {
|
||||
uint8_t * const p = (uint8_t * const)pos;
|
||||
uint8_t v = *value;
|
||||
// EEPROM has only ~100,000 write cycles,
|
||||
// so only write bytes that have changed!
|
||||
if (v != eeprom_read_byte(p)) {
|
||||
eeprom_write_byte(p, v);
|
||||
if (eeprom_read_byte(p) != v) {
|
||||
SERIAL_ECHO_START();
|
||||
SERIAL_ECHOLNPGM(MSG_ERR_EEPROM_WRITE);
|
||||
return false;
|
||||
}
|
||||
}
|
||||
crc16(crc, &v, 1);
|
||||
pos++;
|
||||
value++;
|
||||
};
|
||||
return true;
|
||||
}
|
||||
|
||||
void read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc) {
|
||||
do {
|
||||
uint8_t c = eeprom_read_byte((unsigned char*)pos);
|
||||
*value = c;
|
||||
crc16(crc, &c, 1);
|
||||
pos++;
|
||||
value++;
|
||||
} while (--size);
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
#endif // EEPROM_SETTINGS
|
||||
#endif // ARDUINO_ARCH_AVR
|
@ -0,0 +1,67 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program 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 General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef SPI_PINS_H_
|
||||
#define SPI_PINS_H_
|
||||
|
||||
/**
|
||||
* Define SPI Pins: SCK, MISO, MOSI, SS
|
||||
*/
|
||||
#if defined(__AVR_ATmega168__) || defined(__AVR_ATmega328__) || defined(__AVR_ATmega328P__)
|
||||
#define AVR_SCK_PIN 13
|
||||
#define AVR_MISO_PIN 12
|
||||
#define AVR_MOSI_PIN 11
|
||||
#define AVR_SS_PIN 10
|
||||
#elif defined(__AVR_ATmega644__) || defined(__AVR_ATmega644P__) || defined(__AVR_ATmega644PA__) || defined(__AVR_ATmega1284P__)
|
||||
#define AVR_SCK_PIN 7
|
||||
#define AVR_MISO_PIN 6
|
||||
#define AVR_MOSI_PIN 5
|
||||
#define AVR_SS_PIN 4
|
||||
#elif defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
|
||||
#define AVR_SCK_PIN 52
|
||||
#define AVR_MISO_PIN 50
|
||||
#define AVR_MOSI_PIN 51
|
||||
#define AVR_SS_PIN 53
|
||||
#elif defined(__AVR_AT90USB1287__) || defined(__AVR_AT90USB1286__) || defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB647__)
|
||||
#define AVR_SCK_PIN 21
|
||||
#define AVR_MISO_PIN 23
|
||||
#define AVR_MOSI_PIN 22
|
||||
#define AVR_SS_PIN 20
|
||||
#elif defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2561__)
|
||||
#define AVR_SCK_PIN 10
|
||||
#define AVR_MISO_PIN 12
|
||||
#define AVR_MOSI_PIN 11
|
||||
#define AVR_SS_PIN 16
|
||||
#endif
|
||||
|
||||
#ifndef SCK_PIN
|
||||
#define SCK_PIN AVR_SCK_PIN
|
||||
#endif
|
||||
#ifndef MISO_PIN
|
||||
#define MISO_PIN AVR_MISO_PIN
|
||||
#endif
|
||||
#ifndef MOSI_PIN
|
||||
#define MOSI_PIN AVR_MOSI_PIN
|
||||
#endif
|
||||
#ifndef SS_PIN
|
||||
#define SS_PIN AVR_SS_PIN
|
||||
#endif
|
||||
|
||||
|
||||
#endif /* SPI_PINS_H_ */
|
@ -0,0 +1,53 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program 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 General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
|
||||
#ifndef HAL_ENDSTOP_INTERRUPTS_H_
|
||||
#define HAL_ENDSTOP_INTERRUPTS_H_
|
||||
|
||||
volatile uint8_t e_hit = 0; // Different from 0 when the endstops should be tested in detail.
|
||||
// Must be reset to 0 by the test function when finished.
|
||||
|
||||
// This is what is really done inside the interrupts.
|
||||
FORCE_INLINE void endstop_ISR_worker( void ) {
|
||||
e_hit = 2; // Because the detection of a e-stop hit has a 1 step debouncer it has to be called at least twice.
|
||||
}
|
||||
|
||||
// One ISR for all EXT-Interrupts
|
||||
void endstop_ISR(void) { endstop_ISR_worker(); }
|
||||
|
||||
#ifdef ARDUINO_ARCH_AVR
|
||||
|
||||
#include "HAL_AVR/endstop_interrupts.h"
|
||||
|
||||
#elif defined(ARDUINO_ARCH_SAM)
|
||||
|
||||
#include "HAL_DUE/endstop_interrupts.h"
|
||||
|
||||
#elif IS_32BIT_TEENSY
|
||||
|
||||
#include "HAL_TEENSY35_36/endstop_interrupts.h"
|
||||
|
||||
#else
|
||||
|
||||
#error Unsupported Platform!
|
||||
|
||||
#endif
|
||||
|
||||
#endif /* HAL_ENDSTOP_INTERRUPTS_H_ */
|
@ -0,0 +1,35 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program 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 General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef HAL_PINSDEBUG_H
|
||||
|
||||
#ifdef ARDUINO_ARCH_AVR
|
||||
#include "HAL_AVR/HAL_pinsDebug_AVR.h"
|
||||
#elif defined(ARDUINO_ARCH_SAM)
|
||||
#include "HAL_DUE/HAL_pinsDebug_Due.h"
|
||||
#elif IS_32BIT_TEENSY
|
||||
#include "HAL_TEENSY35_36/HAL_pinsDebug_Teensy.h"
|
||||
#else
|
||||
#error Unsupported Platform!
|
||||
#endif
|
||||
|
||||
#endif
|
@ -0,0 +1,39 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program 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 General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
|
||||
#ifndef HAL_SPI_PINS_H_
|
||||
#define HAL_SPI_PINS_H_
|
||||
|
||||
#include "MarlinConfig.h"
|
||||
|
||||
#ifdef ARDUINO_ARCH_SAM
|
||||
#include "HAL_DUE/spi_pins.h"
|
||||
|
||||
#elif defined(IS_32BIT_TEENSY)
|
||||
#include "HAL_TEENSY35_36/spi_pins.h"
|
||||
|
||||
#elif defined(ARDUINO_ARCH_AVR)
|
||||
#include "HAL_AVR/spi_pins.h"
|
||||
|
||||
#else
|
||||
#error "Unsupported Platform!"
|
||||
#endif
|
||||
|
||||
#endif /* HAL_SPI_PINS_H_ */
|
@ -0,0 +1,162 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program 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 General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
|
||||
/**
|
||||
* Description: functions for I2C connected external EEPROM.
|
||||
* Not platform dependent.
|
||||
*/
|
||||
|
||||
#include "../../MarlinConfig.h"
|
||||
|
||||
#if ENABLED(I2C_EEPROM)
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Includes
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
#include "HAL.h"
|
||||
#include <Wire.h>
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Externals
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Local defines
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Types
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Variables
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Public Variables
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Private Variables
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Function prototypes
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Private functions
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Public functions
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
static bool eeprom_initialised = false;
|
||||
static uint8_t eeprom_device_address = 0x50;
|
||||
|
||||
static void eeprom_init(void) {
|
||||
if (!eeprom_initialised) {
|
||||
Wire.begin();
|
||||
eeprom_initialised = true;
|
||||
}
|
||||
}
|
||||
|
||||
void eeprom_write_byte(unsigned char *pos, unsigned char value) {
|
||||
unsigned eeprom_address = (unsigned) pos;
|
||||
|
||||
eeprom_init();
|
||||
|
||||
Wire.beginTransmission(eeprom_device_address);
|
||||
Wire.write((int)(eeprom_address >> 8)); // MSB
|
||||
Wire.write((int)(eeprom_address & 0xFF)); // LSB
|
||||
Wire.write(value);
|
||||
Wire.endTransmission();
|
||||
|
||||
// wait for write cycle to complete
|
||||
// this could be done more efficiently with "acknowledge polling"
|
||||
delay(5);
|
||||
}
|
||||
|
||||
// WARNING: address is a page address, 6-bit end will wrap around
|
||||
// also, data can be maximum of about 30 bytes, because the Wire library has a buffer of 32 bytes
|
||||
void eeprom_update_block(const void* pos, void* eeprom_address, size_t n) {
|
||||
uint8_t eeprom_temp[32] = {0};
|
||||
uint8_t flag = 0;
|
||||
|
||||
eeprom_init();
|
||||
|
||||
Wire.beginTransmission(eeprom_device_address);
|
||||
Wire.write((int)((unsigned)eeprom_address >> 8)); // MSB
|
||||
Wire.write((int)((unsigned)eeprom_address & 0xFF)); // LSB
|
||||
Wire.endTransmission();
|
||||
Wire.requestFrom(eeprom_device_address, (byte)n);
|
||||
for (byte c = 0; c < n; c++) {
|
||||
if (Wire.available()) eeprom_temp[c] = Wire.read();
|
||||
flag |= (eeprom_temp[c] ^ *((uint8_t*)pos + c));
|
||||
}
|
||||
|
||||
if (flag) {
|
||||
Wire.beginTransmission(eeprom_device_address);
|
||||
Wire.write((int)((unsigned)eeprom_address >> 8)); // MSB
|
||||
Wire.write((int)((unsigned)eeprom_address & 0xFF)); // LSB
|
||||
Wire.write((uint8_t*)(pos), n);
|
||||
Wire.endTransmission();
|
||||
|
||||
// wait for write cycle to complete
|
||||
// this could be done more efficiently with "acknowledge polling"
|
||||
delay(5);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
unsigned char eeprom_read_byte(unsigned char *pos) {
|
||||
byte data = 0xFF;
|
||||
unsigned eeprom_address = (unsigned) pos;
|
||||
|
||||
eeprom_init ();
|
||||
|
||||
Wire.beginTransmission(eeprom_device_address);
|
||||
Wire.write((int)(eeprom_address >> 8)); // MSB
|
||||
Wire.write((int)(eeprom_address & 0xFF)); // LSB
|
||||
Wire.endTransmission();
|
||||
Wire.requestFrom(eeprom_device_address, (byte)1);
|
||||
if (Wire.available())
|
||||
data = Wire.read();
|
||||
return data;
|
||||
}
|
||||
|
||||
// maybe let's not read more than 30 or 32 bytes at a time!
|
||||
void eeprom_read_block(void* pos, const void* eeprom_address, size_t n) {
|
||||
eeprom_init();
|
||||
|
||||
Wire.beginTransmission(eeprom_device_address);
|
||||
Wire.write((int)((unsigned)eeprom_address >> 8)); // MSB
|
||||
Wire.write((int)((unsigned)eeprom_address & 0xFF)); // LSB
|
||||
Wire.endTransmission();
|
||||
Wire.requestFrom(eeprom_device_address, (byte)n);
|
||||
for (byte c = 0; c < n; c++ )
|
||||
if (Wire.available()) *((uint8_t*)pos + c) = Wire.read();
|
||||
}
|
||||
|
||||
|
||||
#endif // ENABLED(I2C_EEPROM)
|
||||
|
@ -0,0 +1,117 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program 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 General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* Description: functions for SPI connected external EEPROM.
|
||||
* Not platform dependent.
|
||||
*/
|
||||
|
||||
#include "../../MarlinConfig.h"
|
||||
|
||||
#if ENABLED(SPI_EEPROM)
|
||||
|
||||
#include "HAL.h"
|
||||
|
||||
#define CMD_WREN 6 // WREN
|
||||
#define CMD_READ 2 // WRITE
|
||||
#define CMD_WRITE 2 // WRITE
|
||||
|
||||
uint8_t eeprom_read_byte(uint8_t* pos) {
|
||||
uint8_t v;
|
||||
uint8_t eeprom_temp[3];
|
||||
|
||||
// set read location
|
||||
// begin transmission from device
|
||||
eeprom_temp[0] = CMD_READ;
|
||||
eeprom_temp[1] = ((unsigned)pos>>8) & 0xFF; // addr High
|
||||
eeprom_temp[2] = (unsigned)pos& 0xFF; // addr Low
|
||||
digitalWrite(SPI_EEPROM1_CS, HIGH);
|
||||
digitalWrite(SPI_EEPROM1_CS, LOW);
|
||||
spiSend(SPI_CHAN_EEPROM1, eeprom_temp, 3);
|
||||
|
||||
v = spiRec(SPI_CHAN_EEPROM1);
|
||||
digitalWrite(SPI_EEPROM1_CS, HIGH);
|
||||
return v;
|
||||
}
|
||||
|
||||
|
||||
void eeprom_read_block(void* dest, const void* eeprom_address, size_t n) {
|
||||
uint8_t eeprom_temp[3];
|
||||
|
||||
// set read location
|
||||
// begin transmission from device
|
||||
eeprom_temp[0] = CMD_READ;
|
||||
eeprom_temp[1] = ((unsigned)eeprom_address>>8) & 0xFF; // addr High
|
||||
eeprom_temp[2] = (unsigned)eeprom_address& 0xFF; // addr Low
|
||||
digitalWrite(SPI_EEPROM1_CS, HIGH);
|
||||
digitalWrite(SPI_EEPROM1_CS, LOW);
|
||||
spiSend(SPI_CHAN_EEPROM1, eeprom_temp, 3);
|
||||
|
||||
uint8_t *p_dest = (uint8_t *)dest;
|
||||
while (n--)
|
||||
*p_dest++ = spiRec(SPI_CHAN_EEPROM1);
|
||||
digitalWrite(SPI_EEPROM1_CS, HIGH);
|
||||
}
|
||||
|
||||
void eeprom_write_byte(uint8_t* pos, uint8_t value) {
|
||||
uint8_t eeprom_temp[3];
|
||||
|
||||
/*write enable*/
|
||||
eeprom_temp[0] = CMD_WREN;
|
||||
digitalWrite(SPI_EEPROM1_CS, LOW);
|
||||
spiSend(SPI_CHAN_EEPROM1, eeprom_temp, 1);
|
||||
digitalWrite(SPI_EEPROM1_CS, HIGH);
|
||||
delay(1);
|
||||
|
||||
/*write addr*/
|
||||
eeprom_temp[0] = CMD_WRITE;
|
||||
eeprom_temp[1] = ((unsigned)pos>>8) & 0xFF; //addr High
|
||||
eeprom_temp[2] = (unsigned)pos & 0xFF; //addr Low
|
||||
digitalWrite(SPI_EEPROM1_CS, LOW);
|
||||
spiSend(SPI_CHAN_EEPROM1, eeprom_temp, 3);
|
||||
|
||||
spiSend(SPI_CHAN_EEPROM1, value);
|
||||
digitalWrite(SPI_EEPROM1_CS, HIGH);
|
||||
delay(7); // wait for page write to complete
|
||||
}
|
||||
|
||||
void eeprom_update_block(const void* src, void* eeprom_address, size_t n) {
|
||||
uint8_t eeprom_temp[3];
|
||||
|
||||
/*write enable*/
|
||||
eeprom_temp[0] = CMD_WREN;
|
||||
digitalWrite(SPI_EEPROM1_CS, LOW);
|
||||
spiSend(SPI_CHAN_EEPROM1, eeprom_temp, 1);
|
||||
digitalWrite(SPI_EEPROM1_CS, HIGH);
|
||||
delay(1);
|
||||
|
||||
/*write addr*/
|
||||
eeprom_temp[0] = CMD_WRITE;
|
||||
eeprom_temp[1] = ((unsigned)eeprom_address>>8) & 0xFF; //addr High
|
||||
eeprom_temp[2] = (unsigned)eeprom_address & 0xFF; //addr Low
|
||||
digitalWrite(SPI_EEPROM1_CS, LOW);
|
||||
spiSend(SPI_CHAN_EEPROM1, eeprom_temp, 3);
|
||||
|
||||
spiSend(SPI_CHAN_EEPROM1, (const uint8_t*)src, n);
|
||||
digitalWrite(SPI_EEPROM1_CS, HIGH);
|
||||
delay(7); // wait for page write to complete
|
||||
}
|
||||
|
||||
|
||||
#endif // ENABLED(SPI_EEPROM)
|
@ -0,0 +1,33 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program 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 General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef MATH_32BIT_H
|
||||
#define MATH_32BIT_H
|
||||
|
||||
/**
|
||||
* Math helper functions for 32 bit CPUs
|
||||
*/
|
||||
|
||||
#define MultiU32X32toH32(intRes, longIn1, longIn2) intRes = ((uint64_t)longIn1 * longIn2 + 0x80000000) >> 32
|
||||
#define MultiU32X24toH32(intRes, longIn1, longIn2) intRes = ((uint64_t)longIn1 * longIn2 + 0x00800000) >> 24
|
||||
|
||||
#endif
|
@ -0,0 +1,19 @@
|
||||
#ifndef _PERSISTENT_STORE_H_
|
||||
#define _PERSISTENT_STORE_H_
|
||||
|
||||
#include <stddef.h>
|
||||
#include <stdint.h>
|
||||
|
||||
namespace HAL {
|
||||
namespace PersistentStore {
|
||||
|
||||
bool access_start();
|
||||
bool access_finish();
|
||||
bool write_data(int &pos, const uint8_t *value, uint16_t size, uint16_t *crc);
|
||||
void read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc) ;
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
#endif /* _PERSISTANT_STORE_H_ */
|
@ -0,0 +1,168 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program 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 General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
|
||||
/**
|
||||
* servo.cpp - Interrupt driven Servo library for Arduino using 16 bit timers- Version 2
|
||||
* Copyright (c) 2009 Michael Margolis. All right reserved.
|
||||
*/
|
||||
|
||||
/**
|
||||
* A servo is activated by creating an instance of the Servo class passing the desired pin to the attach() method.
|
||||
* The servos are pulsed in the background using the value most recently written using the write() method
|
||||
*
|
||||
* Note that analogWrite of PWM on pins associated with the timer are disabled when the first servo is attached.
|
||||
* Timers are seized as needed in groups of 12 servos - 24 servos use two timers, 48 servos will use four.
|
||||
*
|
||||
* The methods are:
|
||||
*
|
||||
* Servo - Class for manipulating servo motors connected to Arduino pins.
|
||||
*
|
||||
* attach(pin) - Attach a servo motor to an i/o pin.
|
||||
* attach(pin, min, max) - Attach to a pin, setting min and max values in microseconds
|
||||
* Default min is 544, max is 2400
|
||||
*
|
||||
* write() - Set the servo angle in degrees. (Invalid angles —over MIN_PULSE_WIDTH— are treated as µs.)
|
||||
* writeMicroseconds() - Set the servo pulse width in microseconds.
|
||||
* move(pin, angle) - Sequence of attach(pin), write(angle), delay(SERVO_DELAY).
|
||||
* With DEACTIVATE_SERVOS_AFTER_MOVE it detaches after SERVO_DELAY.
|
||||
* read() - Get the last-written servo pulse width as an angle between 0 and 180.
|
||||
* readMicroseconds() - Get the last-written servo pulse width in microseconds.
|
||||
* attached() - Return true if a servo is attached.
|
||||
* detach() - Stop an attached servo from pulsing its i/o pin.
|
||||
*
|
||||
*/
|
||||
|
||||
|
||||
#include "../../MarlinConfig.h"
|
||||
|
||||
#include "HAL.h"
|
||||
|
||||
#if HAS_SERVOS && !IS_32BIT_TEENSY
|
||||
|
||||
//#include <Arduino.h>
|
||||
|
||||
#include "servo.h"
|
||||
#include "servo_private.h"
|
||||
|
||||
ServoInfo_t servo_info[MAX_SERVOS]; // static array of servo info structures
|
||||
uint8_t ServoCount = 0; // the total number of attached servos
|
||||
|
||||
|
||||
#define SERVO_MIN() (MIN_PULSE_WIDTH - this->min * 4) // minimum value in uS for this servo
|
||||
#define SERVO_MAX() (MAX_PULSE_WIDTH - this->max * 4) // maximum value in uS for this servo
|
||||
|
||||
/************ static functions common to all instances ***********************/
|
||||
|
||||
static boolean isTimerActive(timer16_Sequence_t timer) {
|
||||
// returns true if any servo is active on this timer
|
||||
for (uint8_t channel = 0; channel < SERVOS_PER_TIMER; channel++) {
|
||||
if (SERVO(timer, channel).Pin.isActive)
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
/****************** end of static functions ******************************/
|
||||
|
||||
Servo::Servo() {
|
||||
if (ServoCount < MAX_SERVOS) {
|
||||
this->servoIndex = ServoCount++; // assign a servo index to this instance
|
||||
servo_info[this->servoIndex].ticks = usToTicks(DEFAULT_PULSE_WIDTH); // store default values - 12 Aug 2009
|
||||
}
|
||||
else
|
||||
this->servoIndex = INVALID_SERVO; // too many servos
|
||||
}
|
||||
|
||||
int8_t Servo::attach(int pin) {
|
||||
return this->attach(pin, MIN_PULSE_WIDTH, MAX_PULSE_WIDTH);
|
||||
}
|
||||
|
||||
int8_t Servo::attach(int pin, int min, int max) {
|
||||
|
||||
if (this->servoIndex >= MAX_SERVOS) return -1;
|
||||
|
||||
if (pin > 0) servo_info[this->servoIndex].Pin.nbr = pin;
|
||||
pinMode(servo_info[this->servoIndex].Pin.nbr, OUTPUT); // set servo pin to output
|
||||
|
||||
// todo min/max check: abs(min - MIN_PULSE_WIDTH) /4 < 128
|
||||
this->min = (MIN_PULSE_WIDTH - min) / 4; //resolution of min/max is 4 uS
|
||||
this->max = (MAX_PULSE_WIDTH - max) / 4;
|
||||
|
||||
// initialize the timer if it has not already been initialized
|
||||
timer16_Sequence_t timer = SERVO_INDEX_TO_TIMER(servoIndex);
|
||||
if (!isTimerActive(timer)) initISR(timer);
|
||||
servo_info[this->servoIndex].Pin.isActive = true; // this must be set after the check for isTimerActive
|
||||
|
||||
return this->servoIndex;
|
||||
}
|
||||
|
||||
void Servo::detach() {
|
||||
servo_info[this->servoIndex].Pin.isActive = false;
|
||||
timer16_Sequence_t timer = SERVO_INDEX_TO_TIMER(servoIndex);
|
||||
if (!isTimerActive(timer)) finISR(timer);
|
||||
}
|
||||
|
||||
void Servo::write(int value) {
|
||||
if (value < MIN_PULSE_WIDTH) { // treat values less than 544 as angles in degrees (valid values in microseconds are handled as microseconds)
|
||||
value = map(constrain(value, 0, 180), 0, 180, SERVO_MIN(), SERVO_MAX());
|
||||
}
|
||||
this->writeMicroseconds(value);
|
||||
}
|
||||
|
||||
void Servo::writeMicroseconds(int value) {
|
||||
// calculate and store the values for the given channel
|
||||
byte channel = this->servoIndex;
|
||||
if (channel < MAX_SERVOS) { // ensure channel is valid
|
||||
// ensure pulse width is valid
|
||||
value = constrain(value, SERVO_MIN(), SERVO_MAX()) - (TRIM_DURATION);
|
||||
value = usToTicks(value); // convert to ticks after compensating for interrupt overhead - 12 Aug 2009
|
||||
|
||||
CRITICAL_SECTION_START;
|
||||
servo_info[channel].ticks = value;
|
||||
CRITICAL_SECTION_END;
|
||||
}
|
||||
}
|
||||
|
||||
// return the value as degrees
|
||||
int Servo::read() { return map(this->readMicroseconds() + 1, SERVO_MIN(), SERVO_MAX(), 0, 180); }
|
||||
|
||||
int Servo::readMicroseconds() {
|
||||
return (this->servoIndex == INVALID_SERVO) ? 0 : ticksToUs(servo_info[this->servoIndex].ticks) + TRIM_DURATION;
|
||||
}
|
||||
|
||||
bool Servo::attached() { return servo_info[this->servoIndex].Pin.isActive; }
|
||||
|
||||
void Servo::move(int value) {
|
||||
constexpr uint16_t servo_delay[] = SERVO_DELAY;
|
||||
static_assert(COUNT(servo_delay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long.");
|
||||
if (this->attach(0) >= 0) {
|
||||
this->write(value);
|
||||
delay(servo_delay[this->servoIndex]);
|
||||
#if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE)
|
||||
this->detach();
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
#endif // HAS_SERVOS
|
||||
|
@ -0,0 +1,103 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program 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 General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
servo.h - Interrupt driven Servo library for Arduino using 16 bit timers- Version 2
|
||||
Copyright (c) 2009 Michael Margolis. All right reserved.
|
||||
|
||||
This library is free software; you can redistribute it and/or
|
||||
modify it under the terms of the GNU Lesser General Public
|
||||
License as published by the Free Software Foundation; either
|
||||
version 2.1 of the License, or (at your option) any later version.
|
||||
|
||||
This library is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
|
||||
Lesser General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU Lesser General Public
|
||||
License along with this library; if not, write to the Free Software
|
||||
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
|
||||
*/
|
||||
|
||||
#ifndef servo_private_h
|
||||
#define servo_private_h
|
||||
|
||||
#include <inttypes.h>
|
||||
|
||||
// Architecture specific include
|
||||
#ifdef ARDUINO_ARCH_AVR
|
||||
#include "HAL_AVR/ServoTimers.h"
|
||||
#elif defined(ARDUINO_ARCH_SAM)
|
||||
#include "HAL_DUE/ServoTimers.h"
|
||||
#else
|
||||
#error "This library only supports boards with an AVR or SAM3X processor."
|
||||
#endif
|
||||
|
||||
// Macros
|
||||
|
||||
#define MIN_PULSE_WIDTH 544 // the shortest pulse sent to a servo
|
||||
#define MAX_PULSE_WIDTH 2400 // the longest pulse sent to a servo
|
||||
#define DEFAULT_PULSE_WIDTH 1500 // default pulse width when servo is attached
|
||||
#define REFRESH_INTERVAL 20000 // minimum time to refresh servos in microseconds
|
||||
|
||||
#define SERVOS_PER_TIMER 12 // the maximum number of servos controlled by one timer
|
||||
#define MAX_SERVOS (_Nbr_16timers * SERVOS_PER_TIMER)
|
||||
|
||||
#define INVALID_SERVO 255 // flag indicating an invalid servo index
|
||||
|
||||
//
|
||||
#define usToTicks(_us) (( clockCyclesPerMicrosecond()* _us) / PRESCALER) // converts microseconds to tick (PRESCALER depends on architecture)
|
||||
#define ticksToUs(_ticks) (( (unsigned)_ticks * PRESCALER)/ clockCyclesPerMicrosecond() ) // converts from ticks back to microseconds
|
||||
|
||||
//#define NBR_TIMERS ((MAX_SERVOS) / (SERVOS_PER_TIMER))
|
||||
|
||||
// convenience macros
|
||||
#define SERVO_INDEX_TO_TIMER(_servo_nbr) ((timer16_Sequence_t)(_servo_nbr / (SERVOS_PER_TIMER))) // returns the timer controlling this servo
|
||||
#define SERVO_INDEX_TO_CHANNEL(_servo_nbr) (_servo_nbr % (SERVOS_PER_TIMER)) // returns the index of the servo on this timer
|
||||
#define SERVO_INDEX(_timer,_channel) ((_timer*(SERVOS_PER_TIMER)) + _channel) // macro to access servo index by timer and channel
|
||||
#define SERVO(_timer,_channel) (servo_info[SERVO_INDEX(_timer,_channel)]) // macro to access servo class by timer and channel
|
||||
|
||||
// Types
|
||||
|
||||
typedef struct {
|
||||
uint8_t nbr : 6 ; // a pin number from 0 to 63
|
||||
uint8_t isActive : 1 ; // true if this channel is enabled, pin not pulsed if false
|
||||
} ServoPin_t;
|
||||
|
||||
typedef struct {
|
||||
ServoPin_t Pin;
|
||||
unsigned int ticks;
|
||||
} ServoInfo_t;
|
||||
|
||||
// Global variables
|
||||
|
||||
extern uint8_t ServoCount;
|
||||
extern ServoInfo_t servo_info[MAX_SERVOS];
|
||||
|
||||
// Public functions
|
||||
|
||||
extern void initISR(timer16_Sequence_t timer);
|
||||
extern void finISR(timer16_Sequence_t timer);
|
||||
|
||||
|
||||
#endif
|
Loading…
Reference in New Issue