From d8b16bb0c4ef58416746416247bf0b88c38721e8 Mon Sep 17 00:00:00 2001 From: bmellink Date: Fri, 18 Sep 2020 19:09:34 +0200 Subject: [PATCH] Fix STM32 compile errors STM32 code was created for STM32 core lib before 1.6. Compiler errors for newer versions. Now supports current version (1.9) --- README.md | 7 +++++-- library.properties | 2 +- src/IBusBM.cpp | 20 +++++++++++--------- src/IBusBM.h | 10 +++++++++- 4 files changed, 26 insertions(+), 13 deletions(-) diff --git a/README.md b/README.md index 7cc933f..3f88633 100644 --- a/README.md +++ b/README.md @@ -221,9 +221,12 @@ void loop() { The IBusBM class exposes the following functions: ``` -- void begin(HardwareSerial& serial, int8_t timerid=0, int8_t rxPin=-1, int8_t txPin=-1); +- void begin(HardwareSerial &serial, int8_t timerid=0, int8_t rxPin=-1, int8_t txPin=-1); // other architectures +- void begin(HardwareSerial &serial, TIM_TypeDef * timerid=TIM1, int8_t rxPin=-1, int8_t txPin=-1); // STM32 architecture + ``` -This initializes the library for a given serial port. rxPin and txPin can be specified for the serial ports 1 and 2 of ESP32 architectures (default to RX1=9, TX1=10, RX2=16, TX2=17). Serial port 0 and ports on AVR boards can not be overruled (pins on ESP32 are RX0=3, TX0=1). The variable timerid specifies the timer used (ESP32 only) to drive the background processing (see below). A value of IBUSBM_NOTIMER disables the timer interrupt and you should call loop() yourself. +This initializes the library for a given serial port. rxPin and txPin can be specified for the serial ports 1 and 2 of ESP32 architectures (default to RX1=9, TX1=10, RX2=16, TX2=17). Serial port 0 and ports on AVR boards can not be overruled (pins on ESP32 are RX0=3, TX0=1). The variable timerid specifies the timer used (ESP32 and STM32 only) to drive the background processing (see below). A value of IBUSBM_NOTIMER disables the timer interrupt and you should call loop() yourself. Please note the default timer for STM32 is TIM1. If you are using +TIM1 for something else (such as Servo or SoftwareSerial), please change the default. ``` uint8_t addSensor(uint8_t type, uint8_t len=2); diff --git a/library.properties b/library.properties index c60d6d9..b2749ea 100644 --- a/library.properties +++ b/library.properties @@ -6,5 +6,5 @@ sentence=Arduino library for the Flysky/Turnigy RC iBUS protocol - servo (receiv paragraph=With this library you can interface to any RC receiver that supports the Flysky iBUS protocol (such as TGY-IA6B). Flysky iBUS uses a half-duplex asynchronous protocol format at 115200 baud. The library requires at least one free hardware UART (serial) port. The library can be used to receive data (typically servo data) and send data (telemetry or sensors). category=Communication url=https://github.com/bmellink/IBusBM -architectures=avr,esp32,stm32,mbed +architectures=avr,esp32,stm32,mbed,STM32F1 includes=IBusBM.h diff --git a/src/IBusBM.cpp b/src/IBusBM.cpp index c6fcd5f..624c11a 100644 --- a/src/IBusBM.cpp +++ b/src/IBusBM.cpp @@ -36,10 +36,6 @@ IBusBM* IBusBMfirst = NULL; SIGNAL(TIMER0_COMPA_vect) { if (IBusBMfirst) IBusBMfirst->loop(); // gets new servo values if available and process any sensor data } -#elif defined _VARIANT_ARDUINO_STM32_ -void onTimer(stimer_t *htim) { - if (IBusBMfirst) IBusBMfirst->loop(); // gets new servo values if available and process any sensor data -} #else void onTimer() { if (IBusBMfirst) IBusBMfirst->loop(); // gets new servo values if available and process any sensor data @@ -84,7 +80,13 @@ extern "C" { Checksum: DA F3 -> calculated by adding up all previous bytes, total must be FFFF */ + +#if defined(_VARIANT_ARDUINO_STM32_) +void IBusBM::begin(HardwareSerial &serial, TIM_TypeDef * timerid, int8_t rxPin, int8_t txPin) { +#else void IBusBM::begin(HardwareSerial &serial, int8_t timerid, int8_t rxPin, int8_t txPin) { +#endif + #ifdef ARDUINO_ARCH_ESP32 serial.begin(115200, SERIAL_8N1, rxPin, txPin); #else @@ -118,11 +120,11 @@ void IBusBM::begin(HardwareSerial &serial, int8_t timerid, int8_t rxPin, int8_t timerAlarmWrite(timer, 1000, true); //1 ms timerAlarmEnable(timer); #elif defined(_VARIANT_ARDUINO_STM32_) - TIM_TypeDef * TIMER = TIM1; // Select timer, TODO convert (int8_t timerid) into: (TIM_TypeDef * TIMER = TIMx) - static stimer_t TimHandle; // Handler for stimer - TimHandle.timer = TIMER; // Set TIMx instance. - TimerHandleInit(&TimHandle, 1000 - 1, ((uint32_t)(getTimerClkFreq(TIMER) / (1000000)) - 1)); // Set TIMx timer to 1ms - attachIntHandle(&TimHandle, onTimer); // Attach onTimer interupt routine + // see https://github.com/stm32duino/wiki/wiki/HardwareTimer-library + HardwareTimer *stimer_t = new HardwareTimer(timerid); + stimer_t->setOverflow(1000, HERTZ_FORMAT); // 1000 Hz + stimer_t->attachInterrupt(onTimer); + stimer_t->resume(); #elif defined(ARDUINO_ARCH_MBED) NRF_TIMER4->TASKS_STOP = 1; // Stop timer NRF_TIMER4->MODE = TIMER_MODE_MODE_Timer; // Set the timer in Counter Mode diff --git a/src/IBusBM.h b/src/IBusBM.h index c998eb2..6efdb09 100644 --- a/src/IBusBM.h +++ b/src/IBusBM.h @@ -28,7 +28,6 @@ #define IBUS_PRESS 0x41 // Pressure (in Pa) #define IBUS_SERVO 0xfd // Servo value -#define IBUSBM_NOTIMER -1 // no timer interrupt used #if defined(ARDUINO_ARCH_MBED) #define HardwareSerial arduino::HardwareSerial @@ -40,7 +39,16 @@ class Stream; class IBusBM { public: +#if defined(_VARIANT_ARDUINO_STM32_) + #if !defined(STM32_CORE_VERSION) || (STM32_CORE_VERSION < 0x01090000) + #error "Due to API change, this sketch is compatible with STM32_CORE_VERSION >= 0x01090000" + #endif + #define IBUSBM_NOTIMER NULL // no timer interrupt used + void begin(HardwareSerial &serial, TIM_TypeDef * timerid=TIM1, int8_t rxPin=-1, int8_t txPin=-1); +#else + #define IBUSBM_NOTIMER -1 // no timer interrupt used void begin(HardwareSerial &serial, int8_t timerid=0, int8_t rxPin=-1, int8_t txPin=-1); +#endif uint16_t readChannel(uint8_t channelNr); // read servo channel 0..9 uint8_t addSensor(uint8_t type, uint8_t len=2); // add sensor type and data length (2 or 4), returns address void setSensorMeasurement(uint8_t adr, int32_t value);