mirror of
https://github.com/DCC-EX/CommandStation-EX.git
synced 2025-02-19 23:46:02 +01:00
Merge branch 'devel' into PORTX_HAL_cursense2_HIGHMEM
This commit is contained in:
commit
ebcde5335c
41
DCC.cpp
41
DCC.cpp
@ -595,30 +595,15 @@ void DCC::loop() {
|
|||||||
void DCC::issueReminders() {
|
void DCC::issueReminders() {
|
||||||
// if the main track transmitter still has a pending packet, skip this time around.
|
// if the main track transmitter still has a pending packet, skip this time around.
|
||||||
if ( DCCWaveform::mainTrack.getPacketPending()) return;
|
if ( DCCWaveform::mainTrack.getPacketPending()) return;
|
||||||
|
// Move to next loco slot. If occupied, send a reminder.
|
||||||
// This loop searches for a loco in the speed table starting at nextLoco and cycling back around
|
int reg = lastLocoReminder+1;
|
||||||
/*
|
if (reg > highestUsedReg) reg = 0; // Go to start of table
|
||||||
for (int reg=0;reg<MAX_LOCOS;reg++) {
|
if (speedTable[reg].loco > 0) {
|
||||||
int slot=reg+nextLoco;
|
// have found loco to remind
|
||||||
if (slot>=MAX_LOCOS) slot-=MAX_LOCOS;
|
if (issueReminder(reg))
|
||||||
if (speedTable[slot].loco > 0) {
|
lastLocoReminder = reg;
|
||||||
// have found the next loco to remind
|
} else
|
||||||
// issueReminder will return true if this loco is completed (ie speed and functions)
|
lastLocoReminder = reg;
|
||||||
if (issueReminder(slot)) nextLoco=slot+1;
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
*/
|
|
||||||
for (int reg=nextLoco;reg<MAX_LOCOS+nextLoco;reg++) {
|
|
||||||
int slot=reg%MAX_LOCOS;
|
|
||||||
if (speedTable[slot].loco > 0) {
|
|
||||||
// have found the next loco to remind
|
|
||||||
// issueReminder will return true if this loco is completed (ie speed and functions)
|
|
||||||
if (issueReminder(slot))
|
|
||||||
nextLoco=(slot+1)%MAX_LOCOS;
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
bool DCC::issueReminder(int reg) {
|
bool DCC::issueReminder(int reg) {
|
||||||
@ -698,6 +683,7 @@ int DCC::lookupSpeedTable(int locoId, bool autoCreate) {
|
|||||||
speedTable[reg].groupFlags=0;
|
speedTable[reg].groupFlags=0;
|
||||||
speedTable[reg].functions=0;
|
speedTable[reg].functions=0;
|
||||||
}
|
}
|
||||||
|
if (reg > highestUsedReg) highestUsedReg = reg;
|
||||||
return reg;
|
return reg;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -705,7 +691,7 @@ void DCC::updateLocoReminder(int loco, byte speedCode) {
|
|||||||
|
|
||||||
if (loco==0) {
|
if (loco==0) {
|
||||||
// broadcast stop/estop but dont change direction
|
// broadcast stop/estop but dont change direction
|
||||||
for (int reg = 0; reg < MAX_LOCOS; reg++) {
|
for (int reg = 0; reg < highestUsedReg; reg++) {
|
||||||
if (speedTable[reg].loco==0) continue;
|
if (speedTable[reg].loco==0) continue;
|
||||||
byte newspeed=(speedTable[reg].speedCode & 0x80) | (speedCode & 0x7f);
|
byte newspeed=(speedTable[reg].speedCode & 0x80) | (speedCode & 0x7f);
|
||||||
if (speedTable[reg].speedCode != newspeed) {
|
if (speedTable[reg].speedCode != newspeed) {
|
||||||
@ -725,13 +711,14 @@ void DCC::updateLocoReminder(int loco, byte speedCode) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
DCC::LOCO DCC::speedTable[MAX_LOCOS];
|
DCC::LOCO DCC::speedTable[MAX_LOCOS];
|
||||||
int DCC::nextLoco = 0;
|
int DCC::lastLocoReminder = 0;
|
||||||
|
int DCC::highestUsedReg = 0;
|
||||||
|
|
||||||
|
|
||||||
void DCC::displayCabList(Print * stream) {
|
void DCC::displayCabList(Print * stream) {
|
||||||
|
|
||||||
int used=0;
|
int used=0;
|
||||||
for (int reg = 0; reg < MAX_LOCOS; reg++) {
|
for (int reg = 0; reg <= highestUsedReg; reg++) {
|
||||||
if (speedTable[reg].loco>0) {
|
if (speedTable[reg].loco>0) {
|
||||||
used ++;
|
used ++;
|
||||||
StringFormatter::send(stream,F("cab=%d, speed=%d, dir=%c \n"),
|
StringFormatter::send(stream,F("cab=%d, speed=%d, dir=%c \n"),
|
||||||
|
3
DCC.h
3
DCC.h
@ -108,7 +108,8 @@ private:
|
|||||||
static void updateLocoReminder(int loco, byte speedCode);
|
static void updateLocoReminder(int loco, byte speedCode);
|
||||||
static void setFunctionInternal(int cab, byte fByte, byte eByte);
|
static void setFunctionInternal(int cab, byte fByte, byte eByte);
|
||||||
static bool issueReminder(int reg);
|
static bool issueReminder(int reg);
|
||||||
static int nextLoco;
|
static int lastLocoReminder;
|
||||||
|
static int highestUsedReg;
|
||||||
static FSH *shieldName;
|
static FSH *shieldName;
|
||||||
static byte globalSpeedsteps;
|
static byte globalSpeedsteps;
|
||||||
|
|
||||||
|
@ -88,7 +88,10 @@ void DCCTimer::clearPWM() {
|
|||||||
|
|
||||||
void DCCTimer::getSimulatedMacAddress(byte mac[6]) {
|
void DCCTimer::getSimulatedMacAddress(byte mac[6]) {
|
||||||
for (byte i=0; i<6; i++) {
|
for (byte i=0; i<6; i++) {
|
||||||
mac[i]=boot_signature_byte_get(0x0E + i);
|
// take the fist 3 and last 3 of the serial.
|
||||||
|
// the first 5 of 8 are at 0x0E to 0x013
|
||||||
|
// the last 3 of 8 are at 0x15 to 0x017
|
||||||
|
mac[i]=boot_signature_byte_get(0x0E + i + (i>2? 4 : 0));
|
||||||
}
|
}
|
||||||
mac[0] &= 0xFE;
|
mac[0] &= 0xFE;
|
||||||
mac[0] |= 0x02;
|
mac[0] |= 0x02;
|
||||||
@ -126,6 +129,7 @@ void DCCTimer::reset() {
|
|||||||
#endif
|
#endif
|
||||||
uint16_t ADCee::usedpins = 0;
|
uint16_t ADCee::usedpins = 0;
|
||||||
int * ADCee::analogvals = NULL;
|
int * ADCee::analogvals = NULL;
|
||||||
|
bool ADCusesHighPort = false;
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* Register a new pin to be scanned
|
* Register a new pin to be scanned
|
||||||
@ -136,6 +140,8 @@ int ADCee::init(uint8_t pin) {
|
|||||||
uint8_t id = pin - A0;
|
uint8_t id = pin - A0;
|
||||||
if (id > NUM_ADC_INPUTS)
|
if (id > NUM_ADC_INPUTS)
|
||||||
return -1023;
|
return -1023;
|
||||||
|
if (id > 7)
|
||||||
|
ADCusesHighPort = true;
|
||||||
pinMode(pin, INPUT);
|
pinMode(pin, INPUT);
|
||||||
int value = analogRead(pin);
|
int value = analogRead(pin);
|
||||||
if (analogvals == NULL)
|
if (analogvals == NULL)
|
||||||
@ -196,7 +202,15 @@ void ADCee::scan() {
|
|||||||
while (true) {
|
while (true) {
|
||||||
if (mask & usedpins) {
|
if (mask & usedpins) {
|
||||||
// start new ADC aquire on id
|
// start new ADC aquire on id
|
||||||
ADMUX=(1<<REFS0)|id; //select AVCC as reference and set MUX
|
#if defined(ADCSRB) && defined(MUX5)
|
||||||
|
if (ADCusesHighPort) { // if we ever have started to use high pins)
|
||||||
|
if (id > 7) // if we use a high ADC pin
|
||||||
|
bitSet(ADCSRB, MUX5); // set MUX5 bit
|
||||||
|
else
|
||||||
|
bitClear(ADCSRB, MUX5);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
ADMUX=(1<<REFS0)|(id & 0x07); //select AVCC as reference and set MUX
|
||||||
bitSet(ADCSRA,ADSC); // start conversion
|
bitSet(ADCSRA,ADSC); // start conversion
|
||||||
// for scope debug TrackManager::track[1]->setBrake(1);
|
// for scope debug TrackManager::track[1]->setBrake(1);
|
||||||
waiting = true;
|
waiting = true;
|
||||||
|
@ -28,13 +28,9 @@
|
|||||||
// This is to avoid repetition and duplication.
|
// This is to avoid repetition and duplication.
|
||||||
#ifdef ARDUINO_ARCH_STM32
|
#ifdef ARDUINO_ARCH_STM32
|
||||||
|
|
||||||
#include "FSH.h" //PMA temp debug
|
|
||||||
#include "DIAG.h" //PMA temp debug
|
|
||||||
#include "DCCTimer.h"
|
#include "DCCTimer.h"
|
||||||
|
|
||||||
#define STM32F411RE // PMA - ideally this ought to be derived from within the STM32 support somehow
|
#if defined(ARDUINO_NUCLEO_F411RE)
|
||||||
|
|
||||||
#if defined(STM32F411RE)
|
|
||||||
// STM32F411RE doesn't have Serial1 defined by default
|
// STM32F411RE doesn't have Serial1 defined by default
|
||||||
HardwareSerial Serial1(PB7, PA15); // Rx=PB7, Tx=PA15 -- CN7 pins 17 and 21 - F411RE
|
HardwareSerial Serial1(PB7, PA15); // Rx=PB7, Tx=PA15 -- CN7 pins 17 and 21 - F411RE
|
||||||
// Serial2 is defined to use USART2 by default, but is in fact used as the diag console
|
// Serial2 is defined to use USART2 by default, but is in fact used as the diag console
|
||||||
@ -42,9 +38,9 @@ HardwareSerial Serial1(PB7, PA15); // Rx=PB7, Tx=PA15 -- CN7 pins 17 and 21 - F
|
|||||||
// for other DCC-EX uses like WiFi, DFPlayer, etc.
|
// for other DCC-EX uses like WiFi, DFPlayer, etc.
|
||||||
// Let's define Serial6 as an additional serial port (the only other option for the F411RE)
|
// Let's define Serial6 as an additional serial port (the only other option for the F411RE)
|
||||||
HardwareSerial Serial6(PA12, PA11); // Rx=PA12, Tx=PA11 -- CN10 pins 12 and 14 - F411RE
|
HardwareSerial Serial6(PA12, PA11); // Rx=PA12, Tx=PA11 -- CN10 pins 12 and 14 - F411RE
|
||||||
#elif defined(STM32F446ZE)
|
#elif defined(ARDUINO_BLAH_F412ZG) || defined(ARDUINO_NUCLEO_F412ZG) || defined(ARDUINO_NUCLEO_F429ZI) || defined(ARDUINO_NUCLEO_F446ZE)
|
||||||
// STM32F446ZE doesn't have Serial1 defined by default
|
// Nucleo-144 boards don't have Serial1 defined by default
|
||||||
HardwareSerial Serial1(PG9, PG14); // Rx=PG9, Tx=PG14 -- D0, D1 - F446ZE
|
HardwareSerial Serial1(PG9, PG14); // Rx=PG9, Tx=PG14 -- D0, D1 - F412ZG/F446ZE
|
||||||
#else
|
#else
|
||||||
#warning Serial1 not defined
|
#warning Serial1 not defined
|
||||||
#endif
|
#endif
|
||||||
@ -94,10 +90,9 @@ void DCCTimer::clearPWM() {
|
|||||||
}
|
}
|
||||||
|
|
||||||
void DCCTimer::getSimulatedMacAddress(byte mac[6]) {
|
void DCCTimer::getSimulatedMacAddress(byte mac[6]) {
|
||||||
volatile uint32_t *serno1 = (volatile uint32_t *)0x0080A00C;
|
volatile uint32_t *serno1 = (volatile uint32_t *)0x1FFF7A10;
|
||||||
volatile uint32_t *serno2 = (volatile uint32_t *)0x0080A040;
|
volatile uint32_t *serno2 = (volatile uint32_t *)0x1FFF7A14;
|
||||||
// volatile uint32_t *serno3 = (volatile uint32_t *)0x0080A044;
|
volatile uint32_t *serno3 = (volatile uint32_t *)0x1FFF7A18;
|
||||||
// volatile uint32_t *serno4 = (volatile uint32_t *)0x0080A048;
|
|
||||||
|
|
||||||
volatile uint32_t m1 = *serno1;
|
volatile uint32_t m1 = *serno1;
|
||||||
volatile uint32_t m2 = *serno2;
|
volatile uint32_t m2 = *serno2;
|
||||||
|
@ -757,7 +757,7 @@ void RMFT2::loop2() {
|
|||||||
break;
|
break;
|
||||||
|
|
||||||
case OPCODE_IFRANDOM: // do block on random percentage
|
case OPCODE_IFRANDOM: // do block on random percentage
|
||||||
skipIf=(int16_t)(micros()%100) >= operand;
|
skipIf=(uint8_t)micros() >= operand * 255/100;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case OPCODE_IFRESERVE: // do block if we successfully RERSERVE
|
case OPCODE_IFRESERVE: // do block if we successfully RERSERVE
|
||||||
|
@ -1 +1 @@
|
|||||||
#define GITHUB_SHA "devel-202211071020Z"
|
#define GITHUB_SHA "devel-202211181919Z"
|
||||||
|
@ -1,5 +1,5 @@
|
|||||||
/*
|
/*
|
||||||
* © 2021, Neil McKechnie. All rights reserved.
|
* © 2022, Neil McKechnie. All rights reserved.
|
||||||
*
|
*
|
||||||
* This file is part of DCC++EX API
|
* This file is part of DCC++EX API
|
||||||
*
|
*
|
||||||
@ -36,24 +36,31 @@
|
|||||||
* In mySetup function within mySetup.cpp:
|
* In mySetup function within mySetup.cpp:
|
||||||
* DFPlayer::create(3500, 5, Serial1);
|
* DFPlayer::create(3500, 5, Serial1);
|
||||||
*
|
*
|
||||||
* Writing an analogue value 0-2999 to the first pin will select a numbered file from the SD card;
|
* Writing an analogue value 1-2999 to the first pin (3500) will play the numbered file from the SD card;
|
||||||
* Writing an analogue value 0-30 to the second pin will set the volume of the output;
|
* Writing an analogue value 0 to the first pin (3500) will stop the file playing;
|
||||||
* Writing a digital value to the first pin will play or stop the file;
|
* Writing an analogue value 0-30 to the second pin (3501) will set the volume;
|
||||||
|
* Writing a digital value of 1 to a pin will play the file corresponding to that pin, e.g.
|
||||||
|
the first file will be played by setting pin 3500, the second by setting pin 3501 etc.;
|
||||||
|
* Writing a digital value of 0 to any pin will stop the player;
|
||||||
* Reading a digital value from any pin will return true(1) if the player is playing, false(0) otherwise.
|
* Reading a digital value from any pin will return true(1) if the player is playing, false(0) otherwise.
|
||||||
*
|
*
|
||||||
* From EX-RAIL, the following commands may be used:
|
* From EX-RAIL, the following commands may be used:
|
||||||
* SET(3500) -- starts playing the first file on the SD card
|
* SET(3500) -- starts playing the first file (file 1) on the SD card
|
||||||
* SET(3501) -- starts playing the second file on the SD card
|
* SET(3501) -- starts playing the second file (file 2) on the SD card
|
||||||
* etc.
|
* etc.
|
||||||
* RESET(3500) -- stops all playing on the player
|
* RESET(3500) -- stops all playing on the player
|
||||||
* WAITFOR(3500) -- wait for the file currently being played by the player to complete
|
* WAITFOR(3500) -- wait for the file currently being played by the player to complete
|
||||||
* SERVO(3500,23,0) -- plays file 23 at current volume
|
* SERVO(3500,2,Instant) -- plays file 2 at current volume
|
||||||
* SERVO(3500,23,30) -- plays file 23 at volume 30 (maximum)
|
* SERVO(3501,20,Instant) -- Sets the volume to 20
|
||||||
* SERVO(3501,20,0) -- Sets the volume to 20
|
|
||||||
*
|
*
|
||||||
* NB The DFPlayer's serial lines are not 5V safe, so connecting the Arduino TX directly
|
* NB The DFPlayer's serial lines are not 5V safe, so connecting the Arduino TX directly
|
||||||
* to the DFPlayer's RX terminal will cause lots of noise over the speaker, or worse.
|
* to the DFPlayer's RX terminal will cause lots of noise over the speaker, or worse.
|
||||||
* A 1k resistor in series with the module's RX terminal will alleviate this.
|
* A 1k resistor in series with the module's RX terminal will alleviate this.
|
||||||
|
*
|
||||||
|
* Files on the SD card are numbered according to their order in the directory on the
|
||||||
|
* card (as listed by the DIR command in Windows). This may not match the order of the files
|
||||||
|
* as displayed by Windows File Manager, which sorts the file names. It is suggested that
|
||||||
|
* files be copied into an empty SDcard in the desired order, one at a time.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#ifndef IO_DFPlayer_h
|
#ifndef IO_DFPlayer_h
|
||||||
@ -68,6 +75,19 @@ private:
|
|||||||
uint8_t _inputIndex = 0;
|
uint8_t _inputIndex = 0;
|
||||||
unsigned long _commandSendTime; // Allows timeout processing
|
unsigned long _commandSendTime; // Allows timeout processing
|
||||||
|
|
||||||
|
// When two commands are sent in quick succession, the device sometimes
|
||||||
|
// fails to execute one. A delay is required between successive commands.
|
||||||
|
// This could be implemented by buffering commands and outputting them
|
||||||
|
// from the loop() function, but it would somewhat complicate the
|
||||||
|
// driver. A simpler solution is to output a number of NUL pad characters
|
||||||
|
// between successive command strings if there isn't sufficient elapsed time
|
||||||
|
// between them. At 9600 baud, each pad character takes approximately
|
||||||
|
// 1ms to complete. Experiments indicate that the minimum number of pads
|
||||||
|
// for reliable operation is 17. This gives 17.7ms between the end of one
|
||||||
|
// command and the beginning of the next, or 28ms between successive commands
|
||||||
|
// being completed. I've allowed 20 characters, which is almost 21ms.
|
||||||
|
const int numPadCharacters = 20; // Number of pad characters between commands
|
||||||
|
|
||||||
public:
|
public:
|
||||||
|
|
||||||
static void create(VPIN firstVpin, int nPins, HardwareSerial &serial) {
|
static void create(VPIN firstVpin, int nPins, HardwareSerial &serial) {
|
||||||
@ -84,7 +104,9 @@ protected:
|
|||||||
}
|
}
|
||||||
|
|
||||||
void _begin() override {
|
void _begin() override {
|
||||||
_serial->begin(9600);
|
_serial->begin(9600, SERIAL_8N1); // 9600baud, no parity, 1 stop bit
|
||||||
|
// Flush any data in input queue
|
||||||
|
while (_serial->available()) _serial->read();
|
||||||
_deviceState = DEVSTATE_INITIALISING;
|
_deviceState = DEVSTATE_INITIALISING;
|
||||||
|
|
||||||
// Send a query to the device to see if it responds
|
// Send a query to the device to see if it responds
|
||||||
@ -94,10 +116,10 @@ protected:
|
|||||||
|
|
||||||
void _loop(unsigned long currentMicros) override {
|
void _loop(unsigned long currentMicros) override {
|
||||||
// Check for incoming data on _serial, and update busy flag accordingly.
|
// Check for incoming data on _serial, and update busy flag accordingly.
|
||||||
// Expected message is in the form "7F FF 06 3D xx xx xx xx xx EF"
|
// Expected message is in the form "7E FF 06 3D xx xx xx xx xx EF"
|
||||||
while (_serial->available()) {
|
while (_serial->available()) {
|
||||||
int c = _serial->read();
|
int c = _serial->read();
|
||||||
if (c == 0x7E)
|
if (c == 0x7E && _inputIndex == 0)
|
||||||
_inputIndex = 1;
|
_inputIndex = 1;
|
||||||
else if ((c==0xFF && _inputIndex==1)
|
else if ((c==0xFF && _inputIndex==1)
|
||||||
|| (c==0x3D && _inputIndex==3)
|
|| (c==0x3D && _inputIndex==3)
|
||||||
@ -124,8 +146,8 @@ protected:
|
|||||||
} else
|
} else
|
||||||
_inputIndex = 0; // Unrecognised character sequence, start again!
|
_inputIndex = 0; // Unrecognised character sequence, start again!
|
||||||
}
|
}
|
||||||
// Check if the initial prompt to device has timed out. Allow 1 second
|
// Check if the initial prompt to device has timed out. Allow 5 seconds
|
||||||
if (_deviceState == DEVSTATE_INITIALISING && currentMicros - _commandSendTime > 1000000UL) {
|
if (_deviceState == DEVSTATE_INITIALISING && currentMicros - _commandSendTime > 5000000UL) {
|
||||||
DIAG(F("DFPlayer device not responding on serial port"));
|
DIAG(F("DFPlayer device not responding on serial port"));
|
||||||
_deviceState = DEVSTATE_FAILED;
|
_deviceState = DEVSTATE_FAILED;
|
||||||
}
|
}
|
||||||
@ -218,6 +240,7 @@ private:
|
|||||||
|
|
||||||
void sendPacket(uint8_t command, uint16_t arg = 0)
|
void sendPacket(uint8_t command, uint16_t arg = 0)
|
||||||
{
|
{
|
||||||
|
unsigned long currentMillis = millis();
|
||||||
uint8_t out[] = { 0x7E,
|
uint8_t out[] = { 0x7E,
|
||||||
0xFF,
|
0xFF,
|
||||||
06,
|
06,
|
||||||
@ -231,7 +254,19 @@ private:
|
|||||||
|
|
||||||
setChecksum(out);
|
setChecksum(out);
|
||||||
|
|
||||||
|
// Check how long since the last command was sent.
|
||||||
|
// Each character takes approx 1ms at 9600 baud
|
||||||
|
unsigned long minimumGap = numPadCharacters + sizeof(out);
|
||||||
|
if (currentMillis - _commandSendTime < minimumGap) {
|
||||||
|
// Output some pad characters to add an
|
||||||
|
// artificial delay between commands
|
||||||
|
for (int i=0; i<numPadCharacters; i++)
|
||||||
|
_serial->write(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Now output the command
|
||||||
_serial->write(out, sizeof(out));
|
_serial->write(out, sizeof(out));
|
||||||
|
_commandSendTime = currentMillis;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint16_t calcChecksum(uint8_t* packet)
|
uint16_t calcChecksum(uint8_t* packet)
|
||||||
|
@ -70,7 +70,7 @@ void StringFormatter::send2(Print * stream,const FSH* format, va_list args) {
|
|||||||
char* flash=(char*)format;
|
char* flash=(char*)format;
|
||||||
for(int i=0; ; ++i) {
|
for(int i=0; ; ++i) {
|
||||||
char c=GETFLASH(flash+i);
|
char c=GETFLASH(flash+i);
|
||||||
if (c=='\0') return;
|
if (c=='\0') break; // to va_end()
|
||||||
if(c!='%') { stream->print(c); continue; }
|
if(c!='%') { stream->print(c); continue; }
|
||||||
|
|
||||||
bool formatContinues=false;
|
bool formatContinues=false;
|
||||||
|
@ -18,7 +18,7 @@ default_envs =
|
|||||||
samd21-dev-usb
|
samd21-dev-usb
|
||||||
samd21-zero-usb
|
samd21-zero-usb
|
||||||
ESP32
|
ESP32
|
||||||
Nucleo-STM32F411RE
|
Nucleo-F411RE
|
||||||
Teensy3.2
|
Teensy3.2
|
||||||
Teensy3.5
|
Teensy3.5
|
||||||
Teensy3.6
|
Teensy3.6
|
||||||
@ -50,17 +50,18 @@ monitor_speed = 115200
|
|||||||
monitor_echo = yes
|
monitor_echo = yes
|
||||||
build_flags = -std=c++17
|
build_flags = -std=c++17
|
||||||
|
|
||||||
[env:samc21-firebox]
|
; Firebox disabled for now
|
||||||
platform = atmelsam
|
; [env:samc21-firebox]
|
||||||
board = firebox
|
; platform = atmelsam
|
||||||
framework = arduino
|
; board = firebox
|
||||||
upload_protocol = atmel-ice
|
; framework = arduino
|
||||||
lib_deps =
|
; upload_protocol = atmel-ice
|
||||||
${env.lib_deps}
|
; lib_deps =
|
||||||
SparkFun External EEPROM Arduino Library
|
; ${env.lib_deps}
|
||||||
monitor_speed = 115200
|
; SparkFun External EEPROM Arduino Library
|
||||||
monitor_echo = yes
|
;monitor_speed = 115200
|
||||||
build_flags = -std=c++17
|
;monitor_echo = yes
|
||||||
|
;build_flags = -std=c++17
|
||||||
|
|
||||||
[env:mega2560-debug]
|
[env:mega2560-debug]
|
||||||
platform = atmelavr
|
platform = atmelavr
|
||||||
@ -108,6 +109,10 @@ lib_deps =
|
|||||||
SPI
|
SPI
|
||||||
monitor_speed = 115200
|
monitor_speed = 115200
|
||||||
monitor_echo = yes
|
monitor_echo = yes
|
||||||
|
; Example, but v12 does generate bigger binaries
|
||||||
|
; platform_packages = toolchain-atmelavr@symlink:///opt/avr-gcc-12.1.0-x64-linux
|
||||||
|
; Should make binaries smaller
|
||||||
|
build_flags = -mcall-prologues
|
||||||
|
|
||||||
[env:mega328]
|
[env:mega328]
|
||||||
platform = atmelavr
|
platform = atmelavr
|
||||||
@ -155,6 +160,8 @@ lib_deps =
|
|||||||
SPI
|
SPI
|
||||||
monitor_speed = 115200
|
monitor_speed = 115200
|
||||||
monitor_echo = yes
|
monitor_echo = yes
|
||||||
|
; Should make binaries smaller
|
||||||
|
build_flags = -mcall-prologues
|
||||||
|
|
||||||
[env:nano]
|
[env:nano]
|
||||||
platform = atmelavr
|
platform = atmelavr
|
||||||
@ -172,7 +179,7 @@ framework = arduino
|
|||||||
lib_deps = ${env.lib_deps}
|
lib_deps = ${env.lib_deps}
|
||||||
build_flags = -std=c++17
|
build_flags = -std=c++17
|
||||||
|
|
||||||
[env:Nucleo-STM32F411RE]
|
[env:Nucleo-F411RE]
|
||||||
platform = ststm32
|
platform = ststm32
|
||||||
board = nucleo_f411re
|
board = nucleo_f411re
|
||||||
framework = arduino
|
framework = arduino
|
||||||
|
@ -4,7 +4,11 @@
|
|||||||
#include "StringFormatter.h"
|
#include "StringFormatter.h"
|
||||||
|
|
||||||
|
|
||||||
#define VERSION "4.2.4"
|
#define VERSION "4.2.6"
|
||||||
|
// 4.2.6 FIX: Remove RAM thief
|
||||||
|
// FIX: ADC port 8-15 fix
|
||||||
|
// 4.2.5 Make GETFLASHW code more universal
|
||||||
|
// FIX: Withrottle roster index
|
||||||
// Ethernet start improvement and link detection
|
// Ethernet start improvement and link detection
|
||||||
// 4.2.4 ESP32 experimental BT support
|
// 4.2.4 ESP32 experimental BT support
|
||||||
// More DC configurations possible and lower frequency
|
// More DC configurations possible and lower frequency
|
||||||
|
Loading…
Reference in New Issue
Block a user