mirror of
https://github.com/DCC-EX/CommandStation-EX.git
synced 2024-12-24 13:21:23 +01:00
Merge remote-tracking branch 'origin/SAMD_Integration_PMA' into PORTX_HAL
This commit is contained in:
commit
06d1040da0
@ -71,6 +71,7 @@ void setup()
|
|||||||
SerialManager::init();
|
SerialManager::init();
|
||||||
|
|
||||||
DIAG(F("License GPLv3 fsf.org (c) dcc-ex.com"));
|
DIAG(F("License GPLv3 fsf.org (c) dcc-ex.com"));
|
||||||
|
DIAG(F("Platform: %s"), F(ARDUINO_TYPE)); // PMA - temporary
|
||||||
|
|
||||||
CONDITIONAL_LCD_START {
|
CONDITIONAL_LCD_START {
|
||||||
// This block is still executed for DIAGS if LCD not in use
|
// This block is still executed for DIAGS if LCD not in use
|
||||||
@ -115,7 +116,6 @@ void setup()
|
|||||||
LCN_SERIAL.begin(115200);
|
LCN_SERIAL.begin(115200);
|
||||||
LCN::init(LCN_SERIAL);
|
LCN::init(LCN_SERIAL);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
LCD(3, F("Ready"));
|
LCD(3, F("Ready"));
|
||||||
CommandDistributor::broadcastPower();
|
CommandDistributor::broadcastPower();
|
||||||
}
|
}
|
||||||
|
5
DCC.cpp
5
DCC.cpp
@ -62,8 +62,11 @@ byte DCC::globalSpeedsteps=128;
|
|||||||
|
|
||||||
void DCC::begin(const FSH * motorShieldName) {
|
void DCC::begin(const FSH * motorShieldName) {
|
||||||
shieldName=(FSH *)motorShieldName;
|
shieldName=(FSH *)motorShieldName;
|
||||||
|
#if defined(ARDUINO_ARCH_SAMD)
|
||||||
|
StringFormatter::send(SerialUSB,F("<iDCC-EX V-%S / %S / %S G-%S>\n"), F(VERSION), F(ARDUINO_TYPE), shieldName, F(GITHUB_SHA));
|
||||||
|
#else
|
||||||
StringFormatter::send(Serial,F("<iDCC-EX V-%S / %S / %S G-%S>\n"), F(VERSION), F(ARDUINO_TYPE), shieldName, F(GITHUB_SHA));
|
StringFormatter::send(Serial,F("<iDCC-EX V-%S / %S / %S G-%S>\n"), F(VERSION), F(ARDUINO_TYPE), shieldName, F(GITHUB_SHA));
|
||||||
|
#endif
|
||||||
#ifndef DISABLE_EEPROM
|
#ifndef DISABLE_EEPROM
|
||||||
// Load stuff from EEprom
|
// Load stuff from EEprom
|
||||||
(void)EEPROM; // tell compiler not to warn this is unused
|
(void)EEPROM; // tell compiler not to warn this is unused
|
||||||
|
@ -905,7 +905,9 @@ bool DCCEXParser::parseD(Print *stream, int16_t params, int16_t p[])
|
|||||||
wdt_enable( WDTO_15MS); // set Arduino watchdog timer for 15ms
|
wdt_enable( WDTO_15MS); // set Arduino watchdog timer for 15ms
|
||||||
delay(50); // wait for the prescaller time to expire
|
delay(50); // wait for the prescaller time to expire
|
||||||
#else
|
#else
|
||||||
|
#ifdef ARDUINO_ARCH_ESP
|
||||||
ESP.restart();
|
ESP.restart();
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
break; // and <X> if we didnt restart
|
break; // and <X> if we didnt restart
|
||||||
}
|
}
|
||||||
|
@ -75,7 +75,7 @@ extern char *__malloc_heap_start;
|
|||||||
|
|
||||||
// ISR called by timer interrupt every 58uS
|
// ISR called by timer interrupt every 58uS
|
||||||
ISR(TCB0_INT_vect){
|
ISR(TCB0_INT_vect){
|
||||||
TCB0.INTFLAGS = TCB_CAPT_bm;
|
TCB0.INTFLAGS = TCB_CAPT_bm; // Clear interrupt request flag
|
||||||
interruptHandler();
|
interruptHandler();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
167
DCCTimerSAMD.cpp
Normal file
167
DCCTimerSAMD.cpp
Normal file
@ -0,0 +1,167 @@
|
|||||||
|
/*
|
||||||
|
* © 2021 Mike S
|
||||||
|
* © 2021 Harald Barth
|
||||||
|
* © 2021 Fred Decker
|
||||||
|
* © 2021 Chris Harlow
|
||||||
|
* © 2021 David Cutting
|
||||||
|
* © 2022 Paul M. Antoine
|
||||||
|
* All rights reserved.
|
||||||
|
*
|
||||||
|
* This file is part of Asbelos DCC API
|
||||||
|
*
|
||||||
|
* This 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.
|
||||||
|
*
|
||||||
|
* It 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 CommandStation. If not, see <https://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
// ATTENTION: this file only compiles on a TEENSY
|
||||||
|
// Please refer to DCCTimer.h for general comments about how this class works
|
||||||
|
// This is to avoid repetition and duplication.
|
||||||
|
#ifdef ARDUINO_ARCH_SAMD
|
||||||
|
|
||||||
|
#include "FSH.h" //PMA temp debug
|
||||||
|
#include "DIAG.h" //PMA temp debug
|
||||||
|
#include "DCCTimer.h"
|
||||||
|
|
||||||
|
INTERRUPT_CALLBACK interruptHandler=0;
|
||||||
|
|
||||||
|
void DCCTimer::begin(INTERRUPT_CALLBACK callback) {
|
||||||
|
interruptHandler=callback;
|
||||||
|
noInterrupts();
|
||||||
|
|
||||||
|
// PMA - Set up ADC to do faster reads... default for Arduino Zero platform configs is 436uS,
|
||||||
|
// and we need sub-100uS. This code sets it to a read speed of around 21uS, and enables 12-bit
|
||||||
|
ADC->CTRLA.bit.ENABLE = 0; // disable ADC
|
||||||
|
while( ADC->STATUS.bit.SYNCBUSY == 1 ); // wait for synchronization
|
||||||
|
|
||||||
|
ADC->CTRLB.reg &= 0b1111100011111111; // mask PRESCALER bits
|
||||||
|
ADC->CTRLB.reg |= ADC_CTRLB_PRESCALER_DIV64 | // divide Clock by 64
|
||||||
|
ADC_CTRLB_RESSEL_10BIT; // Result on 10 bits default, 12 bits possible
|
||||||
|
|
||||||
|
ADC->AVGCTRL.reg = ADC_AVGCTRL_SAMPLENUM_1 | // take 1 sample at a time
|
||||||
|
ADC_AVGCTRL_ADJRES(0x00ul); // adjusting result by 0
|
||||||
|
ADC->SAMPCTRL.reg = 0x00; // sampling Time Length = 0
|
||||||
|
|
||||||
|
ADC->CTRLA.bit.ENABLE = 1; // enable ADC
|
||||||
|
while(ADC->STATUS.bit.SYNCBUSY == 1); // wait for synchronization
|
||||||
|
|
||||||
|
// PMA - actual timer setup goo
|
||||||
|
// Setup clock sources first
|
||||||
|
REG_GCLK_GENDIV = GCLK_GENDIV_DIV(1) | // Divide 48MHz by 1
|
||||||
|
GCLK_GENDIV_ID(4); // Apply to GCLK4
|
||||||
|
while (GCLK->STATUS.bit.SYNCBUSY); // Wait for synchronization
|
||||||
|
|
||||||
|
REG_GCLK_GENCTRL = GCLK_GENCTRL_GENEN | // Enable GCLK
|
||||||
|
GCLK_GENCTRL_SRC_DFLL48M | // Set the 48MHz clock source
|
||||||
|
GCLK_GENCTRL_ID(4); // Select GCLK4
|
||||||
|
while (GCLK->STATUS.bit.SYNCBUSY); // Wait for synchronization
|
||||||
|
|
||||||
|
REG_GCLK_CLKCTRL = GCLK_CLKCTRL_CLKEN | // Enable generic clock
|
||||||
|
4 << GCLK_CLKCTRL_GEN_Pos | // Apply to GCLK4
|
||||||
|
GCLK_CLKCTRL_ID_TCC0_TCC1; // Feed GCLK to TCC0/1
|
||||||
|
while (GCLK->STATUS.bit.SYNCBUSY);
|
||||||
|
|
||||||
|
// PMA - assume we're using TCC0... as we're bit-bashing the DCC waveform output pins anyway
|
||||||
|
// for "normal accuracy" DCC waveform generation. For high accuracy we're going to need
|
||||||
|
// to a good deal more. The TCC waveform output pins are mux'd on the SAMD, and OP pins
|
||||||
|
// for each TCC are only available on certain pins
|
||||||
|
TCC0->WAVE.reg = TCC_WAVE_WAVEGEN_NPWM; // Select NPWM as waveform
|
||||||
|
while (TCC0->SYNCBUSY.bit.WAVE); // Wait for sync
|
||||||
|
|
||||||
|
// PMA - set the frequency
|
||||||
|
TCC0->CTRLA.reg |= TCC_CTRLA_PRESCALER(TCC_CTRLA_PRESCALER_DIV1_Val);
|
||||||
|
TCC0->PER.reg = CLOCK_CYCLES * 2;
|
||||||
|
while (TCC0->SYNCBUSY.bit.PER);
|
||||||
|
|
||||||
|
// PMA - start it
|
||||||
|
TCC0->CTRLA.bit.ENABLE = 1;
|
||||||
|
while (TCC0->SYNCBUSY.bit.ENABLE);
|
||||||
|
|
||||||
|
// PMA - set interrupt condition, priority and enable
|
||||||
|
TCC0->INTENSET.reg = TCC_INTENSET_OVF; // Only interrupt on overflow
|
||||||
|
NVIC_SetPriority((IRQn_Type)TCC0_IRQn, 0); // Make this highest priority
|
||||||
|
NVIC_EnableIRQ((IRQn_Type)TCC0_IRQn); // Enable the interrupt
|
||||||
|
interrupts();
|
||||||
|
}
|
||||||
|
|
||||||
|
// PMA - Timer IRQ handlers replace the dummy handlers (cortex_handlers)
|
||||||
|
// copied from rf24 branch
|
||||||
|
// TODO: test
|
||||||
|
void TCC0_Handler() {
|
||||||
|
if(TCC0->INTFLAG.bit.OVF) {
|
||||||
|
TCC0->INTFLAG.bit.OVF = 1; // writing a 1 clears the flag
|
||||||
|
interruptHandler();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void TCC1_Handler() {
|
||||||
|
if(TCC1->INTFLAG.bit.OVF) {
|
||||||
|
TCC1->INTFLAG.bit.OVF = 1; // writing a 1 clears the flag
|
||||||
|
interruptHandler();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void TCC2_Handler() {
|
||||||
|
if(TCC2->INTFLAG.bit.OVF) {
|
||||||
|
TCC2->INTFLAG.bit.OVF = 1; // writing a 1 clears the flag
|
||||||
|
interruptHandler();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
bool DCCTimer::isPWMPin(byte pin) {
|
||||||
|
//TODO: SAMD whilst this call to digitalPinHasPWM will reveal which pins can do PWM,
|
||||||
|
// there's no support yet for High Accuracy, so for now return false
|
||||||
|
// return digitalPinHasPWM(pin);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
void DCCTimer::setPWM(byte pin, bool high) {
|
||||||
|
// TODO: what are the relevant pins?
|
||||||
|
(void) pin;
|
||||||
|
(void) high;
|
||||||
|
}
|
||||||
|
|
||||||
|
void DCCTimer::getSimulatedMacAddress(byte mac[6]) {
|
||||||
|
volatile uint32_t *serno1 = (volatile uint32_t *)0x0080A00C;
|
||||||
|
volatile uint32_t *serno2 = (volatile uint32_t *)0x0080A040;
|
||||||
|
// volatile uint32_t *serno3 = (volatile uint32_t *)0x0080A044;
|
||||||
|
// volatile uint32_t *serno4 = (volatile uint32_t *)0x0080A048;
|
||||||
|
|
||||||
|
volatile uint32_t m1 = *serno1;
|
||||||
|
volatile uint32_t m2 = *serno2;
|
||||||
|
mac[0] = m1 >> 8;
|
||||||
|
mac[1] = m1 >> 0;
|
||||||
|
mac[2] = m2 >> 24;
|
||||||
|
mac[3] = m2 >> 16;
|
||||||
|
mac[4] = m2 >> 8;
|
||||||
|
mac[5] = m2 >> 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
volatile int DCCTimer::minimum_free_memory=__INT_MAX__;
|
||||||
|
|
||||||
|
// Return low memory value...
|
||||||
|
int DCCTimer::getMinimumFreeMemory() {
|
||||||
|
noInterrupts(); // Disable interrupts to get volatile value
|
||||||
|
int retval = freeMemory();
|
||||||
|
interrupts();
|
||||||
|
return retval;
|
||||||
|
}
|
||||||
|
|
||||||
|
extern "C" char* sbrk(int incr);
|
||||||
|
|
||||||
|
int DCCTimer::freeMemory() {
|
||||||
|
char top;
|
||||||
|
return (int)(&top - reinterpret_cast<char *>(sbrk(0)));
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
@ -31,12 +31,12 @@
|
|||||||
#include "Sensors.h"
|
#include "Sensors.h"
|
||||||
#include "Turnouts.h"
|
#include "Turnouts.h"
|
||||||
|
|
||||||
#if defined(ARDUINO_ARCH_SAMD)
|
#if defined(ARDUINO_ARCH_SAMC)
|
||||||
ExternalEEPROM EEPROM;
|
ExternalEEPROM EEPROM;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
void EEStore::init() {
|
void EEStore::init() {
|
||||||
#if defined(ARDUINO_ARCH_SAMD)
|
#if defined(ARDUINO_ARCH_SAMC)
|
||||||
EEPROM.begin(0x50); // Address for Microchip 24-series EEPROM with all three
|
EEPROM.begin(0x50); // Address for Microchip 24-series EEPROM with all three
|
||||||
// A pins grounded (0b1010000 = 0x50)
|
// A pins grounded (0b1010000 = 0x50)
|
||||||
#endif
|
#endif
|
||||||
|
@ -111,10 +111,10 @@
|
|||||||
*/
|
*/
|
||||||
|
|
||||||
// Uncomment following line to enable Wire library instead of native I2C drivers
|
// Uncomment following line to enable Wire library instead of native I2C drivers
|
||||||
//#define I2C_USE_WIRE
|
#define I2C_USE_WIRE
|
||||||
|
|
||||||
// Uncomment following line to disable the use of interrupts by the native I2C drivers.
|
// Uncomment following line to disable the use of interrupts by the native I2C drivers.
|
||||||
//#define I2C_NO_INTERRUPTS
|
#define I2C_NO_INTERRUPTS
|
||||||
|
|
||||||
// Default to use interrupts within the native I2C drivers.
|
// Default to use interrupts within the native I2C drivers.
|
||||||
#ifndef I2C_NO_INTERRUPTS
|
#ifndef I2C_NO_INTERRUPTS
|
||||||
|
188
I2CManager_SAMD.h
Normal file
188
I2CManager_SAMD.h
Normal file
@ -0,0 +1,188 @@
|
|||||||
|
/*
|
||||||
|
* © 2021, Neil McKechnie. All rights reserved.
|
||||||
|
*
|
||||||
|
* This file is part of CommandStation-EX
|
||||||
|
*
|
||||||
|
* This 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.
|
||||||
|
*
|
||||||
|
* It 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 CommandStation. If not, see <https://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef I2CMANAGER_SAMD_H
|
||||||
|
#define I2CMANAGER_SAMD_H
|
||||||
|
|
||||||
|
#include <Arduino.h>
|
||||||
|
#include "I2CManager.h"
|
||||||
|
|
||||||
|
//#include <avr/io.h>
|
||||||
|
//#include <avr/interrupt.h>
|
||||||
|
|
||||||
|
#if defined(I2C_USE_INTERRUPTS) && defined(ARDUINO_SAMD_ZERO)
|
||||||
|
// PMA - IRQ handler, based on SERCOM3 being used for I2C, as per Arduino Zero & Sparkfun SAMD21
|
||||||
|
// TODO: test
|
||||||
|
void SERCOM3_Handler() {
|
||||||
|
I2CManagerClass::handleInterrupt();
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/***************************************************************************
|
||||||
|
* Set I2C clock speed register.
|
||||||
|
***************************************************************************/
|
||||||
|
void I2CManagerClass::I2C_setClock(unsigned long i2cClockSpeed) {
|
||||||
|
unsigned long temp = ((F_CPU / i2cClockSpeed) - 16) / 2;
|
||||||
|
for (uint8_t preScaler = 0; preScaler<=3; preScaler++) {
|
||||||
|
if (temp <= 255) {
|
||||||
|
TWBR = temp;
|
||||||
|
TWSR = (TWSR & 0xfc) | preScaler;
|
||||||
|
return;
|
||||||
|
} else
|
||||||
|
temp /= 4;
|
||||||
|
}
|
||||||
|
// Set slowest speed ~= 500 bits/sec
|
||||||
|
TWBR = 255;
|
||||||
|
TWSR |= 0x03;
|
||||||
|
}
|
||||||
|
|
||||||
|
/***************************************************************************
|
||||||
|
* Initialise I2C registers.
|
||||||
|
***************************************************************************/
|
||||||
|
void I2CManagerClass::I2C_init()
|
||||||
|
{
|
||||||
|
// PMA - broadly we do the following
|
||||||
|
initialise the clock
|
||||||
|
initialise the NVIC
|
||||||
|
software reset the I2C for the sercom
|
||||||
|
set master mode
|
||||||
|
do we need smart mode and quick command??
|
||||||
|
configure interrupt handlers
|
||||||
|
enable interrupts
|
||||||
|
set default baud rate
|
||||||
|
set SDA/SCL pins as outputs and enable pullups
|
||||||
|
}
|
||||||
|
|
||||||
|
/***************************************************************************
|
||||||
|
* Initiate a start bit for transmission.
|
||||||
|
***************************************************************************/
|
||||||
|
void I2CManagerClass::I2C_sendStart() {
|
||||||
|
bytesToSend = currentRequest->writeLen;
|
||||||
|
bytesToReceive = currentRequest->readLen;
|
||||||
|
// We may have initiated a stop bit before this without waiting for it.
|
||||||
|
// Wait for stop bit to be sent before sending start.
|
||||||
|
while (TWCR & (1<<TWSTO)) {}
|
||||||
|
TWCR = (1<<TWEN)|ENABLE_TWI_INTERRUPT|(1<<TWINT)|(1<<TWEA)|(1<<TWSTA); // Send Start
|
||||||
|
}
|
||||||
|
|
||||||
|
/***************************************************************************
|
||||||
|
* Initiate a stop bit for transmission (does not interrupt)
|
||||||
|
***************************************************************************/
|
||||||
|
void I2CManagerClass::I2C_sendStop() {
|
||||||
|
TWDR = 0xff; // Default condition = SDA released
|
||||||
|
TWCR = (1<<TWEN)|(1<<TWINT)|(1<<TWEA)|(1<<TWSTO); // Send Stop
|
||||||
|
}
|
||||||
|
|
||||||
|
/***************************************************************************
|
||||||
|
* Close I2C down
|
||||||
|
***************************************************************************/
|
||||||
|
void I2CManagerClass::I2C_close() {
|
||||||
|
// disable TWI
|
||||||
|
I2C_sendStop();
|
||||||
|
while (TWCR & (1<<TWSTO)) {}
|
||||||
|
TWCR = (1<<TWINT); // clear any interrupt and stop twi.
|
||||||
|
}
|
||||||
|
|
||||||
|
/***************************************************************************
|
||||||
|
* Main state machine for I2C, called from interrupt handler or,
|
||||||
|
* if I2C_USE_INTERRUPTS isn't defined, from the I2CManagerClass::loop() function
|
||||||
|
* (and therefore, indirectly, from I2CRB::wait() and I2CRB::isBusy()).
|
||||||
|
***************************************************************************/
|
||||||
|
void I2CManagerClass::I2C_handleInterrupt() {
|
||||||
|
if (!(TWCR & (1<<TWINT))) return; // Nothing to do.
|
||||||
|
|
||||||
|
uint8_t twsr = TWSR & 0xF8;
|
||||||
|
|
||||||
|
// Cases are ordered so that the most frequently used ones are tested first.
|
||||||
|
switch (twsr) {
|
||||||
|
case TWI_MTX_DATA_ACK: // Data byte has been transmitted and ACK received
|
||||||
|
case TWI_MTX_ADR_ACK: // SLA+W has been transmitted and ACK received
|
||||||
|
if (bytesToSend) { // Send first.
|
||||||
|
if (operation == OPERATION_SEND_P)
|
||||||
|
TWDR = GETFLASH(currentRequest->writeBuffer + (txCount++));
|
||||||
|
else
|
||||||
|
TWDR = currentRequest->writeBuffer[txCount++];
|
||||||
|
bytesToSend--;
|
||||||
|
TWCR = (1<<TWEN)|ENABLE_TWI_INTERRUPT|(1<<TWINT)|(1<<TWEA);
|
||||||
|
} else if (bytesToReceive) { // All sent, anything to receive?
|
||||||
|
while (TWCR & (1<<TWSTO)) {} // Wait for stop to be sent
|
||||||
|
TWCR = (1<<TWEN)|ENABLE_TWI_INTERRUPT|(1<<TWINT)|(1<<TWEA)|(1<<TWSTA); // Send Start
|
||||||
|
} else { // Nothing left to send or receive
|
||||||
|
TWDR = 0xff; // Default condition = SDA released
|
||||||
|
TWCR = (1<<TWEN)|(1<<TWINT)|(1<<TWEA)|(1<<TWSTO); // Send Stop
|
||||||
|
state = I2C_STATUS_OK;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case TWI_MRX_DATA_ACK: // Data byte has been received and ACK transmitted
|
||||||
|
if (bytesToReceive > 0) {
|
||||||
|
currentRequest->readBuffer[rxCount++] = TWDR;
|
||||||
|
bytesToReceive--;
|
||||||
|
}
|
||||||
|
/* fallthrough */
|
||||||
|
case TWI_MRX_ADR_ACK: // SLA+R has been sent and ACK received
|
||||||
|
if (bytesToReceive <= 1) {
|
||||||
|
TWCR = (1<<TWEN)|ENABLE_TWI_INTERRUPT|(1<<TWINT); // Send NACK after next reception
|
||||||
|
} else {
|
||||||
|
// send ack
|
||||||
|
TWCR = (1<<TWEN)|ENABLE_TWI_INTERRUPT|(1<<TWINT)|(1<<TWEA);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case TWI_MRX_DATA_NACK: // Data byte has been received and NACK transmitted
|
||||||
|
if (bytesToReceive > 0) {
|
||||||
|
currentRequest->readBuffer[rxCount++] = TWDR;
|
||||||
|
bytesToReceive--;
|
||||||
|
}
|
||||||
|
TWCR = (1<<TWEN)|(1<<TWINT)|(1<<TWEA)|(1<<TWSTO); // Send Stop
|
||||||
|
state = I2C_STATUS_OK;
|
||||||
|
break;
|
||||||
|
case TWI_START: // START has been transmitted
|
||||||
|
case TWI_REP_START: // Repeated START has been transmitted
|
||||||
|
// Set up address and R/W
|
||||||
|
if (operation == OPERATION_READ || (operation==OPERATION_REQUEST && !bytesToSend))
|
||||||
|
TWDR = (currentRequest->i2cAddress << 1) | 1; // SLA+R
|
||||||
|
else
|
||||||
|
TWDR = (currentRequest->i2cAddress << 1) | 0; // SLA+W
|
||||||
|
TWCR = (1<<TWEN)|ENABLE_TWI_INTERRUPT|(1<<TWINT)|(1<<TWEA);
|
||||||
|
break;
|
||||||
|
case TWI_MTX_ADR_NACK: // SLA+W has been transmitted and NACK received
|
||||||
|
case TWI_MRX_ADR_NACK: // SLA+R has been transmitted and NACK received
|
||||||
|
case TWI_MTX_DATA_NACK: // Data byte has been transmitted and NACK received
|
||||||
|
TWDR = 0xff; // Default condition = SDA released
|
||||||
|
TWCR = (1<<TWEN)|(1<<TWINT)|(1<<TWEA)|(1<<TWSTO); // Send Stop
|
||||||
|
state = I2C_STATUS_NEGATIVE_ACKNOWLEDGE;
|
||||||
|
break;
|
||||||
|
case TWI_ARB_LOST: // Arbitration lost
|
||||||
|
// Restart transaction from start.
|
||||||
|
I2C_sendStart();
|
||||||
|
break;
|
||||||
|
case TWI_BUS_ERROR: // Bus error due to an illegal START or STOP condition
|
||||||
|
default:
|
||||||
|
TWDR = 0xff; // Default condition = SDA released
|
||||||
|
TWCR = (1<<TWEN)|(1<<TWINT)|(1<<TWEA)|(1<<TWSTO); // Send Stop
|
||||||
|
state = I2C_STATUS_TRANSMIT_ERROR;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
#if defined(I2C_USE_INTERRUPTS)
|
||||||
|
ISR(TWI_vect) {
|
||||||
|
I2CManagerClass::handleInterrupt();
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif /* I2CMANAGER_AVR_H */
|
@ -231,7 +231,11 @@ unsigned int MotorDriver::mA2raw( unsigned int mA) {
|
|||||||
void MotorDriver::getFastPin(const FSH* type,int pin, bool input, FASTPIN & result) {
|
void MotorDriver::getFastPin(const FSH* type,int pin, bool input, FASTPIN & result) {
|
||||||
// DIAG(F("MotorDriver %S Pin=%d,"),type,pin);
|
// DIAG(F("MotorDriver %S Pin=%d,"),type,pin);
|
||||||
(void) type; // avoid compiler warning if diag not used above.
|
(void) type; // avoid compiler warning if diag not used above.
|
||||||
|
#if defined(ARDUINO_ARCH_SAMD)
|
||||||
|
PortGroup *port = digitalPinToPort(pin);
|
||||||
|
#else
|
||||||
uint8_t port = digitalPinToPort(pin);
|
uint8_t port = digitalPinToPort(pin);
|
||||||
|
#endif
|
||||||
if (input)
|
if (input)
|
||||||
result.inout = portInputRegister(port);
|
result.inout = portInputRegister(port);
|
||||||
else
|
else
|
||||||
|
@ -62,8 +62,12 @@
|
|||||||
#define UNUSED_PIN 127 // inside int8_t
|
#define UNUSED_PIN 127 // inside int8_t
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(__IMXRT1062__) || defined(ARDUINO_ARCH_ESP8266) || defined(ARDUINO_ARCH_ESP32)
|
#if defined(__IMXRT1062__) || defined(ARDUINO_ARCH_ESP8266) || defined(ARDUINO_ARCH_ESP32) || defined(ARDUINO_ARCH_SAMD)
|
||||||
typedef uint32_t portreg_t;
|
struct FASTPIN {
|
||||||
|
volatile uint32_t *inout;
|
||||||
|
uint32_t maskHIGH;
|
||||||
|
uint32_t maskLOW;
|
||||||
|
};
|
||||||
#else
|
#else
|
||||||
typedef uint8_t portreg_t;
|
typedef uint8_t portreg_t;
|
||||||
#endif
|
#endif
|
||||||
|
@ -46,9 +46,18 @@
|
|||||||
// (HIGH == release brake)
|
// (HIGH == release brake)
|
||||||
//
|
//
|
||||||
// Arduino standard Motor Shield
|
// Arduino standard Motor Shield
|
||||||
|
#if defined(ARDUINO_ARCH_SAMD)
|
||||||
|
// PMA - Setup for SAMD21 Sparkfun DEV board
|
||||||
|
// senseFactor for 3.3v systems is 1.95 as calculated when using 10-bit A/D samples,
|
||||||
|
// and for 12-bit samples it's more like 0.488, but we probably need to tweak both these
|
||||||
|
#define STANDARD_MOTOR_SHIELD F("STANDARD_MOTOR_SHIELD"), \
|
||||||
|
new MotorDriver(3, 12, UNUSED_PIN, 9, A0, 1.95, 2000, UNUSED_PIN), \
|
||||||
|
new MotorDriver(11, 13, UNUSED_PIN, 8, A1, 1.95, 2000, UNUSED_PIN)
|
||||||
|
#else
|
||||||
#define STANDARD_MOTOR_SHIELD F("STANDARD_MOTOR_SHIELD"), \
|
#define STANDARD_MOTOR_SHIELD F("STANDARD_MOTOR_SHIELD"), \
|
||||||
new MotorDriver(3, 12, UNUSED_PIN, 9, A0, 2.99, 2000, UNUSED_PIN), \
|
new MotorDriver(3, 12, UNUSED_PIN, 9, A0, 2.99, 2000, UNUSED_PIN), \
|
||||||
new MotorDriver(11, 13, UNUSED_PIN, 8, A1, 2.99, 2000, UNUSED_PIN)
|
new MotorDriver(11, 13, UNUSED_PIN, 8, A1, 2.99, 2000, UNUSED_PIN)
|
||||||
|
#endif
|
||||||
|
|
||||||
// Pololu Motor Shield
|
// Pololu Motor Shield
|
||||||
#define POLOLU_MOTOR_SHIELD F("POLOLU_MOTOR_SHIELD"), \
|
#define POLOLU_MOTOR_SHIELD F("POLOLU_MOTOR_SHIELD"), \
|
||||||
|
@ -33,9 +33,15 @@ SerialManager::SerialManager(Stream * myserial) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
void SerialManager::init() {
|
void SerialManager::init() {
|
||||||
while (!Serial && millis() < 5000); // wait max 5s for Serial to start
|
// while (!Serial && millis() < 5000); // wait max 5s for Serial to start
|
||||||
|
#if defined(ARDUINO_ARCH_SAMD)
|
||||||
|
SerialUSB.begin(115200);
|
||||||
|
while (!SerialUSB); // PMA - temporary for debuggering purpoises
|
||||||
|
new SerialManager(&SerialUSB);
|
||||||
|
#else
|
||||||
Serial.begin(115200);
|
Serial.begin(115200);
|
||||||
new SerialManager(&Serial);
|
new SerialManager(&Serial);
|
||||||
|
#endif
|
||||||
#ifdef SERIAL3_COMMANDS
|
#ifdef SERIAL3_COMMANDS
|
||||||
Serial3.begin(115200);
|
Serial3.begin(115200);
|
||||||
new SerialManager(&Serial3);
|
new SerialManager(&Serial3);
|
||||||
|
@ -70,6 +70,9 @@
|
|||||||
#elif defined(ARDUINO_ARCH_ESP32)
|
#elif defined(ARDUINO_ARCH_ESP32)
|
||||||
#define ARDUINO_TYPE "ESP32"
|
#define ARDUINO_TYPE "ESP32"
|
||||||
#undef HAS_AVR_WDT
|
#undef HAS_AVR_WDT
|
||||||
|
#elif defined(ARDUINO_ARCH_SAMD)
|
||||||
|
#define ARDUINO_TYPE "SAMD21"
|
||||||
|
#undef HAS_AVR_WDT
|
||||||
#else
|
#else
|
||||||
#define CPU_TYPE_ERROR
|
#define CPU_TYPE_ERROR
|
||||||
#endif
|
#endif
|
||||||
|
@ -10,11 +10,7 @@
|
|||||||
|
|
||||||
[platformio]
|
[platformio]
|
||||||
default_envs =
|
default_envs =
|
||||||
mega2560
|
samd21
|
||||||
uno
|
|
||||||
mega328
|
|
||||||
unowifiR2
|
|
||||||
nano
|
|
||||||
src_dir = .
|
src_dir = .
|
||||||
include_dir = .
|
include_dir = .
|
||||||
|
|
||||||
@ -25,12 +21,13 @@ build_flags = -Wall -Wextra
|
|||||||
platform = atmelsam
|
platform = atmelsam
|
||||||
board = sparkfun_samd21_dev_usb
|
board = sparkfun_samd21_dev_usb
|
||||||
framework = arduino
|
framework = arduino
|
||||||
upload_protocol = atmel-ice
|
upload_protocol = sam-ba
|
||||||
lib_deps =
|
lib_deps =
|
||||||
${env.lib_deps}
|
${env.lib_deps}
|
||||||
SparkFun External EEPROM Arduino Library
|
SparkFun External EEPROM Arduino Library
|
||||||
monitor_speed = 115200
|
monitor_speed = 115200
|
||||||
monitor_flags = --echo
|
monitor_flags = --echo
|
||||||
|
build_flags = -std=c++17
|
||||||
|
|
||||||
[env:mega2560-debug]
|
[env:mega2560-debug]
|
||||||
platform = atmelavr
|
platform = atmelavr
|
||||||
@ -131,7 +128,6 @@ platform = atmelavr
|
|||||||
board = nanoatmega328new
|
board = nanoatmega328new
|
||||||
board_upload.maximum_size = 32256
|
board_upload.maximum_size = 32256
|
||||||
framework = arduino
|
framework = arduino
|
||||||
lib_deps =
|
lib_deps = ${env.lib_deps}
|
||||||
${env.lib_deps}
|
|
||||||
monitor_speed = 115200
|
monitor_speed = 115200
|
||||||
monitor_flags = --echo
|
monitor_flags = --echo
|
||||||
|
Loading…
Reference in New Issue
Block a user