Fix compiling for atmega2561 and add profile for it

This commit is contained in:
Josh Stewart 2020-05-21 15:42:02 +10:00
parent cbb9c339c7
commit fc1663e5d3
9 changed files with 73 additions and 38 deletions

View File

@ -58,7 +58,7 @@ script:
- cd noisymime/speeduino
- platformio update
# Run the builds (Mega must be last so that the hex file isn't cleaned up)
- platformio run -e teensy35 -e teensy40 -e megaatmega2560
- platformio run -e teensy35 -e teensy40 -e megaatmega2561 -e megaatmega2560
# Run the remote unit tests (only on master)
- 'if [ "$TRAVIS_PULL_REQUEST" == "false" ]; then platformio remote test --environment megaatmega2560; fi'
# Uploading the firmware to speeduino.com (Only on master)

View File

@ -16,6 +16,16 @@ build_unflags = -Os
build_flags = -O3 -ffast-math -Wall -Wextra -std=c99
lib_deps = EEPROM
test_build_project_src = true
debug_tool = simavr
[env:megaatmega2561]
platform=atmelavr
board=atmega2561
framework=arduino
build_unflags = -Os
build_flags = -O3 -ffast-math -Wall -Wextra -std=c99
lib_deps = EEPROM
test_build_project_src = true
[env:teensy35]
platform=teensy

View File

@ -14,9 +14,11 @@ uint8_t Gdata[9];
uint8_t Glow, Ghigh;
bool canCmdPending = false;
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
#if ( defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) )
#define CANSerial_AVAILABLE
HardwareSerial &CANSerial = Serial3;
#elif defined(CORE_STM32)
#define CANSerial_AVAILABLE
#ifndef Serial2
#define Serial2 Serial1
#endif
@ -26,6 +28,7 @@ bool canCmdPending = false;
HardwareSerial &CANSerial = Serial2;
#endif
#elif defined(CORE_TEENSY)
#define CANSerial_AVAILABLE
HardwareSerial &CANSerial = Serial2;
#endif

View File

@ -23,6 +23,7 @@ sendcancommand is called when a command is to be sent either to serial3
void secondserial_Command()
{
#if defined(CANSerial_AVAILABLE)
if (! canCmdPending) { currentsecondserialCommand = CANSerial.read(); }
switch (currentsecondserialCommand)
@ -81,27 +82,27 @@ void secondserial_Command()
canlisten = CANSerial.read();
if (canlisten == 0)
{
{
//command request failed and/or data/device was not available
break;
}
}
while (CANSerial.available() == 0) { }
Llength= CANSerial.read(); // next the number of bytes expected value
while (CANSerial.available() == 0) { }
Llength= CANSerial.read(); // next the number of bytes expected value
for (uint8_t Lcount = 0; Lcount <Llength ;Lcount++)
{
while (CANSerial.available() == 0){}
// receive all x bytes into "Lbuffer"
Lbuffer[Lcount] = CANSerial.read();
}
break;
for (uint8_t Lcount = 0; Lcount <Llength ;Lcount++)
{
while (CANSerial.available() == 0){}
// receive all x bytes into "Lbuffer"
Lbuffer[Lcount] = CANSerial.read();
}
break;
case 'n': // sends the bytes of realtime values from the NEW CAN list
sendcanValues(0, NEW_CAN_PACKET_SIZE, 0x32, 1); //send values to serial3
break;
case 'r': //New format for the optimised OutputChannels
case 'r': //New format for the optimised OutputChannels over CAN
byte Cmd;
if (CANSerial.available() >= 6)
{
@ -118,7 +119,7 @@ void secondserial_Command()
length = word(CANSerial.read(), tmp);
sendcanValues(offset, length,Cmd, 1);
canCmdPending = false;
//Serial.print(Cmd);
//Serial.print(Cmd);
}
else
{
@ -129,12 +130,11 @@ void secondserial_Command()
{
canCmdPending = true;
}
break;
case 's': // send the "a" stream code version
CANSerial.print(F("Speeduino csx02019.8"));
break;
break;
case 'S': // send code version
CANSerial.print(F("Speeduino 2019.08-ser"));
@ -155,6 +155,7 @@ void secondserial_Command()
default:
break;
}
#endif
}
void sendcanValues(uint16_t offset, uint16_t packetLength, byte cmd, byte portType)
{
@ -271,11 +272,13 @@ void sendcanValues(uint16_t offset, uint16_t packetLength, byte cmd, byte portTy
for(byte x=0; x<packetLength; x++)
{
if (portType == 1){ CANSerial.write(fullStatus[offset+x]); }
else if (portType == 2)
{
//sendto canbus transmit routine
}
#if defined(CANSerial_AVAILABLE)
if (portType == 1){ CANSerial.write(fullStatus[offset+x]); }
else if (portType == 2)
{
//sendto canbus transmit routine
}
#endif
}
}
@ -326,6 +329,7 @@ void can_Command()
// this routine sends a request(either "0" for a "G" , "1" for a "L" , "2" for a "R" to the Can interface or "3" sends the request via the actual local canbus
void sendCancommand(uint8_t cmdtype, uint16_t canaddress, uint8_t candata1, uint8_t candata2, uint16_t sourcecanAddress)
{
#if defined(CANSerial_AVAILABLE)
switch (cmdtype)
{
case 0:
@ -369,6 +373,7 @@ void sendCancommand(uint8_t cmdtype, uint16_t canaddress, uint8_t candata1, uint
default:
break;
}
#endif
}
// This routine builds the realtime data into packets that the obd requesting device can understand. This is only used by teensy and stm32 with onboard canbus

View File

@ -654,7 +654,9 @@ void sendValues(uint16_t offset, uint16_t packetLength, byte cmd, byte portNum)
for(byte x=0; x<packetLength; x++)
{
if (portNum == 0) { Serial.write(fullStatus[offset+x]); }
else if (portNum == 3){ CANSerial.write(fullStatus[offset+x]); }
#if defined(CANSerial_AVAILABLE)
else if (portNum == 3){ CANSerial.write(fullStatus[offset+x]); }
#endif
}
// Reset any flags that are being used to trigger page refreshes

View File

@ -15,6 +15,19 @@
#define INJ_CHANNELS 4
#define IGN_CHANNELS 5
#if defined(__AVR_ATmega2561__)
//This is a workaround to avoid having to change all the references to higher ADC channels. We simply define the channels (Which don't exist on the 2561) as being the same as A0-A7
//These Analog inputs should never be used on any 2561 board defintion (Because they don't exist on the MCU), so it will not cause any isses
#define A8 A0
#define A9 A1
#define A10 A2
#define A11 A3
#define A12 A4
#define A13 A5
#define A14 A6
#define A15 A7
#endif
//#define TIMER5_MICROS
#elif defined(CORE_TEENSY)

View File

@ -23,7 +23,7 @@ void initialiseIdle()
//By default, turn off the PWM interrupt (It gets turned on below if needed)
IDLE_TIMER_DISABLE();
//pins must always be initialized.
//Pin masks must always be initialized, regardless of whether PWM idle is used. This is required for STM32 to prevent issues if the IRQ function fires on restat/overflow
idle_pin_port = portOutputRegister(digitalPinToPort(pinIdle1));
idle_pin_mask = digitalPinToBitMask(pinIdle1);
idle2_pin_port = portOutputRegister(digitalPinToPort(pinIdle2));

View File

@ -1841,7 +1841,7 @@ void setPinMapping(byte boardID)
case 45:
#ifndef SMALL_FLASH_MODE //No support for bluepill here anyway
//Pin mappings for the DIY-EFI CORE4 Module. This is an AVR only module
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
#if defined(CORE_AVR)
pinInjector1 = 10; //Output pin injector 1 is on
pinInjector2 = 11; //Output pin injector 2 is on
pinInjector3 = 12; //Output pin injector 3 is on

View File

@ -102,27 +102,29 @@ void loop()
}
}
//if can or secondary serial interface is enabled then check for requests.
if (configPage9.enable_secondarySerial == 1) //secondary serial interface enabled
#if defined(CANSerial_AVAILABLE)
//if can or secondary serial interface is enabled then check for requests.
if (configPage9.enable_secondarySerial == 1) //secondary serial interface enabled
{
if ( ((mainLoopCount & 31) == 1) or (CANSerial.available() > SERIAL_BUFFER_THRESHOLD) )
{
if ( ((mainLoopCount & 31) == 1) or (CANSerial.available() > SERIAL_BUFFER_THRESHOLD) )
{
if (CANSerial.available() > 0) { secondserial_Command(); }
}
if (CANSerial.available() > 0) { secondserial_Command(); }
}
#if defined(CORE_TEENSY)
}
#endif
#if defined(CORE_TEENSY)
//currentStatus.canin[12] = configPage9.enable_intcan;
if (configPage9.enable_intcan == 1) // use internal can module
{
//check local can module
// if ( BIT_CHECK(LOOP_TIMER, BIT_TIMER_15HZ) or (CANbus0.available())
while (Can0.read(inMsg) )
{
can_Command();
//Can0.read(inMsg);
//currentStatus.canin[12] = inMsg.buf[5];
//currentStatus.canin[13] = inMsg.id;
}
{
can_Command();
//Can0.read(inMsg);
//currentStatus.canin[12] = inMsg.buf[5];
//currentStatus.canin[13] = inMsg.id;
}
}
#endif