HAL for DUE architecture

This commit is contained in:
Christopher Pepper
2017-07-19 00:29:06 +01:00
committed by Scott Lahteine
parent 4b16fa3272
commit cfef925559
23 changed files with 2996 additions and 0 deletions

View File

@ -0,0 +1,124 @@
/* **************************************************************************
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 Arduino Due and compatible (SAM3X8E)
*
* For ARDUINO_ARCH_SAM
*/
#ifdef ARDUINO_ARCH_SAM
// --------------------------------------------------------------------------
// Includes
// --------------------------------------------------------------------------
#include "../HAL.h"
#include <Wire.h>
// --------------------------------------------------------------------------
// Externals
// --------------------------------------------------------------------------
// --------------------------------------------------------------------------
// Local defines
// --------------------------------------------------------------------------
// --------------------------------------------------------------------------
// Types
// --------------------------------------------------------------------------
// --------------------------------------------------------------------------
// Variables
// --------------------------------------------------------------------------
// --------------------------------------------------------------------------
// Public Variables
// --------------------------------------------------------------------------
uint16_t HAL_adc_result;
// --------------------------------------------------------------------------
// Private Variables
// --------------------------------------------------------------------------
// --------------------------------------------------------------------------
// Function prototypes
// --------------------------------------------------------------------------
// --------------------------------------------------------------------------
// Private functions
// --------------------------------------------------------------------------
// --------------------------------------------------------------------------
// Public functions
// --------------------------------------------------------------------------
// disable interrupts
void cli(void) { noInterrupts(); }
// enable interrupts
void sei(void) { interrupts(); }
void HAL_clear_reset_source(void) { }
uint8_t HAL_get_reset_source (void) {
switch ((RSTC->RSTC_SR >> 8) & 7) {
case 0: return RST_POWER_ON; break;
case 1: return RST_BACKUP; break;
case 2: return RST_WATCHDOG; break;
case 3: return RST_SOFTWARE; break;
case 4: return RST_EXTERNAL; break;
default:
return 0;
}
}
void _delay_ms(int delay_ms) {
//todo: port for Due?
delay (delay_ms);
}
extern "C" {
extern unsigned int _ebss; // end of bss section
}
// return free memory between end of heap (or end bss) and whatever is current
int freeMemory() {
int free_memory, heap_end = (int)_sbrk(0);
return (int)&free_memory - (heap_end ? heap_end : (int)&_ebss);
}
// --------------------------------------------------------------------------
// ADC
// --------------------------------------------------------------------------
void HAL_adc_start_conversion (uint8_t adc_pin) {
HAL_adc_result = analogRead(adc_pin);
}
uint16_t HAL_adc_get_result(void) {
// nop
return HAL_adc_result;
}
#endif // ARDUINO_ARCH_SAM

View File

@ -0,0 +1,169 @@
/**
* Marlin 3D Printer Firmware
*
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
* Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.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 Arduino Due and compatible (SAM3X8E)
*
* For ARDUINO_ARCH_SAM
*/
#ifndef _HAL_DUE_H
#define _HAL_DUE_H
// --------------------------------------------------------------------------
// Includes
// --------------------------------------------------------------------------
#include <stdint.h>
#include "Arduino.h"
#include "fastio_Due.h"
#include "watchdog_Due.h"
#include "HAL_timers_Due.h"
// --------------------------------------------------------------------------
// Defines
// --------------------------------------------------------------------------
#if SERIAL_PORT == -1
#define MYSERIAL SerialUSB
#elif SERIAL_PORT == 0
#define MYSERIAL Serial
#elif SERIAL_PORT == 1
#define MYSERIAL Serial1
#elif SERIAL_PORT == 2
#define MYSERIAL Serial2
#elif SERIAL_PORT == 3
#define MYSERIAL Serial3
#endif
#define _BV(bit) (1 << (bit))
#ifndef analogInputToDigitalPin
#define analogInputToDigitalPin(p) ((p < 12u) ? (p) + 54u : -1)
#endif
#define CRITICAL_SECTION_START uint32_t primask = __get_PRIMASK(); __disable_irq();
#define CRITICAL_SECTION_END if (!primask) __enable_irq();
// On AVR this is in math.h?
#define square(x) ((x)*(x))
#ifndef strncpy_P
#define strncpy_P(dest, src, num) strncpy((dest), (src), (num))
#endif
// Fix bug in pgm_read_ptr
#undef pgm_read_ptr
#define pgm_read_ptr(addr) (*(addr))
#define RST_POWER_ON 1
#define RST_EXTERNAL 2
#define RST_BROWN_OUT 4
#define RST_WATCHDOG 8
#define RST_JTAG 16
#define RST_SOFTWARE 32
#define RST_BACKUP 64
// --------------------------------------------------------------------------
// Types
// --------------------------------------------------------------------------
// --------------------------------------------------------------------------
// Public Variables
// --------------------------------------------------------------------------
/** result of last ADC conversion */
extern uint16_t HAL_adc_result;
// --------------------------------------------------------------------------
// Public functions
// --------------------------------------------------------------------------
// Disable interrupts
void cli(void);
// Enable interrupts
void sei(void);
/** clear reset reason */
void HAL_clear_reset_source (void);
/** reset reason */
uint8_t HAL_get_reset_source (void);
void _delay_ms(int delay);
int freeMemory(void);
// SPI: Extended functions which take a channel number (hardware SPI only)
/** Write single byte to specified SPI channel */
void spiSend(uint32_t chan, byte b);
/** Write buffer to specified SPI channel */
void spiSend(uint32_t chan, const uint8_t* buf, size_t n);
/** Read single byte from specified SPI channel */
uint8_t spiRec(uint32_t chan);
// EEPROM
void eeprom_write_byte(unsigned char *pos, unsigned char value);
unsigned char eeprom_read_byte(unsigned char *pos);
void eeprom_read_block (void *__dst, const void *__src, size_t __n);
void eeprom_update_block (const void *__src, void *__dst, size_t __n);
// ADC
#define HAL_ANALOG_SELECT(pin)
inline void HAL_adc_init(void) {}//todo
#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin)
#define HAL_READ_ADC HAL_adc_result
void HAL_adc_start_conversion (uint8_t adc_pin);
uint16_t HAL_adc_get_result(void);
//
uint16_t HAL_getAdcReading(uint8_t chan);
void HAL_startAdcConversion(uint8_t chan);
uint8_t HAL_pinToAdcChannel(int pin);
uint16_t HAL_getAdcFreerun(uint8_t chan, bool wait_for_conversion = false);
//uint16_t HAL_getAdcSuperSample(uint8_t chan);
void HAL_enable_AdcFreerun(void);
//void HAL_disable_AdcFreerun(uint8_t chan);
// --------------------------------------------------------------------------
//
// --------------------------------------------------------------------------
#endif // _HAL_DUE_H

View File

@ -0,0 +1,336 @@
/**
* 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/>.
*
*/
/**
* Software SPI functions originally from Arduino Sd2Card Library
* Copyright (C) 2009 by William Greiman
*/
/**
* Description: HAL for Arduino Due and compatible (SAM3X8E)
*
* For ARDUINO_ARCH_SAM
*/
#ifdef ARDUINO_ARCH_SAM
// --------------------------------------------------------------------------
// Includes
// --------------------------------------------------------------------------
#include "../../../MarlinConfig.h"
// --------------------------------------------------------------------------
// Public Variables
// --------------------------------------------------------------------------
// --------------------------------------------------------------------------
// Public functions
// --------------------------------------------------------------------------
#if ENABLED(SOFTWARE_SPI)
// --------------------------------------------------------------------------
// software SPI
// --------------------------------------------------------------------------
// bitbanging transfer
// run at ~100KHz (necessary for init)
static uint8_t spiTransfer(uint8_t b) { // using Mode 0
for (int bits = 0; bits < 8; bits++) {
if (b & 0x80) {
WRITE(MOSI_PIN, HIGH);
}
else {
WRITE(MOSI_PIN, LOW);
}
b <<= 1;
WRITE(SCK_PIN, HIGH);
delayMicroseconds(5U);
if (READ(MISO_PIN)) {
b |= 1;
}
WRITE(SCK_PIN, LOW);
delayMicroseconds(5U);
}
return b;
}
void spiBegin() {
SET_OUTPUT(SS_PIN);
WRITE(SS_PIN, HIGH);
SET_OUTPUT(SCK_PIN);
SET_INPUT(MISO_PIN);
SET_OUTPUT(MOSI_PIN);
}
void spiInit(uint8_t spiRate) {
UNUSED(spiRate);
WRITE(SS_PIN, HIGH);
WRITE(MOSI_PIN, HIGH);
WRITE(SCK_PIN, LOW);
}
uint8_t spiRec() {
WRITE(SS_PIN, LOW);
uint8_t b = spiTransfer(0xff);
WRITE(SS_PIN, HIGH);
return b;
}
void spiRead(uint8_t*buf, uint16_t nbyte) {
if (nbyte == 0) return;
WRITE(SS_PIN, LOW);
for (int i = 0; i < nbyte; i++) {
buf[i] = spiTransfer(0xff);
}
WRITE(SS_PIN, HIGH);
}
void spiSend(uint8_t b) {
WRITE(SS_PIN, LOW);
uint8_t response = spiTransfer(b);
UNUSED(response);
WRITE(SS_PIN, HIGH);
}
static void spiSend(const uint8_t* buf, size_t n) {
uint8_t response;
if (n == 0) return;
WRITE(SS_PIN, LOW);
for (uint16_t i = 0; i < n; i++) {
response = spiTransfer(buf[i]);
}
UNUSED(response);
WRITE(SS_PIN, HIGH);
}
void spiSendBlock(uint8_t token, const uint8_t* buf) {
uint8_t response;
WRITE(SS_PIN, LOW);
response = spiTransfer(token);
for (uint16_t i = 0; i < 512; i++) {
response = spiTransfer(buf[i]);
}
UNUSED(response);
WRITE(SS_PIN, HIGH);
}
#else
// --------------------------------------------------------------------------
// hardware SPI
// --------------------------------------------------------------------------
// 8.4 MHz, 4 MHz, 2 MHz, 1 MHz, 0.5 MHz, 0.329 MHz, 0.329 MHz
int spiDueDividors[] = { 10, 21, 42, 84, 168, 255, 255 };
bool spiInitMaded = false;
void spiBegin() {
if(spiInitMaded == false) {
// Configure SPI pins
PIO_Configure(
g_APinDescription[SCK_PIN].pPort,
g_APinDescription[SCK_PIN].ulPinType,
g_APinDescription[SCK_PIN].ulPin,
g_APinDescription[SCK_PIN].ulPinConfiguration);
PIO_Configure(
g_APinDescription[MOSI_PIN].pPort,
g_APinDescription[MOSI_PIN].ulPinType,
g_APinDescription[MOSI_PIN].ulPin,
g_APinDescription[MOSI_PIN].ulPinConfiguration);
PIO_Configure(
g_APinDescription[MISO_PIN].pPort,
g_APinDescription[MISO_PIN].ulPinType,
g_APinDescription[MISO_PIN].ulPin,
g_APinDescription[MISO_PIN].ulPinConfiguration);
// set master mode, peripheral select, fault detection
SPI_Configure(SPI0, ID_SPI0, SPI_MR_MSTR | SPI_MR_MODFDIS | SPI_MR_PS);
SPI_Enable(SPI0);
#if MB(ALLIGATOR)
SET_OUTPUT(DAC0_SYNC);
#if EXTRUDERS > 1
SET_OUTPUT(DAC1_SYNC);
WRITE(DAC1_SYNC, HIGH);
#endif
SET_OUTPUT(SPI_EEPROM1_CS);
SET_OUTPUT(SPI_EEPROM2_CS);
SET_OUTPUT(SPI_FLASH_CS);
WRITE(DAC0_SYNC, HIGH);
WRITE(SPI_EEPROM1_CS, HIGH );
WRITE(SPI_EEPROM2_CS, HIGH );
WRITE(SPI_FLASH_CS, HIGH );
WRITE(SS_PIN, HIGH );
#endif // MB(ALLIGATOR)
PIO_Configure(
g_APinDescription[SPI_PIN].pPort,
g_APinDescription[SPI_PIN].ulPinType,
g_APinDescription[SPI_PIN].ulPin,
g_APinDescription[SPI_PIN].ulPinConfiguration);
spiInit(1);
spiInitMaded = true;
}
}
void spiInit(uint8_t spiRate) {
if(spiInitMaded == false) {
if(spiRate > 6) spiRate = 1;
#if MB(ALLIGATOR)
// Set SPI mode 1, clock, select not active after transfer, with delay between transfers
SPI_ConfigureNPCS(SPI0, SPI_CHAN_DAC,
SPI_CSR_CSAAT | SPI_CSR_SCBR(spiDueDividors[spiRate]) |
SPI_CSR_DLYBCT(1));
// Set SPI mode 0, clock, select not active after transfer, with delay between transfers
SPI_ConfigureNPCS(SPI0, SPI_CHAN_EEPROM1, SPI_CSR_NCPHA |
SPI_CSR_CSAAT | SPI_CSR_SCBR(spiDueDividors[spiRate]) |
SPI_CSR_DLYBCT(1));
#endif//MB(ALLIGATOR)
// Set SPI mode 0, clock, select not active after transfer, with delay between transfers
SPI_ConfigureNPCS(SPI0, SPI_CHAN, SPI_CSR_NCPHA |
SPI_CSR_CSAAT | SPI_CSR_SCBR(spiDueDividors[spiRate]) |
SPI_CSR_DLYBCT(1));
SPI_Enable(SPI0);
spiInitMaded = true;
}
}
// Write single byte to SPI
void spiSend(byte b) {
// write byte with address and end transmission flag
SPI0->SPI_TDR = (uint32_t)b | SPI_PCS(SPI_CHAN) | SPI_TDR_LASTXFER;
// wait for transmit register empty
while ((SPI0->SPI_SR & SPI_SR_TDRE) == 0);
// wait for receive register
while ((SPI0->SPI_SR & SPI_SR_RDRF) == 0);
// clear status
SPI0->SPI_RDR;
//delayMicroseconds(1U);
}
void spiSend(const uint8_t* buf, size_t n) {
if (n == 0) return;
for (size_t i = 0; i < n - 1; i++) {
SPI0->SPI_TDR = (uint32_t)buf[i] | SPI_PCS(SPI_CHAN);
while ((SPI0->SPI_SR & SPI_SR_TDRE) == 0);
while ((SPI0->SPI_SR & SPI_SR_RDRF) == 0);
SPI0->SPI_RDR;
//delayMicroseconds(1U);
}
spiSend(buf[n - 1]);
}
void spiSend(uint32_t chan, byte b) {
uint8_t dummy_read = 0;
// wait for transmit register empty
while ((SPI0->SPI_SR & SPI_SR_TDRE) == 0);
// write byte with address and end transmission flag
SPI0->SPI_TDR = (uint32_t)b | SPI_PCS(chan) | SPI_TDR_LASTXFER;
// wait for receive register
while ((SPI0->SPI_SR & SPI_SR_RDRF) == 0);
// clear status
while ((SPI0->SPI_SR & SPI_SR_RDRF) == 1)
dummy_read = SPI0->SPI_RDR;
UNUSED(dummy_read);
}
void spiSend(uint32_t chan, const uint8_t* buf, size_t n) {
uint8_t dummy_read = 0;
if (n == 0) return;
for (int i = 0; i < (int)n - 1; i++) {
while ((SPI0->SPI_SR & SPI_SR_TDRE) == 0);
SPI0->SPI_TDR = (uint32_t)buf[i] | SPI_PCS(chan);
while ((SPI0->SPI_SR & SPI_SR_RDRF) == 0);
while ((SPI0->SPI_SR & SPI_SR_RDRF) == 1)
dummy_read = SPI0->SPI_RDR;
UNUSED(dummy_read);
}
spiSend(chan, buf[n - 1]);
}
// Read single byte from SPI
uint8_t spiRec() {
// write dummy byte with address and end transmission flag
SPI0->SPI_TDR = 0x000000FF | SPI_PCS(SPI_CHAN) | SPI_TDR_LASTXFER;
// wait for transmit register empty
while ((SPI0->SPI_SR & SPI_SR_TDRE) == 0);
// wait for receive register
while ((SPI0->SPI_SR & SPI_SR_RDRF) == 0);
// get byte from receive register
//delayMicroseconds(1U);
return SPI0->SPI_RDR;
}
uint8_t spiRec(uint32_t chan) {
uint8_t spirec_tmp;
// wait for transmit register empty
while ((SPI0->SPI_SR & SPI_SR_TDRE) == 0);
while ((SPI0->SPI_SR & SPI_SR_RDRF) == 1)
spirec_tmp = SPI0->SPI_RDR;
UNUSED(spirec_tmp);
// write dummy byte with address and end transmission flag
SPI0->SPI_TDR = 0x000000FF | SPI_PCS(chan) | SPI_TDR_LASTXFER;
// wait for receive register
while ((SPI0->SPI_SR & SPI_SR_RDRF) == 0);
// get byte from receive register
return SPI0->SPI_RDR;
}
// Read from SPI into buffer
void spiRead(uint8_t*buf, uint16_t nbyte) {
if (nbyte-- == 0) return;
for (int i = 0; i < nbyte; i++) {
//while ((SPI0->SPI_SR & SPI_SR_TDRE) == 0);
SPI0->SPI_TDR = 0x000000FF | SPI_PCS(SPI_CHAN);
while ((SPI0->SPI_SR & SPI_SR_RDRF) == 0);
buf[i] = SPI0->SPI_RDR;
//delayMicroseconds(1U);
}
buf[nbyte] = spiRec();
}
// Write from buffer to SPI
void spiSendBlock(uint8_t token, const uint8_t* buf) {
SPI0->SPI_TDR = (uint32_t)token | SPI_PCS(SPI_CHAN);
while ((SPI0->SPI_SR & SPI_SR_TDRE) == 0);
//while ((SPI0->SPI_SR & SPI_SR_RDRF) == 0);
//SPI0->SPI_RDR;
for (int i = 0; i < 511; i++) {
SPI0->SPI_TDR = (uint32_t)buf[i] | SPI_PCS(SPI_CHAN);
while ((SPI0->SPI_SR & SPI_SR_TDRE) == 0);
while ((SPI0->SPI_SR & SPI_SR_RDRF) == 0);
SPI0->SPI_RDR;
//delayMicroseconds(1U);
}
spiSend(buf[511]);
}
#endif // ENABLED(SOFTWARE_SPI)
#endif // ARDUINO_ARCH_SAM

View File

@ -0,0 +1,137 @@
/**
* Marlin 3D Printer Firmware
*
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
* Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.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 Arduino Due and compatible (SAM3X8E)
*
* For ARDUINO_ARCH_SAM
*/
#ifdef ARDUINO_ARCH_SAM
// --------------------------------------------------------------------------
// Includes
// --------------------------------------------------------------------------
#include "../HAL.h"
#include "HAL_timers_Due.h"
// --------------------------------------------------------------------------
// Externals
// --------------------------------------------------------------------------
// --------------------------------------------------------------------------
// Local defines
// --------------------------------------------------------------------------
#define NUM_HARDWARE_TIMERS 9
#define PRESCALER 2
// --------------------------------------------------------------------------
// Types
// --------------------------------------------------------------------------
// --------------------------------------------------------------------------
// Public Variables
// --------------------------------------------------------------------------
// --------------------------------------------------------------------------
// Private Variables
// --------------------------------------------------------------------------
const tTimerConfig TimerConfig [NUM_HARDWARE_TIMERS] = {
{ TC0, 0, TC0_IRQn, 0}, // 0 - [servo timer5]
{ TC0, 1, TC1_IRQn, 0}, // 1
{ TC0, 2, TC2_IRQn, 0}, // 2
{ TC1, 0, TC3_IRQn, 2}, // 3 - stepper
{ TC1, 1, TC4_IRQn, 15}, // 4 - temperature
{ TC1, 2, TC5_IRQn, 0}, // 5 - [servo timer3]
{ TC2, 0, TC6_IRQn, 0}, // 6
{ TC2, 1, TC7_IRQn, 0}, // 7
{ TC2, 2, TC8_IRQn, 0}, // 8
};
// --------------------------------------------------------------------------
// Function prototypes
// --------------------------------------------------------------------------
// --------------------------------------------------------------------------
// Private functions
// --------------------------------------------------------------------------
// --------------------------------------------------------------------------
// Public functions
// --------------------------------------------------------------------------
/*
Timer_clock1: Prescaler 2 -> 42MHz
Timer_clock2: Prescaler 8 -> 10.5MHz
Timer_clock3: Prescaler 32 -> 2.625MHz
Timer_clock4: Prescaler 128 -> 656.25kHz
*/
void HAL_timer_start (uint8_t timer_num, uint32_t frequency) {
Tc *tc = TimerConfig [timer_num].pTimerRegs;
IRQn_Type irq = TimerConfig [timer_num].IRQ_Id;
uint32_t channel = TimerConfig [timer_num].channel;
pmc_set_writeprotect(false);
pmc_enable_periph_clk((uint32_t)irq);
NVIC_SetPriority (irq, TimerConfig [timer_num].priority);
TC_Configure (tc, channel, TC_CMR_WAVE | TC_CMR_WAVSEL_UP_RC | TC_CMR_TCCLKS_TIMER_CLOCK1);
TC_SetRC(tc, channel, VARIANT_MCK/2/frequency);
TC_Start(tc, channel);
// enable interrupt on RC compare
tc->TC_CHANNEL[channel].TC_IER = TC_IER_CPCS;
NVIC_EnableIRQ(irq);
}
void HAL_timer_enable_interrupt (uint8_t timer_num) {
const tTimerConfig *pConfig = &TimerConfig [timer_num];
pConfig->pTimerRegs->TC_CHANNEL [pConfig->channel].TC_IER = TC_IER_CPCS;
}
void HAL_timer_disable_interrupt (uint8_t timer_num) {
const tTimerConfig *pConfig = &TimerConfig [timer_num];
pConfig->pTimerRegs->TC_CHANNEL [pConfig->channel].TC_IDR = TC_IDR_CPCS;
}
#if 0
void HAL_timer_set_count (uint8_t timer_num, uint32_t count) {
const tTimerConfig *pConfig = &TimerConfig [timer_num];
TC_SetRC (pConfig->pTimerRegs, pConfig->channel, count);
}
void HAL_timer_isr_prologue (uint8_t timer_num) {
const tTimerConfig *pConfig = &TimerConfig [timer_num];
TC_GetStatus (pConfig->pTimerRegs, pConfig->channel);
}
#endif
#endif // ARDUINO_ARCH_SAM

View File

@ -0,0 +1,116 @@
/**
* 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/>.
*
*/
/**
* HAL for Arduino Due and compatible (SAM3X8E)
*
* For ARDUINO_ARCH_SAM
*/
#ifndef _HAL_TIMERS_DUE_H
#define _HAL_TIMERS_DUE_H
// --------------------------------------------------------------------------
// Includes
// --------------------------------------------------------------------------
#include <stdint.h>
// --------------------------------------------------------------------------
// Defines
// --------------------------------------------------------------------------
#define FORCE_INLINE __attribute__((always_inline)) inline
#define HAL_TIMER_TYPE uint32_t
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFF
#define STEP_TIMER_NUM 3 // index of timer to use for stepper
#define TEMP_TIMER_NUM 4 // index of timer to use for temperature
#define HAL_TIMER_RATE ((F_CPU) / 2.0) // frequency of timers peripherals
#define STEPPER_TIMER_PRESCALE 1.0 // prescaler for setting stepper frequency
#define HAL_STEPPER_TIMER_RATE HAL_TIMER_RATE // frequency of stepper timer (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE)
#define HAL_TICKS_PER_US ((HAL_STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per us
#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency
#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt (STEP_TIMER_NUM)
#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt (STEP_TIMER_NUM)
#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt (TEMP_TIMER_NUM)
#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt (TEMP_TIMER_NUM)
#define HAL_ENABLE_ISRs() do { if (thermalManager.in_temp_isr)DISABLE_TEMPERATURE_INTERRUPT(); else ENABLE_TEMPERATURE_INTERRUPT(); ENABLE_STEPPER_DRIVER_INTERRUPT(); } while(0)
//
#define HAL_STEP_TIMER_ISR void TC3_Handler()
#define HAL_TEMP_TIMER_ISR void TC4_Handler()
// --------------------------------------------------------------------------
// Types
// --------------------------------------------------------------------------
typedef struct {
Tc *pTimerRegs;
uint16_t channel;
IRQn_Type IRQ_Id;
uint8_t priority;
} tTimerConfig;
// --------------------------------------------------------------------------
// Public Variables
// --------------------------------------------------------------------------
extern const tTimerConfig TimerConfig[];
// --------------------------------------------------------------------------
// Public functions
// --------------------------------------------------------------------------
void HAL_timer_start (uint8_t timer_num, uint32_t frequency);
static FORCE_INLINE void HAL_timer_set_count (uint8_t timer_num, uint32_t count) {
const tTimerConfig *pConfig = &TimerConfig[timer_num];
pConfig->pTimerRegs->TC_CHANNEL[pConfig->channel].TC_RC = count;
}
static FORCE_INLINE HAL_TIMER_TYPE HAL_timer_get_count (uint8_t timer_num) {
const tTimerConfig *pConfig = &TimerConfig[timer_num];
return pConfig->pTimerRegs->TC_CHANNEL[pConfig->channel].TC_RC;
}
static FORCE_INLINE uint32_t HAL_timer_get_current_count(uint8_t timer_num) {
const tTimerConfig *pConfig = &TimerConfig[timer_num];
return pConfig->pTimerRegs->TC_CHANNEL[pConfig->channel].TC_CV;
}
void HAL_timer_enable_interrupt(uint8_t timer_num);
void HAL_timer_disable_interrupt(uint8_t timer_num);
//void HAL_timer_isr_prologue (uint8_t timer_num);
static FORCE_INLINE void HAL_timer_isr_prologue(uint8_t timer_num) {
const tTimerConfig *pConfig = &TimerConfig[timer_num];
// Reading the status register clears the interrupt flag
pConfig->pTimerRegs->TC_CHANNEL[pConfig->channel].TC_SR;
}
#endif // _HAL_TIMERS_DUE_H

View File

@ -0,0 +1,161 @@
/**
* 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/>.
*
*/
/*
Copyright (c) 2013 Arduino LLC. 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
*/
#ifdef ARDUINO_ARCH_SAM
#include "../../../MarlinConfig.h"
#if HAS_SERVOS
#include <Arduino.h>
#include "../servo.h"
#include "../servo_private.h"
static volatile int8_t Channel[_Nbr_16timers ]; // counter for the servo being pulsed for each timer (or -1 if refresh interval)
//------------------------------------------------------------------------------
/// Interrupt handler for the TC0 channel 1.
//------------------------------------------------------------------------------
void Servo_Handler(timer16_Sequence_t timer, Tc *pTc, uint8_t channel);
#ifdef _useTimer1
void HANDLER_FOR_TIMER1(void) { Servo_Handler(_timer1, TC_FOR_TIMER1, CHANNEL_FOR_TIMER1); }
#endif
#ifdef _useTimer2
void HANDLER_FOR_TIMER2(void) { Servo_Handler(_timer2, TC_FOR_TIMER2, CHANNEL_FOR_TIMER2); }
#endif
#ifdef _useTimer3
void HANDLER_FOR_TIMER3(void) { Servo_Handler(_timer3, TC_FOR_TIMER3, CHANNEL_FOR_TIMER3); }
#endif
#ifdef _useTimer4
void HANDLER_FOR_TIMER4(void) { Servo_Handler(_timer4, TC_FOR_TIMER4, CHANNEL_FOR_TIMER4); }
#endif
#ifdef _useTimer5
void HANDLER_FOR_TIMER5(void) { Servo_Handler(_timer5, TC_FOR_TIMER5, CHANNEL_FOR_TIMER5); }
#endif
void Servo_Handler(timer16_Sequence_t timer, Tc *tc, uint8_t channel) {
// clear interrupt
tc->TC_CHANNEL[channel].TC_SR;
if (Channel[timer] < 0)
tc->TC_CHANNEL[channel].TC_CCR |= TC_CCR_SWTRG; // channel set to -1 indicated that refresh interval completed so reset the timer
else if (SERVO_INDEX(timer,Channel[timer]) < ServoCount && SERVO(timer,Channel[timer]).Pin.isActive)
digitalWrite(SERVO(timer,Channel[timer]).Pin.nbr, LOW); // pulse this channel low if activated
Channel[timer]++; // increment to the next channel
if (SERVO_INDEX(timer, Channel[timer]) < ServoCount && Channel[timer] < SERVOS_PER_TIMER) {
tc->TC_CHANNEL[channel].TC_RA = tc->TC_CHANNEL[channel].TC_CV + SERVO(timer,Channel[timer]).ticks;
if (SERVO(timer,Channel[timer]).Pin.isActive) // check if activated
digitalWrite( SERVO(timer,Channel[timer]).Pin.nbr,HIGH); // its an active channel so pulse it high
}
else {
// finished all channels so wait for the refresh period to expire before starting over
tc->TC_CHANNEL[channel].TC_RA =
tc->TC_CHANNEL[channel].TC_CV < usToTicks(REFRESH_INTERVAL) - 4
? (unsigned int)usToTicks(REFRESH_INTERVAL) // allow a few ticks to ensure the next OCR1A not missed
: tc->TC_CHANNEL[channel].TC_CV + 4; // at least REFRESH_INTERVAL has elapsed
Channel[timer] = -1; // this will get incremented at the end of the refresh period to start again at the first channel
}
}
static void _initISR(Tc *tc, uint32_t channel, uint32_t id, IRQn_Type irqn) {
pmc_enable_periph_clk(id);
TC_Configure(tc, channel,
TC_CMR_TCCLKS_TIMER_CLOCK3 | // MCK/32
TC_CMR_WAVE | // Waveform mode
TC_CMR_WAVSEL_UP_RC ); // Counter running up and reset when equals to RC
/* 84MHz, MCK/32, for 1.5ms: 3937 */
TC_SetRA(tc, channel, 2625); // 1ms
/* Configure and enable interrupt */
NVIC_EnableIRQ(irqn);
// TC_IER_CPAS: RA Compare
tc->TC_CHANNEL[channel].TC_IER = TC_IER_CPAS;
// Enables the timer clock and performs a software reset to start the counting
TC_Start(tc, channel);
}
void initISR(timer16_Sequence_t timer) {
#ifdef _useTimer1
if (timer == _timer1)
_initISR(TC_FOR_TIMER1, CHANNEL_FOR_TIMER1, ID_TC_FOR_TIMER1, IRQn_FOR_TIMER1);
#endif
#ifdef _useTimer2
if (timer == _timer2)
_initISR(TC_FOR_TIMER2, CHANNEL_FOR_TIMER2, ID_TC_FOR_TIMER2, IRQn_FOR_TIMER2);
#endif
#ifdef _useTimer3
if (timer == _timer3)
_initISR(TC_FOR_TIMER3, CHANNEL_FOR_TIMER3, ID_TC_FOR_TIMER3, IRQn_FOR_TIMER3);
#endif
#ifdef _useTimer4
if (timer == _timer4)
_initISR(TC_FOR_TIMER4, CHANNEL_FOR_TIMER4, ID_TC_FOR_TIMER4, IRQn_FOR_TIMER4);
#endif
#ifdef _useTimer5
if (timer == _timer5)
_initISR(TC_FOR_TIMER5, CHANNEL_FOR_TIMER5, ID_TC_FOR_TIMER5, IRQn_FOR_TIMER5);
#endif
}
void finISR(timer16_Sequence_t timer) {
#ifdef _useTimer1
TC_Stop(TC_FOR_TIMER1, CHANNEL_FOR_TIMER1);
#endif
#ifdef _useTimer2
TC_Stop(TC_FOR_TIMER2, CHANNEL_FOR_TIMER2);
#endif
#ifdef _useTimer3
TC_Stop(TC_FOR_TIMER3, CHANNEL_FOR_TIMER3);
#endif
#ifdef _useTimer4
TC_Stop(TC_FOR_TIMER4, CHANNEL_FOR_TIMER4);
#endif
#ifdef _useTimer5
TC_Stop(TC_FOR_TIMER5, CHANNEL_FOR_TIMER5);
#endif
}
#endif // HAS_SERVOS
#endif // ARDUINO_ARCH_SAM

View File

@ -0,0 +1,75 @@
/**
* 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/>.
*
*/
/**
* Endstop Interrupts
*
* Without endstop interrupts the endstop pins must be polled continually in
* the stepper-ISR via endstops.update(), most of the time finding no change.
* With this feature endstops.update() is called only when we know that at
* least one endstop has changed state, saving valuable CPU cycles.
*
* This feature only works when all used endstop pins can generate an 'external interrupt'.
*
* Test whether pins issue interrupts on your board by flashing 'pin_interrupt_test.ino'.
* (Located in Marlin/buildroot/share/pin_interrupt_test/pin_interrupt_test.ino)
*/
#ifndef _ENDSTOP_INTERRUPTS_H_
#define _ENDSTOP_INTERRUPTS_H_
/**
* Endstop interrupts for Due based targets.
* On Due, all pins support external interrupt capability.
*/
void setup_endstop_interrupts(void) {
#if HAS_X_MAX
attachInterrupt(digitalPinToInterrupt(X_MAX_PIN), endstop_ISR, CHANGE); // assign it
#endif
#if HAS_X_MIN
attachInterrupt(digitalPinToInterrupt(X_MIN_PIN), endstop_ISR, CHANGE);
#endif
#if HAS_Y_MAX
attachInterrupt(digitalPinToInterrupt(Y_MAX_PIN), endstop_ISR, CHANGE);
#endif
#if HAS_Y_MIN
attachInterrupt(digitalPinToInterrupt(Y_MIN_PIN), endstop_ISR, CHANGE);
#endif
#if HAS_Z_MAX
attachInterrupt(digitalPinToInterrupt(Z_MAX_PIN), endstop_ISR, CHANGE);
#endif
#if HAS_Z_MIN
attachInterrupt(digitalPinToInterrupt(Z_MIN_PIN), endstop_ISR, CHANGE);
#endif
#if HAS_Z2_MAX
attachInterrupt(digitalPinToInterrupt(Z2_MAX_PIN), endstop_ISR, CHANGE);
#endif
#if HAS_Z2_MIN
attachInterrupt(digitalPinToInterrupt(Z2_MIN_PIN), endstop_ISR, CHANGE);
#endif
#if HAS_Z_MIN_PROBE_PIN
attachInterrupt(digitalPinToInterrupt(Z_MIN_PROBE_PIN), endstop_ISR, CHANGE);
#endif
}
#endif //_ENDSTOP_INTERRUPTS_H_

View File

@ -0,0 +1,435 @@
/**
* 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/>.
*
*/
/**
This code contributed by Triffid_Hunter and modified by Kliment
why double up on these macros? see http://gcc.gnu.org/onlinedocs/cpp/Stringification.html
*/
/**
* Description: Fast IO functions for Arduino Due and compatible (SAM3X8E)
*
* For ARDUINO_ARCH_SAM
*/
#ifndef _FASTIO_DUE_H
#define _FASTIO_DUE_H
/**
utility functions
*/
#ifndef MASK
#define MASK(PIN) (1 << PIN)
#endif
/**
magic I/O routines
now you can simply SET_OUTPUT(STEP); WRITE(STEP, 1); WRITE(STEP, 0);
*/
/// Read a pin
#define _READ(IO) ((bool)(DIO ## IO ## _WPORT -> PIO_PDSR & (MASK(DIO ## IO ## _PIN))))
/// Write to a pin
#define _WRITE_VAR(IO, v) do { if (v) {g_APinDescription[IO].pPort->PIO_SODR = g_APinDescription[IO].ulPin; } \
else {g_APinDescription[IO].pPort->PIO_CODR = g_APinDescription[IO].ulPin; } \
} while (0)
#define _WRITE(IO, v) do { if (v) {DIO ## IO ## _WPORT -> PIO_SODR = MASK(DIO ## IO ##_PIN); } \
else {DIO ## IO ## _WPORT -> PIO_CODR = MASK(DIO ## IO ## _PIN); }; \
} while (0)
/// toggle a pin
#define _TOGGLE(IO) _WRITE(IO, !READ(IO))
/// set pin as input
#define _SET_INPUT(IO) pmc_enable_periph_clk(g_APinDescription[IO].ulPeripheralId); \
PIO_Configure(g_APinDescription[IO].pPort, PIO_INPUT, g_APinDescription[IO].ulPin, 0)
/// set pin as output
#define _SET_OUTPUT(IO) PIO_Configure(g_APinDescription[IO].pPort, PIO_OUTPUT_1, \
g_APinDescription[IO].ulPin, g_APinDescription[IO].ulPinConfiguration)
/// set pin as input with pullup mode
#define _PULLUP(IO, v) { pinMode(IO, (v!=LOW ? INPUT_PULLUP : INPUT)); }
/// check if pin is an input
#define _GET_INPUT(IO)
/// check if pin is an output
#define _GET_OUTPUT(IO)
/// check if pin is an timer
#define _GET_TIMER(IO)
// why double up on these macros? see http://gcc.gnu.org/onlinedocs/cpp/Stringification.html
/// Read a pin wrapper
#define READ(IO) _READ(IO)
/// Write to a pin wrapper
#define WRITE_VAR(IO, v) _WRITE_VAR(IO, v)
#define WRITE(IO, v) _WRITE(IO, v)
/// toggle a pin wrapper
#define TOGGLE(IO) _TOGGLE(IO)
/// set pin as input wrapper
#define SET_INPUT(IO) _SET_INPUT(IO)
/// set pin as input with pullup wrapper
#define SET_INPUT_PULLUP(IO) do{ _SET_INPUT(IO); _PULLUP(IO, HIGH); }while(0)
/// set pin as output wrapper
#define SET_OUTPUT(IO) do{ _SET_OUTPUT(IO); _WRITE(IO, LOW); }while(0)
/// check if pin is an input wrapper
#define GET_INPUT(IO) _GET_INPUT(IO)
/// check if pin is an output wrapper
#define GET_OUTPUT(IO) _GET_OUTPUT(IO)
/// check if pin is an timer wrapper
#define GET_TIMER(IO) _GET_TIMER(IO)
// Shorthand
#define OUT_WRITE(IO, v) { SET_OUTPUT(IO); WRITE(IO, v); }
/**
ports and functions
added as necessary or if I feel like it- not a comprehensive list!
*/
// UART
#define RXD DIO0
#define TXD DIO1
// TWI (I2C)
#define SCL DIO21
#define SDA DIO20
/**
pins
*/
#define DIO0_PIN 8
#define DIO0_WPORT PIOA
#define DIO1_PIN 9
#define DIO1_WPORT PIOA
#define DIO2_PIN 25
#define DIO2_WPORT PIOB
#define DIO3_PIN 28
#define DIO3_WPORT PIOC
#define DIO4_PIN 26
#define DIO4_WPORT PIOC
#define DIO5_PIN 25
#define DIO5_WPORT PIOC
#define DIO6_PIN 24
#define DIO6_WPORT PIOC
#define DIO7_PIN 23
#define DIO7_WPORT PIOC
#define DIO8_PIN 22
#define DIO8_WPORT PIOC
#define DIO9_PIN 21
#define DIO9_WPORT PIOC
#define DIO10_PIN 29
#define DIO10_WPORT PIOC
#define DIO11_PIN 7
#define DIO11_WPORT PIOD
#define DIO12_PIN 8
#define DIO12_WPORT PIOD
#define DIO13_PIN 27
#define DIO13_WPORT PIOB
#define DIO14_PIN 4
#define DIO14_WPORT PIOD
#define DIO15_PIN 5
#define DIO15_WPORT PIOD
#define DIO16_PIN 13
#define DIO16_WPORT PIOA
#define DIO17_PIN 12
#define DIO17_WPORT PIOA
#define DIO18_PIN 11
#define DIO18_WPORT PIOA
#define DIO19_PIN 10
#define DIO19_WPORT PIOA
#define DIO20_PIN 12
#define DIO20_WPORT PIOB
#define DIO21_PIN 13
#define DIO21_WPORT PIOB
#define DIO22_PIN 26
#define DIO22_WPORT PIOB
#define DIO23_PIN 14
#define DIO23_WPORT PIOA
#define DIO24_PIN 15
#define DIO24_WPORT PIOA
#define DIO25_PIN 0
#define DIO25_WPORT PIOD
#define DIO26_PIN 1
#define DIO26_WPORT PIOD
#define DIO27_PIN 2
#define DIO27_WPORT PIOD
#define DIO28_PIN 3
#define DIO28_WPORT PIOD
#define DIO29_PIN 6
#define DIO29_WPORT PIOD
#define DIO30_PIN 9
#define DIO30_WPORT PIOD
#define DIO31_PIN 7
#define DIO31_WPORT PIOA
#define DIO32_PIN 10
#define DIO32_WPORT PIOD
#define DIO33_PIN 1
#define DIO33_WPORT PIOC
#define DIO34_PIN 2
#define DIO34_WPORT PIOC
#define DIO35_PIN 3
#define DIO35_WPORT PIOC
#define DIO36_PIN 4
#define DIO36_WPORT PIOC
#define DIO37_PIN 5
#define DIO37_WPORT PIOC
#define DIO38_PIN 6
#define DIO38_WPORT PIOC
#define DIO39_PIN 7
#define DIO39_WPORT PIOC
#define DIO40_PIN 8
#define DIO40_WPORT PIOC
#define DIO41_PIN 9
#define DIO41_WPORT PIOC
#define DIO42_PIN 19
#define DIO42_WPORT PIOA
#define DIO43_PIN 20
#define DIO43_WPORT PIOA
#define DIO44_PIN 19
#define DIO44_WPORT PIOC
#define DIO45_PIN 18
#define DIO45_WPORT PIOC
#define DIO46_PIN 17
#define DIO46_WPORT PIOC
#define DIO47_PIN 16
#define DIO47_WPORT PIOC
#define DIO48_PIN 15
#define DIO48_WPORT PIOC
#define DIO49_PIN 14
#define DIO49_WPORT PIOC
#define DIO50_PIN 13
#define DIO50_WPORT PIOC
#define DIO51_PIN 12
#define DIO51_WPORT PIOC
#define DIO52_PIN 21
#define DIO52_WPORT PIOB
#define DIO53_PIN 14
#define DIO53_WPORT PIOB
#define DIO54_PIN 16
#define DIO54_WPORT PIOA
#define DIO55_PIN 24
#define DIO55_WPORT PIOA
#define DIO56_PIN 23
#define DIO56_WPORT PIOA
#define DIO57_PIN 22
#define DIO57_WPORT PIOA
#define DIO58_PIN 6
#define DIO58_WPORT PIOA
#define DIO59_PIN 4
#define DIO59_WPORT PIOA
#define DIO60_PIN 3
#define DIO60_WPORT PIOA
#define DIO61_PIN 2
#define DIO61_WPORT PIOA
#define DIO62_PIN 17
#define DIO62_WPORT PIOB
#define DIO63_PIN 18
#define DIO63_WPORT PIOB
#define DIO64_PIN 19
#define DIO64_WPORT PIOB
#define DIO65_PIN 20
#define DIO65_WPORT PIOB
#define DIO66_PIN 15
#define DIO66_WPORT PIOB
#define DIO67_PIN 16
#define DIO67_WPORT PIOB
#define DIO68_PIN 1
#define DIO68_WPORT PIOA
#define DIO69_PIN 0
#define DIO69_WPORT PIOA
#define DIO70_PIN 17
#define DIO70_WPORT PIOA
#define DIO71_PIN 18
#define DIO71_WPORT PIOA
#define DIO72_PIN 30
#define DIO72_WPORT PIOC
#define DIO73_PIN 21
#define DIO73_WPORT PIOA
#define DIO74_PIN 25
#define DIO74_WPORT PIOA
#define DIO75_PIN 26
#define DIO75_WPORT PIOA
#define DIO76_PIN 27
#define DIO76_WPORT PIOA
#define DIO77_PIN 28
#define DIO77_WPORT PIOA
#define DIO78_PIN 23
#define DIO78_WPORT PIOB
#define DIO79_PIN 17
#define DIO79_WPORT PIOA
#define DIO80_PIN 12
#define DIO80_WPORT PIOB
#define DIO81_PIN 8
#define DIO81_WPORT PIOA
#define DIO82_PIN 11
#define DIO82_WPORT PIOA
#define DIO83_PIN 13
#define DIO83_WPORT PIOA
#define DIO84_PIN 4
#define DIO84_WPORT PIOD
#define DIO85_PIN 11
#define DIO85_WPORT PIOB
#define DIO86_PIN 21
#define DIO86_WPORT PIOB
#define DIO87_PIN 29
#define DIO87_WPORT PIOA
#define DIO88_PIN 15
#define DIO88_WPORT PIOB
#define DIO89_PIN 14
#define DIO89_WPORT PIOB
#define DIO90_PIN 1
#define DIO90_WPORT PIOA
#define DIO91_PIN 15
#define DIO91_WPORT PIOB
#define DIO92_PIN 5
#define DIO92_WPORT PIOA
#define DIO93_PIN 12
#define DIO93_WPORT PIOB
#define DIO94_PIN 22
#define DIO94_WPORT PIOB
#define DIO95_PIN 23
#define DIO95_WPORT PIOB
#define DIO96_PIN 24
#define DIO96_WPORT PIOB
#define DIO97_PIN 20
#define DIO97_WPORT PIOC
#define DIO98_PIN 27
#define DIO98_WPORT PIOC
#define DIO99_PIN 10
#define DIO99_WPORT PIOC
#define DIO100_PIN 11
#define DIO100_WPORT PIOC
#endif // _FASTIO_DUE_H

View File

@ -0,0 +1,57 @@
#include "../persistent_store_api.h"
#include "../../../types.h"
#include "../../../language.h"
#include "../../../serial.h"
#include "../../../utility.h"
#ifdef ARDUINO_ARCH_SAM
#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

View File

@ -0,0 +1,91 @@
/*
Copyright (c) 2013 Arduino LLC. 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 32 bit timer on the current board
* timer16_Sequence_t enumerates the sequence that the timers should be allocated
* _Nbr_16timers indicates how many timers are available.
*/
/**
* SAM Only definitions
* --------------------
*/
// For SAM3X:
//!#define _useTimer1
//!#define _useTimer2
#define _useTimer3
//!#define _useTimer4
#define _useTimer5
#define TRIM_DURATION 2 // compensation ticks to trim adjust for digitalWrite delays
#define PRESCALER 32 // timer prescaler
/*
TC0, chan 0 => TC0_Handler
TC0, chan 1 => TC1_Handler
TC0, chan 2 => TC2_Handler
TC1, chan 0 => TC3_Handler
TC1, chan 1 => TC4_Handler
TC1, chan 2 => TC5_Handler
TC2, chan 0 => TC6_Handler
TC2, chan 1 => TC7_Handler
TC2, chan 2 => TC8_Handler
*/
#ifdef _useTimer1
#define TC_FOR_TIMER1 TC1
#define CHANNEL_FOR_TIMER1 0
#define ID_TC_FOR_TIMER1 ID_TC3
#define IRQn_FOR_TIMER1 TC3_IRQn
#define HANDLER_FOR_TIMER1 TC3_Handler
#endif
#ifdef _useTimer2
#define TC_FOR_TIMER2 TC1
#define CHANNEL_FOR_TIMER2 1
#define ID_TC_FOR_TIMER2 ID_TC4
#define IRQn_FOR_TIMER2 TC4_IRQn
#define HANDLER_FOR_TIMER2 TC4_Handler
#endif
#ifdef _useTimer3
#define TC_FOR_TIMER3 TC1
#define CHANNEL_FOR_TIMER3 2
#define ID_TC_FOR_TIMER3 ID_TC5
#define IRQn_FOR_TIMER3 TC5_IRQn
#define HANDLER_FOR_TIMER3 TC5_Handler
#endif
#ifdef _useTimer4
#define TC_FOR_TIMER4 TC0
#define CHANNEL_FOR_TIMER4 2
#define ID_TC_FOR_TIMER4 ID_TC2
#define IRQn_FOR_TIMER4 TC2_IRQn
#define HANDLER_FOR_TIMER4 TC2_Handler
#endif
#ifdef _useTimer5
#define TC_FOR_TIMER5 TC0
#define CHANNEL_FOR_TIMER5 0
#define ID_TC_FOR_TIMER5 ID_TC0
#define IRQn_FOR_TIMER5 TC0_IRQn
#define HANDLER_FOR_TIMER5 TC0_Handler
#endif
//typedef enum { _timer1, _timer2, _timer3, _timer4, _timer5, _Nbr_16timers } timer16_Sequence_t;
typedef enum { _timer3, _timer5, _Nbr_16timers } timer16_Sequence_t;

View File

@ -0,0 +1,56 @@
/**
* 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
*
* Available chip select pins for HW SPI are 4 10 52 77
*/
#if (SDSS == 4) || (SDSS == 10) || (SDSS == 52) || (SDSS == 77)
#if (SDSS == 4)
#define SPI_PIN 87
#define SPI_CHAN 1
#elif (SDSS == 10)
#define SPI_PIN 77
#define SPI_CHAN 0
#elif (SDSS == 52)
#define SPI_PIN 86
#define SPI_CHAN 2
#else
#define SPI_PIN 77
#define SPI_CHAN 0
#endif
#define SCK_PIN 76
#define MISO_PIN 74
#define MOSI_PIN 75
#else
// defaults
#define SOFTWARE_SPI
#define SCK_PIN 52
#define MISO_PIN 50
#define MOSI_PIN 51
#endif
#define SS_PIN SDSS // A.28, A.29, B.21, C.26, C.29
#endif /* SPI_PINS_H_ */

View File

@ -0,0 +1,39 @@
/**
* 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/>.
*
*/
#ifdef ARDUINO_ARCH_SAM
#include "../../../MarlinConfig.h"
#if ENABLED(USE_WATCHDOG)
#include "watchdog_Due.h"
void watchdogSetup(void) {
// do whatever. don't remove this function.
}
void watchdog_init(void) { watchdogEnable(4000); }
#endif // USE_WATCHDOG
#endif

View File

@ -0,0 +1,37 @@
/**
* 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 WATCHDOG_DUE_H
#define WATCHDOG_DUE_H
//#include "../../../Marlin.h"
// Arduino Due core now has watchdog support
// Initialize watchdog with a 4 second interrupt time
void watchdog_init();
// Reset watchdog. MUST be called at least every 4 seconds after the
// first watchdog_init or AVR will go into emergency procedures.
inline void watchdog_reset() { watchdogReset(); }
#endif /* WATCHDOG_DUE_H */