Fix building stm32 f401 (#489)
* fix building for STM32F401CC and general macro cleanup * Now building for all generic STM32F4x7 boards in arduino IDE is ok. * buildflag cleanup Co-authored-by: Tjeerd <tjeerdie@users.noreply.github.com>
This commit is contained in:
parent
cebf27e573
commit
5c5ecbbcea
|
@ -78,7 +78,7 @@ framework = arduino
|
||||||
board = black_f407ve
|
board = black_f407ve
|
||||||
;lib_deps = EEPROM
|
;lib_deps = EEPROM
|
||||||
board_build.core = stm32
|
board_build.core = stm32
|
||||||
build_flags = -std=gnu++11 -UBOARD_NR_GPIO_PINS -DARDUINO_BLACK_F407VE -DCORE_STM32_OFFICIAL -DENABLE_HWSERIAL2 -DENABLE_HWSERIAL3 -DUSBCON -DHAL_PCD_MODULE_ENABLED -DUSBD_USE_CDC -DHAL_UART_MODULE_ENABLED
|
build_flags = -std=gnu++11 -UBOARD_NR_GPIO_PINS -DENABLE_HWSERIAL2 -DENABLE_HWSERIAL3 -DUSBCON -DHAL_PCD_MODULE_ENABLED -DUSBD_USE_CDC
|
||||||
upload_protocol = dfu
|
upload_protocol = dfu
|
||||||
debug_tool = stlink
|
debug_tool = stlink
|
||||||
monitor_speed = 115200
|
monitor_speed = 115200
|
||||||
|
@ -89,7 +89,7 @@ platform = ststm32
|
||||||
framework = arduino
|
framework = arduino
|
||||||
board = blackpill_f401cc
|
board = blackpill_f401cc
|
||||||
board_build.core = stm32
|
board_build.core = stm32
|
||||||
build_flags = -fpermissive -std=gnu++11 -UBOARD_NR_GPIO_PINS -DUSBCON -DHAL_PCD_MODULE_ENABLED -DUSBD_USE_CDC -DHAL_UART_MODULE_ENABLED -DHAL_DAC_MODULE_DISABLED -DHAL_RTC_MODULE_DISABLED -DHAL_ETH_MODULE_DISABLED -DHAL_SD_MODULE_DISABLED -DHAL_QSPI_MODULE_DISABLED
|
build_flags = -std=gnu++11 -UBOARD_NR_GPIO_PINS -DUSBCON -DHAL_PCD_MODULE_ENABLED -DUSBD_USE_CDC -DHAL_DAC_MODULE_DISABLED -DHAL_RTC_MODULE_DISABLED -DHAL_ETH_MODULE_DISABLED -DHAL_SD_MODULE_DISABLED -DHAL_QSPI_MODULE_DISABLED
|
||||||
upload_protocol = dfu
|
upload_protocol = dfu
|
||||||
debug_tool = stlink
|
debug_tool = stlink
|
||||||
monitor_speed = 115200
|
monitor_speed = 115200
|
||||||
|
|
|
@ -36,7 +36,7 @@
|
||||||
|
|
||||||
#if defined(FRAM_AS_EEPROM)
|
#if defined(FRAM_AS_EEPROM)
|
||||||
#include <Fram.h>
|
#include <Fram.h>
|
||||||
#if defined(ARDUINO_BLACK_F407VE)
|
#if defined(STM32F407xx)
|
||||||
FramClass EEPROM(PB5, PB4, PB3, PB0); /*(mosi, miso, sclk, ssel, clockspeed) 31/01/2020*/
|
FramClass EEPROM(PB5, PB4, PB3, PB0); /*(mosi, miso, sclk, ssel, clockspeed) 31/01/2020*/
|
||||||
#else
|
#else
|
||||||
FramClass EEPROM(PB15, PB14, PB13, PB12); //Blue/Black Pills
|
FramClass EEPROM(PB15, PB14, PB13, PB12); //Blue/Black Pills
|
||||||
|
|
|
@ -1,7 +1,7 @@
|
||||||
#ifndef STM32OFFICIAL_H
|
#ifndef STM32OFFICIAL_H
|
||||||
#define STM32OFFICIAL_H
|
#define STM32OFFICIAL_H
|
||||||
#if defined(CORE_STM32_OFFICIAL)
|
|
||||||
#include <Arduino.h>
|
#include <Arduino.h>
|
||||||
|
#if defined(STM32_CORE_VERSION_MAJOR)
|
||||||
#include <HardwareTimer.h>
|
#include <HardwareTimer.h>
|
||||||
#include <HardwareSerial.h>
|
#include <HardwareSerial.h>
|
||||||
|
|
||||||
|
@ -27,6 +27,12 @@
|
||||||
|
|
||||||
|
|
||||||
#define USE_SERIAL3
|
#define USE_SERIAL3
|
||||||
|
|
||||||
|
//When building for Black board Serial1 is instanciated,building generic STM32F4x7 has serial2 and serial 1 must be done here
|
||||||
|
#if SERIAL_UART_INSTANCE==2
|
||||||
|
HardwareSerial Serial1(PA10, PA9);
|
||||||
|
#endif
|
||||||
|
|
||||||
void initBoard();
|
void initBoard();
|
||||||
uint16_t freeRam();
|
uint16_t freeRam();
|
||||||
void doSystemReset();
|
void doSystemReset();
|
||||||
|
@ -83,7 +89,7 @@ extern "C" char* sbrk(int incr);
|
||||||
#elif defined(FRAM_AS_EEPROM) //https://github.com/VitorBoss/FRAM
|
#elif defined(FRAM_AS_EEPROM) //https://github.com/VitorBoss/FRAM
|
||||||
#define EEPROM_LIB_H <Fram.h>
|
#define EEPROM_LIB_H <Fram.h>
|
||||||
#include EEPROM_LIB_H
|
#include EEPROM_LIB_H
|
||||||
#if defined(ARDUINO_BLACK_F407VE)
|
#if defined(STM32F407xx)
|
||||||
FramClass EEPROM(PB5, PB4, PB3, PB0); /*(mosi, miso, sclk, ssel, clockspeed) 31/01/2020*/
|
FramClass EEPROM(PB5, PB4, PB3, PB0); /*(mosi, miso, sclk, ssel, clockspeed) 31/01/2020*/
|
||||||
#else
|
#else
|
||||||
FramClass EEPROM(PB15, PB14, PB13, PB12); //Blue/Black Pills
|
FramClass EEPROM(PB15, PB14, PB13, PB12); //Blue/Black Pills
|
||||||
|
@ -291,7 +297,8 @@ void ignitionSchedule8Interrupt(HardwareTimer*);
|
||||||
***********************************************************************************************************
|
***********************************************************************************************************
|
||||||
* CAN / Second serial
|
* CAN / Second serial
|
||||||
*/
|
*/
|
||||||
#if defined(ARDUINO_BLACK_F407VE)
|
#if defined(STM32F407xx) || defined(STM32F103xB) || defined(STM32F405xx)
|
||||||
|
#define NATIVE_CAN_AVAILABLE
|
||||||
//HardwareSerial CANSerial(PD6, PD5);
|
//HardwareSerial CANSerial(PD6, PD5);
|
||||||
#include <src/STM32_CAN/STM32_CAN.h>
|
#include <src/STM32_CAN/STM32_CAN.h>
|
||||||
//This activates CAN1 interface on STM32, but it's named as Can0, because that's how Teensy implementation is done
|
//This activates CAN1 interface on STM32, but it's named as Can0, because that's how Teensy implementation is done
|
||||||
|
|
|
@ -1,5 +1,5 @@
|
||||||
#if defined(CORE_STM32_OFFICIAL)
|
|
||||||
#include "board_stm32_official.h"
|
#include "board_stm32_official.h"
|
||||||
|
#if defined(STM32_CORE_VERSION_MAJOR)
|
||||||
#include "globals.h"
|
#include "globals.h"
|
||||||
#include "auxiliaries.h"
|
#include "auxiliaries.h"
|
||||||
#include "idle.h"
|
#include "idle.h"
|
||||||
|
@ -158,6 +158,7 @@
|
||||||
|
|
||||||
void jumpToBootloader( void ) // https://github.com/3devo/Arduino_Core_STM32/blob/jumpSysBL/libraries/SrcWrapper/src/stm32/bootloader.c
|
void jumpToBootloader( void ) // https://github.com/3devo/Arduino_Core_STM32/blob/jumpSysBL/libraries/SrcWrapper/src/stm32/bootloader.c
|
||||||
{ // https://github.com/markusgritsch/SilF4ware/blob/master/SilF4ware/drv_reset.c
|
{ // https://github.com/markusgritsch/SilF4ware/blob/master/SilF4ware/drv_reset.c
|
||||||
|
#if !defined(STM32F103xB)
|
||||||
HAL_RCC_DeInit();
|
HAL_RCC_DeInit();
|
||||||
HAL_DeInit();
|
HAL_DeInit();
|
||||||
SysTick->VAL = SysTick->LOAD = SysTick->CTRL = 0;
|
SysTick->VAL = SysTick->LOAD = SysTick->CTRL = 0;
|
||||||
|
@ -182,6 +183,7 @@
|
||||||
: : [DFU_addr] "l" (DFU_addr) : "r0"
|
: : [DFU_addr] "l" (DFU_addr) : "r0"
|
||||||
);
|
);
|
||||||
__builtin_unreachable();
|
__builtin_unreachable();
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
|
|
@ -149,5 +149,6 @@
|
||||||
#endif
|
#endif
|
||||||
static CAN_message_t outMsg;
|
static CAN_message_t outMsg;
|
||||||
static CAN_message_t inMsg;
|
static CAN_message_t inMsg;
|
||||||
|
#define NATIVE_CAN_AVAILABLE
|
||||||
#endif //CORE_TEENSY
|
#endif //CORE_TEENSY
|
||||||
#endif //TEENSY35_H
|
#endif //TEENSY35_H
|
|
@ -157,6 +157,7 @@
|
||||||
FlexCAN_T4<CAN3, RX_SIZE_256, TX_SIZE_16> Can2;
|
FlexCAN_T4<CAN3, RX_SIZE_256, TX_SIZE_16> Can2;
|
||||||
static CAN_message_t outMsg;
|
static CAN_message_t outMsg;
|
||||||
static CAN_message_t inMsg;
|
static CAN_message_t inMsg;
|
||||||
|
#define NATIVE_CAN_AVAILABLE
|
||||||
|
|
||||||
#endif //CORE_TEENSY
|
#endif //CORE_TEENSY
|
||||||
#endif //TEENSY41_H
|
#endif //TEENSY41_H
|
|
@ -286,7 +286,7 @@ void sendcanValues(uint16_t offset, uint16_t packetLength, byte cmd, byte portTy
|
||||||
void can_Command()
|
void can_Command()
|
||||||
{
|
{
|
||||||
//int currentcanCommand = inMsg.id;
|
//int currentcanCommand = inMsg.id;
|
||||||
#if defined(CORE_TEENSY) || defined(ARDUINO_ARCH_STM32)
|
#if defined (NATIVE_CAN_AVAILABLE)
|
||||||
// currentStatus.canin[12] = (inMsg.id);
|
// currentStatus.canin[12] = (inMsg.id);
|
||||||
if ( (inMsg.id == uint16_t(configPage9.obd_address + 0x100)) || (inMsg.id == 0x7DF))
|
if ( (inMsg.id == uint16_t(configPage9.obd_address + 0x100)) || (inMsg.id == 0x7DF))
|
||||||
{
|
{
|
||||||
|
@ -355,7 +355,7 @@ void sendCancommand(uint8_t cmdtype, uint16_t canaddress, uint8_t candata1, uint
|
||||||
//send to truecan send routine
|
//send to truecan send routine
|
||||||
//canaddress == speeduino canid, candata1 == canin channel dest, paramgroup == can address to request from
|
//canaddress == speeduino canid, candata1 == canin channel dest, paramgroup == can address to request from
|
||||||
//This section is to be moved to the correct can output routine later
|
//This section is to be moved to the correct can output routine later
|
||||||
#if defined(CORE_TEENSY) || defined(ARDUINO_ARCH_STM32) //Scope guarding this for now, but this needs a bit of a rethink for how it can be handled better across multiple archs
|
#if defined(CORE_TEENSY) || defined(STM32F407xx) || defined(STM32F103xB) || defined(STM32F405xx) //Scope guarding this for now, but this needs a bit of a rethink for how it can be handled better across multiple archs
|
||||||
outMsg.id = (canaddress);
|
outMsg.id = (canaddress);
|
||||||
outMsg.len = 8;
|
outMsg.len = 8;
|
||||||
outMsg.buf[0] = 0x0B ; //11;
|
outMsg.buf[0] = 0x0B ; //11;
|
||||||
|
@ -376,7 +376,7 @@ void sendCancommand(uint8_t cmdtype, uint16_t canaddress, uint8_t candata1, uint
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
#if defined(CORE_TEENSY35) || defined(ARDUINO_ARCH_STM32)
|
#if defined(NATIVE_CAN_AVAILABLE)
|
||||||
// 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
|
// 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
|
||||||
void obd_response(uint8_t PIDmode, uint8_t requestedPIDlow, uint8_t requestedPIDhigh)
|
void obd_response(uint8_t PIDmode, uint8_t requestedPIDlow, uint8_t requestedPIDhigh)
|
||||||
{
|
{
|
||||||
|
|
|
@ -70,7 +70,7 @@
|
||||||
#ifndef LED_BUILTIN
|
#ifndef LED_BUILTIN
|
||||||
#define LED_BUILTIN PB1 //Maple Mini
|
#define LED_BUILTIN PB1 //Maple Mini
|
||||||
#endif
|
#endif
|
||||||
#elif defined(ARDUINO_BLACK_F407VE)
|
#elif defined(STM32F407xx)
|
||||||
#define BOARD_DIGITAL_GPIO_PINS 74
|
#define BOARD_DIGITAL_GPIO_PINS 74
|
||||||
#define BOARD_NR_GPIO_PINS 74
|
#define BOARD_NR_GPIO_PINS 74
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -212,7 +212,7 @@ void initialiseAll()
|
||||||
//Setup the calibration tables
|
//Setup the calibration tables
|
||||||
loadCalibration();
|
loadCalibration();
|
||||||
|
|
||||||
#if defined(CORE_TEENSY35) || defined(ARDUINO_ARCH_STM32)
|
#if defined (NATIVE_CAN_AVAILABLE)
|
||||||
configPage9.intcan_available = 1; // device has internal canbus
|
configPage9.intcan_available = 1; // device has internal canbus
|
||||||
//Teensy uses the Flexcan_T4 library to use the internal canbus
|
//Teensy uses the Flexcan_T4 library to use the internal canbus
|
||||||
//enable local can interface
|
//enable local can interface
|
||||||
|
@ -1309,7 +1309,7 @@ void setPinMapping(byte boardID)
|
||||||
pinCoil4 = 29;
|
pinCoil4 = 29;
|
||||||
pinCoil3 = 30;
|
pinCoil3 = 30;
|
||||||
pinO2 = A22;
|
pinO2 = A22;
|
||||||
#elif defined(ARDUINO_BLACK_F407VE)
|
#elif defined(STM32F407xx)
|
||||||
//Pin definitions for experimental board Tjeerd
|
//Pin definitions for experimental board Tjeerd
|
||||||
//Black F407VE wiki.stm32duino.com/index.php?title=STM32F407
|
//Black F407VE wiki.stm32duino.com/index.php?title=STM32F407
|
||||||
|
|
||||||
|
@ -2043,7 +2043,7 @@ void setPinMapping(byte boardID)
|
||||||
|
|
||||||
|
|
||||||
case 60:
|
case 60:
|
||||||
#if defined(ARDUINO_BLACK_F407VE)
|
#if defined(STM32F407xx)
|
||||||
//Pin definitions for experimental board Tjeerd
|
//Pin definitions for experimental board Tjeerd
|
||||||
//Black F407VE wiki.stm32duino.com/index.php?title=STM32F407
|
//Black F407VE wiki.stm32duino.com/index.php?title=STM32F407
|
||||||
//https://github.com/Tjeerdie/SPECTRE/tree/master/SPECTRE_V0.5
|
//https://github.com/Tjeerdie/SPECTRE/tree/master/SPECTRE_V0.5
|
||||||
|
@ -2191,7 +2191,7 @@ void setPinMapping(byte boardID)
|
||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
#if defined(ARDUINO_BLACK_F407VE)
|
#if defined(STM32F407xx)
|
||||||
//Pin definitions for experimental board Tjeerd
|
//Pin definitions for experimental board Tjeerd
|
||||||
//Black F407VE wiki.stm32duino.com/index.php?title=STM32F407
|
//Black F407VE wiki.stm32duino.com/index.php?title=STM32F407
|
||||||
|
|
||||||
|
|
|
@ -92,7 +92,7 @@ void setIgnitionSchedule8(void (*startCallback)(), unsigned long timeout, unsign
|
||||||
inline void refreshIgnitionSchedule1(unsigned long timeToEnd) __attribute__((always_inline));
|
inline void refreshIgnitionSchedule1(unsigned long timeToEnd) __attribute__((always_inline));
|
||||||
|
|
||||||
//The ARM cores use seprate functions for their ISRs
|
//The ARM cores use seprate functions for their ISRs
|
||||||
#if defined(CORE_STM32_OFFICIAL) || defined(CORE_STM32_GENERIC) || defined(CORE_TEENSY)
|
#if defined(ARDUINO_ARCH_STM32) || defined(CORE_TEENSY)
|
||||||
static inline void fuelSchedule1Interrupt();
|
static inline void fuelSchedule1Interrupt();
|
||||||
static inline void fuelSchedule2Interrupt();
|
static inline void fuelSchedule2Interrupt();
|
||||||
static inline void fuelSchedule3Interrupt();
|
static inline void fuelSchedule3Interrupt();
|
||||||
|
|
|
@ -126,7 +126,7 @@ void loop()
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
#if defined(CORE_TEENSY35) || defined(ARDUINO_ARCH_STM32)
|
#if defined (NATIVE_CAN_AVAILABLE)
|
||||||
//currentStatus.canin[12] = configPage9.enable_intcan;
|
//currentStatus.canin[12] = configPage9.enable_intcan;
|
||||||
if (configPage9.enable_intcan == 1) // use internal can module
|
if (configPage9.enable_intcan == 1) // use internal can module
|
||||||
{
|
{
|
||||||
|
|
|
@ -1,5 +1,4 @@
|
||||||
//#if defined(ARDUINO_BLACK_F407VE)
|
#if defined(STM32F407xx)
|
||||||
#if defined(ARDUINO_ARCH_STM32)
|
|
||||||
#include "BackupSramAsEEPROM.h"
|
#include "BackupSramAsEEPROM.h"
|
||||||
|
|
||||||
BackupSramAsEEPROM::BackupSramAsEEPROM(){
|
BackupSramAsEEPROM::BackupSramAsEEPROM(){
|
||||||
|
|
|
@ -2,9 +2,7 @@
|
||||||
//The backup battery is available on the ebay stm32F407VET6 black boards.
|
//The backup battery is available on the ebay stm32F407VET6 black boards.
|
||||||
#ifndef BACKUPSRAMASEEPROM_H
|
#ifndef BACKUPSRAMASEEPROM_H
|
||||||
#define BACKUPSRAMASEEPROM_H
|
#define BACKUPSRAMASEEPROM_H
|
||||||
#if defined(ARDUINO_ARCH_STM32)
|
#if defined(STM32F407xx)
|
||||||
|
|
||||||
|
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
#include "stm32f407xx.h"
|
#include "stm32f407xx.h"
|
||||||
|
|
||||||
|
|
|
@ -37,7 +37,7 @@ SPIFlash::SPIFlash(uint8_t cs) {
|
||||||
pinMode(csPin, OUTPUT);
|
pinMode(csPin, OUTPUT);
|
||||||
CHIP_DESELECT
|
CHIP_DESELECT
|
||||||
}
|
}
|
||||||
#elif defined (ARDUINO_ARCH_SAMD) || defined (ARCH_STM32)
|
#elif defined (ARDUINO_ARCH_SAMD) || defined (ARDUINO_ARCH_STM32)
|
||||||
SPIFlash::SPIFlash(uint8_t cs, SPIClass *spiinterface) {
|
SPIFlash::SPIFlash(uint8_t cs, SPIClass *spiinterface) {
|
||||||
_spi = spiinterface; //Sets SPI interface - if no user selection is made, this defaults to SPI
|
_spi = spiinterface; //Sets SPI interface - if no user selection is made, this defaults to SPI
|
||||||
csPin = cs;
|
csPin = cs;
|
||||||
|
|
|
@ -34,7 +34,7 @@ class SPIFlash {
|
||||||
public:
|
public:
|
||||||
//------------------------------------ Constructor ------------------------------------//
|
//------------------------------------ Constructor ------------------------------------//
|
||||||
//New Constructor to Accept the PinNames as a Chip select Parameter - @boseji <salearj@hotmail.com> 02.03.17
|
//New Constructor to Accept the PinNames as a Chip select Parameter - @boseji <salearj@hotmail.com> 02.03.17
|
||||||
#if defined (ARDUINO_ARCH_SAMD) || defined(ARCH_STM32) || defined(CORE_STM32_OFFICIAL)
|
#if defined (ARDUINO_ARCH_SAMD) || defined(ARDUINO_ARCH_STM32)
|
||||||
SPIFlash(uint8_t cs = CS, SPIClass *spiinterface=&SPI);
|
SPIFlash(uint8_t cs = CS, SPIClass *spiinterface=&SPI);
|
||||||
#elif defined (BOARD_RTL8195A)
|
#elif defined (BOARD_RTL8195A)
|
||||||
SPIFlash(PinName cs = CS);
|
SPIFlash(PinName cs = CS);
|
||||||
|
|
|
@ -107,7 +107,7 @@
|
||||||
#define ARCH_STM32
|
#define ARCH_STM32
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
#if defined (ARDUINO_ARCH_SAM) || defined (ARDUINO_ARCH_SAMD) || defined (ARDUINO_ARCH_ESP8266) || defined (SIMBLEE) || defined (ARDUINO_ARCH_ESP32) || defined (BOARD_RTL8195A) || defined(ARCH_STM32) || defined(ESP32) || defined(NRF5)
|
#if defined (ARDUINO_ARCH_SAM) || defined (ARDUINO_ARCH_SAMD) || defined (ARDUINO_ARCH_ESP8266) || defined (SIMBLEE) || defined (ARDUINO_ARCH_ESP32) || defined (BOARD_RTL8195A) || defined(ARDUINO_ARCH_STM32) || defined(ESP32) || defined(NRF5)
|
||||||
// RTL8195A included - @boseji <salearj@hotmail.com> 02.03.17
|
// RTL8195A included - @boseji <salearj@hotmail.com> 02.03.17
|
||||||
#define _delay_us(us) delayMicroseconds(us)
|
#define _delay_us(us) delayMicroseconds(us)
|
||||||
#else
|
#else
|
||||||
|
|
|
@ -43,7 +43,7 @@
|
||||||
#define BEGIN_SPI SPI.begin();
|
#define BEGIN_SPI SPI.begin();
|
||||||
|
|
||||||
// Defines and variables specific to SAMD architecture
|
// Defines and variables specific to SAMD architecture
|
||||||
#elif defined (ARDUINO_ARCH_SAMD) || defined(ARCH_STM32)
|
#elif defined (ARDUINO_ARCH_SAMD) || defined(ARDUINO_ARCH_STM32)
|
||||||
#define CHIP_SELECT digitalWrite(csPin, LOW);
|
#define CHIP_SELECT digitalWrite(csPin, LOW);
|
||||||
#define CHIP_DESELECT digitalWrite(csPin, HIGH);
|
#define CHIP_DESELECT digitalWrite(csPin, HIGH);
|
||||||
#define xfer(n) _spi->transfer(n)
|
#define xfer(n) _spi->transfer(n)
|
||||||
|
|
|
@ -1,4 +1,4 @@
|
||||||
#if defined(ARDUINO_ARCH_STM32)
|
#if defined(STM32F407xx) || defined(STM32F103xB) || defined(STM32F405xx)
|
||||||
#include "STM32_CAN.h"
|
#include "STM32_CAN.h"
|
||||||
|
|
||||||
uint8_t STM32_CAN::CANMsgAvail()
|
uint8_t STM32_CAN::CANMsgAvail()
|
||||||
|
|
|
@ -9,7 +9,7 @@ https://github.com/nopnop2002/Arduino-STM32-CAN
|
||||||
#ifndef STM32_CAN_H
|
#ifndef STM32_CAN_H
|
||||||
#define STM32_CAN_H
|
#define STM32_CAN_H
|
||||||
|
|
||||||
#if defined(ARDUINO_ARCH_STM32)
|
#if defined(STM32F407xx) || defined(STM32F103xB) || defined(STM32F405xx)
|
||||||
#include <Arduino.h>
|
#include <Arduino.h>
|
||||||
|
|
||||||
#define STM32_CAN_TIR_TXRQ (1U << 0U) // Bit 0: Transmit Mailbox Request
|
#define STM32_CAN_TIR_TXRQ (1U << 0U) // Bit 0: Transmit Mailbox Request
|
||||||
|
|
|
@ -39,7 +39,7 @@ volatile uint16_t last250msLoopCount = 1000; //Set to effectively random number
|
||||||
#if defined (CORE_TEENSY)
|
#if defined (CORE_TEENSY)
|
||||||
IntervalTimer lowResTimer;
|
IntervalTimer lowResTimer;
|
||||||
void oneMSInterval();
|
void oneMSInterval();
|
||||||
#elif defined(CORE_STM32_OFFICIAL) || defined(CORE_STM32_GENERIC)
|
#elif defined (ARDUINO_ARCH_STM32)
|
||||||
void oneMSInterval();
|
void oneMSInterval();
|
||||||
#endif
|
#endif
|
||||||
void initialiseTimers();
|
void initialiseTimers();
|
||||||
|
|
Loading…
Reference in New Issue