From 31f7b32fab3015a8c34c281d2b21dde068c3d740 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 11 May 2020 15:55:16 +1000 Subject: [PATCH] HAL_ChibiOS: resync for 4.0 update --- .../AP_HAL_ChibiOS/AP_HAL_ChibiOS_Namespace.h | 1 - libraries/AP_HAL_ChibiOS/AnalogIn.cpp | 12 +- libraries/AP_HAL_ChibiOS/AnalogIn.h | 7 +- libraries/AP_HAL_ChibiOS/CANFDIface.cpp | 5 +- libraries/AP_HAL_ChibiOS/CANSerialRouter.cpp | 12 +- libraries/AP_HAL_ChibiOS/Device.cpp | 10 +- libraries/AP_HAL_ChibiOS/GPIO.cpp | 108 +++- libraries/AP_HAL_ChibiOS/GPIO.h | 10 + .../AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp | 24 +- libraries/AP_HAL_ChibiOS/I2CDevice.cpp | 8 +- libraries/AP_HAL_ChibiOS/RCInput.cpp | 4 +- libraries/AP_HAL_ChibiOS/RCInput.h | 2 +- libraries/AP_HAL_ChibiOS/SPIDevice.cpp | 4 +- libraries/AP_HAL_ChibiOS/Scheduler.cpp | 85 ++- libraries/AP_HAL_ChibiOS/Scheduler.h | 2 + libraries/AP_HAL_ChibiOS/Semaphores.cpp | 73 --- libraries/AP_HAL_ChibiOS/Semaphores.h | 16 +- libraries/AP_HAL_ChibiOS/Storage.cpp | 10 + libraries/AP_HAL_ChibiOS/UARTDriver.cpp | 398 ++++++++----- libraries/AP_HAL_ChibiOS/UARTDriver.h | 36 +- .../hwdef/CUAV-Nora/defaults.parm | 13 + .../hwdef/CUAV-Nora/hwdef-bl.dat | 62 ++ .../AP_HAL_ChibiOS/hwdef/CUAV-Nora/hwdef.dat | 295 ++++++++++ .../hwdef/CUAV-X7/defaults.parm | 18 + .../AP_HAL_ChibiOS/hwdef/CUAV-X7/hwdef-bl.dat | 62 ++ .../AP_HAL_ChibiOS/hwdef/CUAV-X7/hwdef.dat | 306 ++++++++++ .../hwdef/CUAV_GPS/hwdef-bl.dat | 22 +- .../AP_HAL_ChibiOS/hwdef/CUAV_GPS/hwdef.dat | 45 +- .../hwdef/CUAVv5Nano/hwdef-bl.dat | 13 +- .../AP_HAL_ChibiOS/hwdef/CUAVv5Nano/hwdef.dat | 2 +- .../AP_HAL_ChibiOS/hwdef/CubeBlack/hwdef.dat | 23 + .../hwdef/CubeOrange/hwdef-bl.dat | 5 +- .../AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef.dat | 22 +- .../hwdef/CubeYellow/hwdef-bl.dat | 13 +- .../AP_HAL_ChibiOS/hwdef/CubeYellow/hwdef.dat | 24 +- .../hwdef/DrotekP3Pro/hwdef-bl.dat | 12 +- .../hwdef/DrotekP3Pro/hwdef.dat | 9 +- .../hwdef/Durandal/hwdef-bl.dat | 7 +- .../AP_HAL_ChibiOS/hwdef/Durandal/hwdef.dat | 4 +- .../hwdef/F35Lightning/hwdef-bl.dat | 5 +- .../hwdef/F35Lightning/hwdef.dat | 8 +- .../AP_HAL_ChibiOS/hwdef/F4BY/hwdef-bl.dat | 7 +- libraries/AP_HAL_ChibiOS/hwdef/F4BY/hwdef.dat | 10 +- .../hwdef/KakuteF4/hwdef-bl.dat | 5 +- .../AP_HAL_ChibiOS/hwdef/KakuteF4/hwdef.dat | 11 +- .../hwdef/KakuteF7/hwdef-bl.dat | 10 +- .../AP_HAL_ChibiOS/hwdef/KakuteF7/hwdef.dat | 26 +- .../hwdef/KakuteF7Mini/hwdef.dat | 39 +- .../hwdef/MatekF405-Wing/hwdef-bl.dat | 5 +- .../hwdef/MatekF405-Wing/hwdef.dat | 31 +- .../hwdef/MatekF405/hwdef-bl.dat | 5 +- .../AP_HAL_ChibiOS/hwdef/MatekF405/hwdef.dat | 38 +- .../hwdef/MatekF765-Wing/hwdef-bl.dat | 13 +- .../hwdef/MatekF765-Wing/hwdef.dat | 24 +- .../hwdef/MatekH743/hwdef-bl.dat | 50 ++ .../AP_HAL_ChibiOS/hwdef/MatekH743/hwdef.dat | 210 +++++++ .../hwdef/NucleoH743/hwdef-bl.dat | 4 +- .../AP_HAL_ChibiOS/hwdef/NucleoH743/hwdef.dat | 4 +- .../hwdef/OMNIBUSF7V2/hwdef-bl.dat | 13 +- .../hwdef/OMNIBUSF7V2/hwdef.dat | 24 +- .../hwdef/OmnibusNanoV6/hwdef-bl.dat | 5 +- .../hwdef/OmnibusNanoV6/hwdef.dat | 15 +- .../AP_HAL_ChibiOS/hwdef/PH4-mini/hwdef.dat | 2 +- .../hwdef/Pixhawk1-1M/hwdef.dat | 1 + .../AP_HAL_ChibiOS/hwdef/Pixhawk4/README.md | 8 +- .../AP_HAL_ChibiOS/hwdef/R9Pilot/hwdef-bl.dat | 44 ++ .../AP_HAL_ChibiOS/hwdef/R9Pilot/hwdef.dat | 184 ++++++ .../hwdef/SuccexF4/hwdef-bl.dat | 43 ++ .../AP_HAL_ChibiOS/hwdef/SuccexF4/hwdef.dat | 136 +++++ .../hwdef/TBS-Colibri-F7/hwdef-bl.dat | 12 +- .../hwdef/TBS-Colibri-F7/hwdef.dat | 2 +- .../hwdef/VRBrain-v51/hwdef-bl.dat | 5 +- .../hwdef/VRBrain-v51/hwdef.dat | 6 +- .../hwdef/VRBrain-v52/hwdef-bl.dat | 5 +- .../hwdef/VRBrain-v52/hwdef.dat | 6 +- .../hwdef/VRBrain-v54/hwdef-bl.dat | 4 +- .../hwdef/VRBrain-v54/hwdef.dat | 5 +- .../hwdef/VRCore-v10/hwdef-bl.dat | 5 +- .../AP_HAL_ChibiOS/hwdef/VRCore-v10/hwdef.dat | 6 +- .../hwdef/VRUBrain-v51/hwdef-bl.dat | 5 +- .../hwdef/VRUBrain-v51/hwdef.dat | 7 +- .../hwdef/ZubaxGNSS/hwdef-bl.dat | 10 +- .../AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef.dat | 11 +- .../hwdef/airbotf4/hwdef-bl.dat | 5 +- .../AP_HAL_ChibiOS/hwdef/airbotf4/hwdef.dat | 8 +- libraries/AP_HAL_ChibiOS/hwdef/common/board.c | 5 +- .../AP_HAL_ChibiOS/hwdef/common/chconf.h | 15 +- .../AP_HAL_ChibiOS/hwdef/common/common.ld | 3 + libraries/AP_HAL_ChibiOS/hwdef/common/flash.c | 21 +- .../AP_HAL_ChibiOS/hwdef/common/halconf.h | 2 +- libraries/AP_HAL_ChibiOS/hwdef/common/hrt.c | 12 +- .../AP_HAL_ChibiOS/hwdef/common/malloc.c | 15 + .../AP_HAL_ChibiOS/hwdef/common/mcuconf.h | 2 + .../AP_HAL_ChibiOS/hwdef/common/stm32_util.c | 106 +++- .../AP_HAL_ChibiOS/hwdef/common/stm32_util.h | 24 +- .../hwdef/common/stm32f3_mcuconf.h | 174 ++++++ .../hwdef/common/stm32f47_mcuconf.h | 68 ++- .../hwdef/common/stm32h7_mcuconf.h | 31 +- .../AP_HAL_ChibiOS/hwdef/common/watchdog.c | 4 +- .../AP_HAL_ChibiOS/hwdef/common/watchdog.h | 1 + .../hwdef/crazyflie2/hwdef-bl.dat | 46 ++ .../AP_HAL_ChibiOS/hwdef/crazyflie2/hwdef.dat | 7 +- .../hwdef/f103-ADSB/hwdef-bl.dat | 3 +- .../AP_HAL_ChibiOS/hwdef/f103-ADSB/hwdef.dat | 3 +- .../hwdef/f103-GPS/hwdef-bl.dat | 4 +- .../AP_HAL_ChibiOS/hwdef/f103-GPS/hwdef.dat | 15 +- .../hwdef/f103-HWESC/hwdef-bl.dat | 6 + .../AP_HAL_ChibiOS/hwdef/f103-HWESC/hwdef.dat | 7 + .../hwdef/f103-RangeFinder/hwdef-bl.dat | 3 +- .../hwdef/f103-RangeFinder/hwdef.dat | 6 +- .../hwdef/f103-Trigger/hwdef-bl.dat | 6 + .../hwdef/f103-Trigger/hwdef.dat | 27 + .../hwdef/f103-periph/hwdef-bl.dat | 4 +- .../hwdef/f103-periph/hwdef.dat | 23 +- .../hwdef/f303-GPS/hwdef-bl.dat | 6 + .../AP_HAL_ChibiOS/hwdef/f303-GPS/hwdef.dat | 18 + .../hwdef/f303-HWESC/hwdef-bl.dat | 5 + .../AP_HAL_ChibiOS/hwdef/f303-HWESC/hwdef.dat | 7 + .../hwdef/f303-M10025/hwdef-bl.dat | 6 + .../hwdef/f303-M10025/hwdef.dat | 26 + .../hwdef/f303-M10070/hwdef-bl.dat | 9 + .../hwdef/f303-M10070/hwdef.dat | 29 + .../hwdef/f303-Universal/hwdef-bl.dat | 6 + .../hwdef/f303-Universal/hwdef.dat | 29 + .../hwdef/f303-periph/hwdef-bl.dat | 98 ++++ .../hwdef/f303-periph/hwdef.dat | 136 +++++ .../AP_HAL_ChibiOS/hwdef/fmuv2/hwdef.dat | 3 + .../AP_HAL_ChibiOS/hwdef/fmuv3/hwdef-bl.dat | 11 +- .../AP_HAL_ChibiOS/hwdef/fmuv3/hwdef.dat | 33 +- .../AP_HAL_ChibiOS/hwdef/fmuv4/hwdef-bl.dat | 4 +- .../AP_HAL_ChibiOS/hwdef/fmuv4/hwdef.dat | 7 +- .../AP_HAL_ChibiOS/hwdef/fmuv5/hwdef-bl.dat | 12 +- .../AP_HAL_ChibiOS/hwdef/fmuv5/hwdef.dat | 17 +- .../AP_HAL_ChibiOS/hwdef/iomcu/hwdef.dat | 5 +- .../hwdef/luminousbee4/hwdef.dat | 8 +- .../hwdef/mRoControlZeroF7/hwdef-bl.dat | 12 +- .../hwdef/mRoControlZeroF7/hwdef.dat | 13 +- .../hwdef/mRoNexus/hwdef-bl.dat | 59 ++ .../AP_HAL_ChibiOS/hwdef/mRoNexus/hwdef.dat | 193 +++++++ .../hwdef/mRoX21-777/hwdef-bl.dat | 12 +- .../AP_HAL_ChibiOS/hwdef/mRoX21-777/hwdef.dat | 23 +- .../hwdef/mindpx-v2/hwdef-bl.dat | 6 +- .../AP_HAL_ChibiOS/hwdef/mindpx-v2/hwdef.dat | 17 +- .../hwdef/mini-pix/hwdef-bl.dat | 4 +- .../AP_HAL_ChibiOS/hwdef/mini-pix/hwdef.dat | 15 +- .../hwdef/omnibusf4pro/hwdef-bl.dat | 5 +- .../hwdef/omnibusf4pro/hwdef.dat | 52 +- .../hwdef/omnibusf4v6/hwdef-bl.dat | 5 +- .../hwdef/omnibusf4v6/hwdef.dat | 10 +- .../hwdef/revo-mini/hwdef-bl.dat | 5 +- .../AP_HAL_ChibiOS/hwdef/revo-mini/hwdef.dat | 8 +- .../hwdef/scripts/STM32F100xB.py | 4 +- .../hwdef/scripts/STM32F103xB.py | 4 +- .../hwdef/scripts/STM32F303xC.py | 464 +++++++++++++++ .../hwdef/scripts/STM32F405xx.py | 4 +- .../hwdef/scripts/STM32F412Rx.py | 2 +- .../hwdef/scripts/STM32F427xx.py | 4 +- .../hwdef/scripts/STM32F745xx.py | 10 +- .../hwdef/scripts/STM32F767xx.py | 8 +- .../hwdef/scripts/STM32F777xx.py | 8 +- .../hwdef/scripts/STM32H743xx.py | 8 +- .../AP_HAL_ChibiOS/hwdef/scripts/af_parse.py | 4 +- .../hwdef/scripts/chibios_hwdef.py | 546 +++++++++++++----- .../hwdef/scripts/convert_uart_order.py | 37 ++ .../hwdef/scripts/dma_resolver.py | 9 +- .../hwdef/skyviper-f412-rev1/hwdef.dat | 5 +- .../hwdef/skyviper-journey/hwdef.dat | 10 +- .../hwdef/skyviper-v2450/hwdef.dat | 7 +- .../AP_HAL_ChibiOS/hwdef/sparky2/hwdef-bl.dat | 5 +- .../AP_HAL_ChibiOS/hwdef/sparky2/hwdef.dat | 7 +- .../hwdef/speedybeef4/hwdef-bl.dat | 5 +- .../hwdef/speedybeef4/hwdef.dat | 14 +- libraries/AP_HAL_ChibiOS/stdio.cpp | 9 +- libraries/AP_HAL_ChibiOS/system.cpp | 58 +- 174 files changed, 4450 insertions(+), 1205 deletions(-) create mode 100755 libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora/defaults.parm create mode 100755 libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora/hwdef-bl.dat create mode 100755 libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora/hwdef.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CUAV-X7/defaults.parm create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CUAV-X7/hwdef-bl.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CUAV-X7/hwdef.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/MatekH743/hwdef-bl.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/MatekH743/hwdef.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/R9Pilot/hwdef-bl.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/R9Pilot/hwdef.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/SuccexF4/hwdef-bl.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/SuccexF4/hwdef.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/common/stm32f3_mcuconf.h create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/crazyflie2/hwdef-bl.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/f103-HWESC/hwdef-bl.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/f103-HWESC/hwdef.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/f103-Trigger/hwdef-bl.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/f103-Trigger/hwdef.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/f303-GPS/hwdef-bl.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/f303-GPS/hwdef.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/f303-HWESC/hwdef-bl.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/f303-HWESC/hwdef.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/f303-M10025/hwdef-bl.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/f303-M10025/hwdef.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/f303-M10070/hwdef-bl.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/f303-M10070/hwdef.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/f303-Universal/hwdef-bl.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/f303-Universal/hwdef.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/f303-periph/hwdef-bl.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/f303-periph/hwdef.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/mRoNexus/hwdef-bl.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/mRoNexus/hwdef.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F303xC.py create mode 100755 libraries/AP_HAL_ChibiOS/hwdef/scripts/convert_uart_order.py diff --git a/libraries/AP_HAL_ChibiOS/AP_HAL_ChibiOS_Namespace.h b/libraries/AP_HAL_ChibiOS/AP_HAL_ChibiOS_Namespace.h index c320b7edc1..d525fb68e6 100644 --- a/libraries/AP_HAL_ChibiOS/AP_HAL_ChibiOS_Namespace.h +++ b/libraries/AP_HAL_ChibiOS/AP_HAL_ChibiOS_Namespace.h @@ -13,7 +13,6 @@ namespace ChibiOS { class RCOutput; class Scheduler; class Semaphore; - class Semaphore_Recursive; class SPIBus; class SPIDesc; class SPIDevice; diff --git a/libraries/AP_HAL_ChibiOS/AnalogIn.cpp b/libraries/AP_HAL_ChibiOS/AnalogIn.cpp index 6b4e805d90..843c5eb94c 100644 --- a/libraries/AP_HAL_ChibiOS/AnalogIn.cpp +++ b/libraries/AP_HAL_ChibiOS/AnalogIn.cpp @@ -69,14 +69,8 @@ adcsample_t *AnalogIn::samples; uint32_t AnalogIn::sample_sum[ADC_GRP1_NUM_CHANNELS]; uint32_t AnalogIn::sample_count; -AnalogSource::AnalogSource(int16_t pin, float initial_value) : - _pin(pin), - _value(initial_value), - _value_ratiometric(initial_value), - _latest_value(initial_value), - _sum_count(0), - _sum_value(0), - _sum_ratiometric(0) +AnalogSource::AnalogSource(int16_t pin) : + _pin(pin) { } @@ -351,7 +345,7 @@ AP_HAL::AnalogSource* AnalogIn::channel(int16_t pin) { for (uint8_t j=0; jsend(it.frame, uavcan::MonotonicTime::fromUSec(AP_HAL::micros64() + 1000), 0)) { _can_tx_queue.pop(); + } else { + break; } + hal.scheduler->delay_microseconds(100); } + hal.scheduler->delay_microseconds(100); } } @@ -137,12 +141,16 @@ void SLCANRouter::can2slcan_router_trampoline(void) } chSysUnlock(); _update_event->wait(uavcan::MonotonicDuration::fromUSec(1000)); - if (_slcan_tx_queue.available()) { + while (_slcan_tx_queue.available()) { _slcan_tx_queue.peek(it); if (_slcan_if.send(it.frame, uavcan::MonotonicTime::fromUSec(AP_HAL::micros64() + 1000), 0)) { _slcan_tx_queue.pop(); + } else { + break; } + hal.scheduler->delay_microseconds(100); } + hal.scheduler->delay_microseconds(100); } } diff --git a/libraries/AP_HAL_ChibiOS/Device.cpp b/libraries/AP_HAL_ChibiOS/Device.cpp index e3d9882fa4..444f081bbb 100644 --- a/libraries/AP_HAL_ChibiOS/Device.cpp +++ b/libraries/AP_HAL_ChibiOS/Device.cpp @@ -58,10 +58,8 @@ void DeviceBus::bus_thread(void *arg) callback->next_usec += callback->period_usec; } // call it with semaphore held - if (binfo->semaphore.take(HAL_SEMAPHORE_BLOCK_FOREVER)) { - callback->cb(); - binfo->semaphore.give(); - } + WITH_SEMAPHORE(binfo->semaphore); + callback->cb(); } } @@ -106,12 +104,12 @@ AP_HAL::Device::PeriodicHandle DeviceBus::register_periodic_callback(uint32_t pe char *name = (char *)malloc(name_len); switch (hal_device->bus_type()) { case AP_HAL::Device::BUS_TYPE_I2C: - snprintf(name, name_len, "I2C:%u", + snprintf(name, name_len, "I2C%u", hal_device->bus_num()); break; case AP_HAL::Device::BUS_TYPE_SPI: - snprintf(name, name_len, "SPI:%u", + snprintf(name, name_len, "SPI%u", hal_device->bus_num()); break; default: diff --git a/libraries/AP_HAL_ChibiOS/GPIO.cpp b/libraries/AP_HAL_ChibiOS/GPIO.cpp index a9b927c942..6837ed21da 100644 --- a/libraries/AP_HAL_ChibiOS/GPIO.cpp +++ b/libraries/AP_HAL_ChibiOS/GPIO.cpp @@ -30,6 +30,7 @@ static struct gpio_entry { AP_HAL::GPIO::irq_handler_fn_t fn; // callback for GPIO interface bool is_input; uint8_t mode; + thread_reference_t thd_wait; } _gpio_tab[] = HAL_GPIO_PINS; #define NUM_PINS ARRAY_SIZE(_gpio_tab) @@ -67,8 +68,47 @@ void GPIO::init() g->enabled = g->pwm_num > pwm_count; } } +#ifdef HAL_PIN_ALT_CONFIG + setup_alt_config(); +#endif } +#ifdef HAL_PIN_ALT_CONFIG +/* + alternative config table, selected using BRD_ALT_CONFIG + */ +static const struct alt_config { + uint8_t alternate; + uint16_t mode; + ioline_t line; +} alternate_config[] HAL_PIN_ALT_CONFIG; + +/* + change pin configuration based on ALT() lines in hwdef.dat + */ +void GPIO::setup_alt_config(void) +{ + AP_BoardConfig *bc = AP::boardConfig(); + if (!bc) { + return; + } + const uint8_t alt = bc->get_alt_config(); + if (alt == 0) { + // use defaults + return; + } + for (uint8_t i=0; ipal_line, proc, mode); } -bool GPIO::_attach_interrupt(ioline_t line, palcallback_t cb, void *p, uint8_t mode) +bool GPIO::_attach_interruptI(ioline_t line, palcallback_t cb, void *p, uint8_t mode) { uint32_t chmode = 0; switch(mode) { @@ -200,11 +240,9 @@ bool GPIO::_attach_interrupt(ioline_t line, palcallback_t cb, void *p, uint8_t m break; } - osalSysLock(); palevent_t *pep = pal_lld_get_line_event(line); if (pep->cb && p != nullptr) { // the pad is already being used for a callback - osalSysUnlock(); return false; } @@ -215,11 +253,18 @@ bool GPIO::_attach_interrupt(ioline_t line, palcallback_t cb, void *p, uint8_t m palDisableLineEventI(line); palSetLineCallbackI(line, cb, p); palEnableLineEventI(line, chmode); - osalSysUnlock(); return true; } +bool GPIO::_attach_interrupt(ioline_t line, palcallback_t cb, void *p, uint8_t mode) +{ + osalSysLock(); + bool ret = _attach_interruptI(line, cb, p, mode); + osalSysUnlock(); + return ret; +} + bool GPIO::usb_connected(void) { return _usb_connected; @@ -249,14 +294,14 @@ void DigitalSource::toggle() palToggleLine(line); } -void pal_interrupt_cb(void *arg) +static void pal_interrupt_cb(void *arg) { if (arg != nullptr) { ((AP_HAL::Proc)arg)(); } } -void pal_interrupt_cb_functor(void *arg) +static void pal_interrupt_cb_functor(void *arg) { const uint32_t now = AP_HAL::micros(); @@ -270,3 +315,54 @@ void pal_interrupt_cb_functor(void *arg) } (g->fn)(g->pin_num, palReadLine(g->pal_line), now); } + +/* + handle interrupt from pin change for wait_pin() + */ +static void pal_interrupt_wait(void *arg) +{ + osalSysLockFromISR(); + struct gpio_entry *g = (gpio_entry *)arg; + if (g == nullptr || g->thd_wait == nullptr) { + osalSysUnlockFromISR(); + return; + } + osalThreadResumeI(&g->thd_wait, MSG_OK); + osalSysUnlockFromISR(); +} + +/* + block waiting for a pin to change. A timeout of 0 means wait + forever. Return true on pin change, false on timeout +*/ +bool GPIO::wait_pin(uint8_t pin, INTERRUPT_TRIGGER_TYPE mode, uint32_t timeout_us) +{ + struct gpio_entry *g = gpio_by_pin_num(pin); + if (!g) { + return false; + } + + osalSysLock(); + if (g->thd_wait) { + // only allow single waiter + osalSysUnlock(); + return false; + } + + if (!_attach_interruptI(g->pal_line, + palcallback_t(pal_interrupt_wait), + g, + mode)) { + osalSysUnlock(); + return false; + } + + msg_t msg = osalThreadSuspendTimeoutS(&g->thd_wait, TIME_US2I(timeout_us)); + _attach_interruptI(g->pal_line, + palcallback_t(nullptr), + nullptr, + mode); + osalSysUnlock(); + + return msg == MSG_OK; +} diff --git a/libraries/AP_HAL_ChibiOS/GPIO.h b/libraries/AP_HAL_ChibiOS/GPIO.h index 3aa5f941da..3e44410e3d 100644 --- a/libraries/AP_HAL_ChibiOS/GPIO.h +++ b/libraries/AP_HAL_ChibiOS/GPIO.h @@ -56,11 +56,21 @@ public: /* attach interrupt via ioline_t */ bool _attach_interrupt(ioline_t line, AP_HAL::Proc p, uint8_t mode); + /* + block waiting for a pin to change. A timeout of 0 means wait + forever. Return true on pin change, false on timeout + */ + bool wait_pin(uint8_t pin, INTERRUPT_TRIGGER_TYPE mode, uint32_t timeout_us) override; + private: bool _usb_connected; bool _ext_started; + bool _attach_interruptI(ioline_t line, palcallback_t cb, void *p, uint8_t mode); bool _attach_interrupt(ioline_t line, palcallback_t cb, void *p, uint8_t mode); +#ifdef HAL_PIN_ALT_CONFIG + void setup_alt_config(void); +#endif }; class ChibiOS::DigitalSource : public AP_HAL::DigitalSource { diff --git a/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp b/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp index c7f64dc7ff..bd40ff8e5c 100644 --- a/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp +++ b/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp @@ -159,8 +159,6 @@ thread_t* get_main_thread() static AP_HAL::HAL::Callbacks* g_callbacks; -static AP_HAL::Util::PersistentData last_persistent_data; - static void main_loop() { daemon_task = chThdGetSelfX(); @@ -200,7 +198,7 @@ static void main_loop() if (stm32_was_watchdog_reset()) { // load saved watchdog data stm32_watchdog_load((uint32_t *)&utilInstance.persistent_data, (sizeof(utilInstance.persistent_data)+3)/4); - last_persistent_data = utilInstance.persistent_data; + utilInstance.last_persistent_data = utilInstance.persistent_data; } schedulerInstance.hal_initialized(); @@ -217,21 +215,7 @@ static void main_loop() #ifndef HAL_NO_LOGGING if (hal.util->was_watchdog_reset()) { - AP::internalerror().error(AP_InternalError::error_t::watchdog_reset); - const AP_HAL::Util::PersistentData &pd = last_persistent_data; - AP::logger().WriteCritical("WDOG", "TimeUS,Task,IErr,IErrCnt,MavMsg,MavCmd,SemLine,FL,FT,FA,FP,ICSR", "QbIIHHHHHIBI", - AP_HAL::micros64(), - pd.scheduler_task, - pd.internal_errors, - pd.internal_error_count, - pd.last_mavlink_msgid, - pd.last_mavlink_cmd, - pd.semaphore_line, - pd.fault_line, - pd.fault_type, - pd.fault_addr, - pd.fault_thd_prio, - pd.fault_icsr); + INTERNAL_ERROR(AP_InternalError::error_t::watchdog_reset); } #endif // HAL_NO_LOGGING #endif // IOMCU_FW @@ -279,8 +263,8 @@ void HAL_ChibiOS::run(int argc, char * const argv[], Callbacks* callbacks) const * RTOS is active. */ -#ifdef HAL_USB_PRODUCT_ID - setup_usb_strings(); +#if HAL_USE_SERIAL_USB == TRUE + usb_initialise(); #endif #ifdef HAL_STDOUT_SERIAL diff --git a/libraries/AP_HAL_ChibiOS/I2CDevice.cpp b/libraries/AP_HAL_ChibiOS/I2CDevice.cpp index 5b3c447dc0..84cbe5ac64 100644 --- a/libraries/AP_HAL_ChibiOS/I2CDevice.cpp +++ b/libraries/AP_HAL_ChibiOS/I2CDevice.cpp @@ -126,7 +126,7 @@ I2CDeviceManager::I2CDeviceManager(void) drop the speed to be the minimum speed requested */ businfo[i].busclock = HAL_I2C_MAX_CLOCK; -#if defined(STM32F7) +#if defined(STM32F7) || defined(STM32F3) if (businfo[i].busclock <= 100000) { businfo[i].i2ccfg.timingr = HAL_I2C_F7_100_TIMINGR; businfo[i].busclock = 100000; @@ -166,7 +166,7 @@ I2CDevice::I2CDevice(uint8_t busnum, uint8_t address, uint32_t bus_clock, bool u asprintf(&pname, "I2C:%u:%02x", (unsigned)busnum, (unsigned)address); if (bus_clock < bus.busclock) { -#if defined(STM32F7) || defined(STM32H7) +#if defined(STM32F7) || defined(STM32H7) || defined(STM32F3) if (bus_clock <= 100000) { bus.i2ccfg.timingr = HAL_I2C_F7_100_TIMINGR; bus.busclock = 100000; @@ -213,7 +213,7 @@ bool I2CDevice::transfer(const uint8_t *send, uint32_t send_len, return false; } -#if defined(STM32F7) || defined(STM32H7) +#if defined(STM32F7) || defined(STM32H7) || defined(STM32F3) if (_use_smbus) { bus.i2ccfg.cr1 |= I2C_CR1_SMBHEN; } else { @@ -294,7 +294,7 @@ bool I2CDevice::_transfer(const uint8_t *send, uint32_t send_len, bus.dma_handle->unlock(); if (I2CD[bus.busnum].i2c->errors & I2C_ISR_LIMIT) { - AP::internalerror().error(AP_InternalError::error_t::i2c_isr); + INTERNAL_ERROR(AP_InternalError::error_t::i2c_isr); break; } diff --git a/libraries/AP_HAL_ChibiOS/RCInput.cpp b/libraries/AP_HAL_ChibiOS/RCInput.cpp index fda011c395..a12e60730c 100644 --- a/libraries/AP_HAL_ChibiOS/RCInput.cpp +++ b/libraries/AP_HAL_ChibiOS/RCInput.cpp @@ -179,6 +179,7 @@ void RCInput::_timer_tick(void) _num_channels = rcprot.num_channels(); _num_channels = MIN(_num_channels, RC_INPUT_MAX_CHANNELS); rcprot.read(_rc_values, _num_channels); + _rssi = rcprot.get_RSSI(); #ifndef HAL_NO_UARTDRIVER rc_protocol = rcprot.protocol_name(); #endif @@ -206,6 +207,7 @@ void RCInput::_timer_tick(void) _rcin_timestamp_last_signal = last_iomcu_us; #ifndef HAL_NO_UARTDRIVER rc_protocol = iomcu.get_rc_protocol(); + _rssi = iomcu.get_RSSI(); #endif } } @@ -214,7 +216,7 @@ void RCInput::_timer_tick(void) #ifndef HAL_NO_UARTDRIVER if (rc_protocol && rc_protocol != last_protocol) { last_protocol = rc_protocol; - gcs().send_text(MAV_SEVERITY_DEBUG, "RCInput: decoding %s", last_protocol); + GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "RCInput: decoding %s", last_protocol); } #endif diff --git a/libraries/AP_HAL_ChibiOS/RCInput.h b/libraries/AP_HAL_ChibiOS/RCInput.h index 7f3de7d419..1751ea842d 100644 --- a/libraries/AP_HAL_ChibiOS/RCInput.h +++ b/libraries/AP_HAL_ChibiOS/RCInput.h @@ -63,7 +63,7 @@ private: uint64_t _last_read; uint8_t _num_channels; - HAL_Semaphore_Recursive rcin_mutex; + Semaphore rcin_mutex; int16_t _rssi = -1; uint32_t _rcin_timestamp_last_signal; bool _init; diff --git a/libraries/AP_HAL_ChibiOS/SPIDevice.cpp b/libraries/AP_HAL_ChibiOS/SPIDevice.cpp index bbe0eb3360..bf50ef80e1 100644 --- a/libraries/AP_HAL_ChibiOS/SPIDevice.cpp +++ b/libraries/AP_HAL_ChibiOS/SPIDevice.cpp @@ -208,7 +208,7 @@ bool SPIDevice::do_transfer(const uint8_t *send, uint8_t *recv, uint32_t len) if (msg == MSG_TIMEOUT) { ret = false; if (!hal.scheduler->in_expected_delay()) { - AP::internalerror().error(AP_InternalError::error_t::spi_fail); + INTERNAL_ERROR(AP_InternalError::error_t::spi_fail); } spiAbort(spi_devices[device_desc.bus].driver); } @@ -222,7 +222,7 @@ bool SPIDevice::clock_pulse(uint32_t n) { if (!cs_forced) { //special mode to init sdcard without cs asserted - bus.semaphore.take(HAL_SEMAPHORE_BLOCK_FOREVER); + bus.semaphore.take_blocking(); acquire_bus(true, true); spiIgnore(spi_devices[device_desc.bus].driver, n); acquire_bus(false, true); diff --git a/libraries/AP_HAL_ChibiOS/Scheduler.cpp b/libraries/AP_HAL_ChibiOS/Scheduler.cpp index 5c1c5c2299..1c06de7849 100644 --- a/libraries/AP_HAL_ChibiOS/Scheduler.cpp +++ b/libraries/AP_HAL_ChibiOS/Scheduler.cpp @@ -307,7 +307,7 @@ void Scheduler::_run_timers() void Scheduler::_timer_thread(void *arg) { Scheduler *sched = (Scheduler *)arg; - chRegSetThreadName("apm_timer"); + chRegSetThreadName("timer"); while (!sched->_hal_initialized) { sched->delay_microseconds(1000); @@ -333,6 +333,10 @@ void Scheduler::_timer_thread(void *arg) */ bool Scheduler::in_expected_delay(void) const { + if (!_initialized) { + // until setup() is complete we expect delays + return true; + } if (expect_delay_start != 0) { uint32_t now = AP_HAL::millis(); if (now - expect_delay_start <= expect_delay_length) { @@ -346,12 +350,15 @@ bool Scheduler::in_expected_delay(void) const void Scheduler::_monitor_thread(void *arg) { Scheduler *sched = (Scheduler *)arg; - chRegSetThreadName("apm_monitor"); + chRegSetThreadName("monitor"); while (!sched->_initialized) { sched->delay(100); } bool using_watchdog = AP_BoardConfig::watchdog_enabled(); +#ifndef HAL_NO_LOGGING + uint8_t log_wd_counter = 0; +#endif while (true) { sched->delay(100); @@ -364,22 +371,50 @@ void Scheduler::_monitor_thread(void *arg) // the main loop has been stuck for at least // 200ms. Starting logging the main loop state const AP_HAL::Util::PersistentData &pd = hal.util->persistent_data; - AP::logger().Write("MON", "TimeUS,LDelay,Task,IErr,IErrCnt,MavMsg,MavCmd,SemLine,SPICnt,I2CCnt", "QIbIIHHHII", - AP_HAL::micros64(), - loop_delay, - pd.scheduler_task, - pd.internal_errors, - pd.internal_error_count, - pd.last_mavlink_msgid, - pd.last_mavlink_cmd, - pd.semaphore_line, - pd.spi_count, - pd.i2c_count); + if (AP_Logger::get_singleton()) { + AP::logger().Write("MON", "TimeUS,LDelay,Task,IErr,IErrCnt,IErrLn,MavMsg,MavCmd,SemLine,SPICnt,I2CCnt", "QIbIHHHHHII", + AP_HAL::micros64(), + loop_delay, + pd.scheduler_task, + pd.internal_errors, + pd.internal_error_count, + pd.internal_error_last_line, + pd.last_mavlink_msgid, + pd.last_mavlink_cmd, + pd.semaphore_line, + pd.spi_count, + pd.i2c_count); + } } if (loop_delay >= 500) { // at 500ms we declare an internal error - AP::internalerror().error(AP_InternalError::error_t::main_loop_stuck); + INTERNAL_ERROR(AP_InternalError::error_t::main_loop_stuck); } + +#ifndef HAL_NO_LOGGING + if (log_wd_counter++ == 10 && hal.util->was_watchdog_reset()) { + log_wd_counter = 0; + // log watchdog message once a second + const AP_HAL::Util::PersistentData &pd = hal.util->last_persistent_data; + AP::logger().WriteCritical("WDOG", "TimeUS,Tsk,IE,IEC,IEL,MvMsg,MvCmd,SmLn,FL,FT,FA,FP,ICSR,LR,TN", "QbIHHHHHHHIBIIn", + AP_HAL::micros64(), + pd.scheduler_task, + pd.internal_errors, + pd.internal_error_count, + pd.internal_error_last_line, + pd.last_mavlink_msgid, + pd.last_mavlink_cmd, + pd.semaphore_line, + pd.fault_line, + pd.fault_type, + pd.fault_addr, + pd.fault_thd_prio, + pd.fault_icsr, + pd.fault_lr, + pd.thread_name4); + } +#endif // HAL_NO_LOGGING + } } #endif // HAL_NO_MONITOR_THREAD @@ -387,7 +422,7 @@ void Scheduler::_monitor_thread(void *arg) void Scheduler::_rcin_thread(void *arg) { Scheduler *sched = (Scheduler *)arg; - chRegSetThreadName("apm_rcin"); + chRegSetThreadName("rcin"); while (!sched->_hal_initialized) { sched->delay_microseconds(20000); } @@ -421,7 +456,7 @@ void Scheduler::_run_io(void) void Scheduler::_io_thread(void* arg) { Scheduler *sched = (Scheduler *)arg; - chRegSetThreadName("apm_io"); + chRegSetThreadName("io"); while (!sched->_hal_initialized) { sched->delay_microseconds(1000); } @@ -447,7 +482,7 @@ void Scheduler::_io_thread(void* arg) void Scheduler::_storage_thread(void* arg) { Scheduler *sched = (Scheduler *)arg; - chRegSetThreadName("apm_storage"); + chRegSetThreadName("storage"); while (!sched->_hal_initialized) { sched->delay_microseconds(10000); } @@ -549,7 +584,7 @@ bool Scheduler::thread_create(AP_HAL::MemberProc proc, const char *name, uint32_ be used to prevent watchdog reset during expected long delays A value of zero cancels the previous expected delay */ -void Scheduler::expect_delay_ms(uint32_t ms) +void Scheduler::_expect_delay_ms(uint32_t ms) { if (!in_main_thread()) { // only for main thread @@ -559,6 +594,8 @@ void Scheduler::expect_delay_ms(uint32_t ms) // pat once immediately watchdog_pat(); + WITH_SEMAPHORE(expect_delay_sem); + if (ms == 0) { if (expect_delay_nesting > 0) { expect_delay_nesting--; @@ -584,6 +621,18 @@ void Scheduler::expect_delay_ms(uint32_t ms) } } +/* + this is _expect_delay_ms() with check that we are in the main thread + */ +void Scheduler::expect_delay_ms(uint32_t ms) +{ + if (!in_main_thread()) { + // only for main thread + return; + } + _expect_delay_ms(ms); +} + // pat the watchdog void Scheduler::watchdog_pat(void) { diff --git a/libraries/AP_HAL_ChibiOS/Scheduler.h b/libraries/AP_HAL_ChibiOS/Scheduler.h index 5a98860470..129e7f9425 100644 --- a/libraries/AP_HAL_ChibiOS/Scheduler.h +++ b/libraries/AP_HAL_ChibiOS/Scheduler.h @@ -103,6 +103,7 @@ public: be used to prevent watchdog reset during expected long delays A value of zero cancels the previous expected delay */ + void _expect_delay_ms(uint32_t ms); void expect_delay_ms(uint32_t ms) override; /* @@ -140,6 +141,7 @@ private: uint32_t expect_delay_start; uint32_t expect_delay_length; uint32_t expect_delay_nesting; + HAL_Semaphore expect_delay_sem; AP_HAL::MemberProc _timer_proc[CHIBIOS_SCHEDULER_MAX_TIMER_PROCS]; uint8_t _num_timer_procs; diff --git a/libraries/AP_HAL_ChibiOS/Semaphores.cpp b/libraries/AP_HAL_ChibiOS/Semaphores.cpp index 06218b6e16..e09e641239 100644 --- a/libraries/AP_HAL_ChibiOS/Semaphores.cpp +++ b/libraries/AP_HAL_ChibiOS/Semaphores.cpp @@ -76,77 +76,4 @@ void Semaphore::assert_owner(void) osalDbgAssert(check_owner(), "owner"); } -// constructor -Semaphore_Recursive::Semaphore_Recursive() - : Semaphore(), count(0) -{} - - -bool Semaphore_Recursive::give() -{ - chSysLock(); - mutex_t *mtx = (mutex_t *)_lock; - osalDbgAssert(count>0, "recursive semaphore"); - if (count != 0) { - count--; - if (count == 0) { - // this thread is giving it up - chMtxUnlockS(mtx); - // we may need to re-schedule if our priority was increased due to - // priority inheritance - chSchRescheduleS(); - } - } - chSysUnlock(); - return true; -} - -bool Semaphore_Recursive::take(uint32_t timeout_ms) -{ - // most common case is we can get the lock immediately - if (Semaphore::take_nonblocking()) { - count=1; - return true; - } - - // check for case where we hold it already - chSysLock(); - mutex_t *mtx = (mutex_t *)_lock; - if (mtx->owner == chThdGetSelfX()) { - count++; - chSysUnlock(); - return true; - } - chSysUnlock(); - if (Semaphore::take(timeout_ms)) { - count = 1; - return true; - } - return false; -} - -bool Semaphore_Recursive::take_nonblocking(void) -{ - // most common case is we can get the lock immediately - if (Semaphore::take_nonblocking()) { - count=1; - return true; - } - - // check for case where we hold it already - chSysLock(); - mutex_t *mtx = (mutex_t *)_lock; - if (mtx->owner == chThdGetSelfX()) { - count++; - chSysUnlock(); - return true; - } - chSysUnlock(); - if (Semaphore::take_nonblocking()) { - count = 1; - return true; - } - return false; -} - #endif // CH_CFG_USE_MUTEXES diff --git a/libraries/AP_HAL_ChibiOS/Semaphores.h b/libraries/AP_HAL_ChibiOS/Semaphores.h index 9ea8f93d0c..484570d086 100644 --- a/libraries/AP_HAL_ChibiOS/Semaphores.h +++ b/libraries/AP_HAL_ChibiOS/Semaphores.h @@ -34,18 +34,6 @@ public: void assert_owner(void); protected: // to avoid polluting the global namespace with the 'ch' variable, - // we declare the lock as a uint64_t, and cast inside the cpp file - uint64_t _lock[2]; -}; - -// a recursive semaphore, allowing for a thread to take it more than -// once. It must be released the same number of times it is taken -class ChibiOS::Semaphore_Recursive : public ChibiOS::Semaphore { -public: - Semaphore_Recursive(); - bool give() override; - bool take(uint32_t timeout_ms) override; - bool take_nonblocking() override; -private: - uint32_t count; + // we declare the lock as a uint32_t array, and cast inside the cpp file + uint32_t _lock[5]; }; diff --git a/libraries/AP_HAL_ChibiOS/Storage.cpp b/libraries/AP_HAL_ChibiOS/Storage.cpp index fefe0c40dc..2f409b4949 100644 --- a/libraries/AP_HAL_ChibiOS/Storage.cpp +++ b/libraries/AP_HAL_ChibiOS/Storage.cpp @@ -340,9 +340,19 @@ bool Storage::_flash_erase_sector(uint8_t sector) // erasing a page can take long enough that USB may not initialise properly if it happens // while the host is connecting. Only do a flash erase if we have been up for more than 4s for (uint8_t i=0; i_expect_delay_ms(1000); if (hal.flash->erasepage(_flash_page+sector)) { + sched->_expect_delay_ms(0); return true; } + sched->_expect_delay_ms(0); hal.scheduler->delay(1); } return false; diff --git a/libraries/AP_HAL_ChibiOS/UARTDriver.cpp b/libraries/AP_HAL_ChibiOS/UARTDriver.cpp index 3d5489d0e0..430e70a0bc 100644 --- a/libraries/AP_HAL_ChibiOS/UARTDriver.cpp +++ b/libraries/AP_HAL_ChibiOS/UARTDriver.cpp @@ -48,10 +48,13 @@ UARTDriver *UARTDriver::uart_drivers[UART_MAX_DRIVERS]; // event used to wake up waiting thread. This event number is for // caller threads -#define EVT_DATA EVENT_MASK(0) +#define EVT_DATA EVENT_MASK(10) // event for parity error -#define EVT_PARITY EVENT_MASK(1) +#define EVT_PARITY EVENT_MASK(11) + +// event for transmit end for half-duplex +#define EVT_TRANSMIT_END EVENT_MASK(12) #ifndef HAL_UART_MIN_TX_SIZE #define HAL_UART_MIN_TX_SIZE 1024 @@ -98,8 +101,9 @@ void UARTDriver::uart_thread(void* arg) if (uart_drivers[i] == nullptr) { continue; } - if ((mask & EVENT_MASK(i)) && - uart_drivers[i]->_initialised) { + if (uart_drivers[i]->_initialised && + (mask & EVENT_MASK(i) || + (uart_drivers[i]->hd_tx_active && (mask & EVT_TRANSMIT_END)))) { uart_drivers[i]->_timer_tick(); } } @@ -209,14 +213,25 @@ void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS) } #ifndef HAL_UART_NODMA - if (rx_bounce_buf == nullptr) { - rx_bounce_buf = (uint8_t *)hal.util->malloc_type(RX_BOUNCE_BUFSIZE, AP_HAL::Util::MEM_DMA_SAFE); + if (!half_duplex && !(_last_options & OPTION_NODMA_RX)) { + if (rx_bounce_buf[0] == nullptr && sdef.dma_rx) { + rx_bounce_buf[0] = (uint8_t *)hal.util->malloc_type(RX_BOUNCE_BUFSIZE, AP_HAL::Util::MEM_DMA_SAFE); + } + if (rx_bounce_buf[1] == nullptr && sdef.dma_rx) { + rx_bounce_buf[1] = (uint8_t *)hal.util->malloc_type(RX_BOUNCE_BUFSIZE, AP_HAL::Util::MEM_DMA_SAFE); + } } - if (tx_bounce_buf == nullptr) { + if (tx_bounce_buf == nullptr && sdef.dma_tx && !(_last_options & OPTION_NODMA_TX)) { tx_bounce_buf = (uint8_t *)hal.util->malloc_type(TX_BOUNCE_BUFSIZE, AP_HAL::Util::MEM_DMA_SAFE); chVTObjectInit(&tx_timeout); tx_bounce_buf_ready = true; } + if (half_duplex) { + rx_dma_enabled = tx_dma_enabled = false; + } else { + rx_dma_enabled = rx_bounce_buf[0] != nullptr && rx_bounce_buf[1] != nullptr; + tx_dma_enabled = tx_bounce_buf != nullptr; + } #endif /* @@ -241,21 +256,7 @@ void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS) */ if (!_device_initialised) { if ((SerialUSBDriver*)sdef.serial == &SDU1) { - sduObjectInit(&SDU1); - sduStart(&SDU1, &serusbcfg1); -#if HAL_HAVE_DUAL_USB_CDC - sduObjectInit(&SDU2); - sduStart(&SDU2, &serusbcfg2); -#endif - /* - * Activates the USB driver and then the USB bus pull-up on D+. - * Note, a delay is inserted in order to not have to disconnect the cable - * after a reset. - */ - usbDisconnectBus(serusbcfg1.usbp); - hal.scheduler->delay_microseconds(1500); - usbStart(serusbcfg1.usbp, &usbcfg); - usbConnectBus(serusbcfg1.usbp); + usb_initialise(); } _device_initialised = true; } @@ -265,9 +266,9 @@ void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS) if (_baudrate != 0) { #ifndef HAL_UART_NODMA bool was_initialised = _device_initialised; - //setup Rx DMA - if(!_device_initialised) { - if(sdef.dma_rx) { + // setup Rx DMA + if (!_device_initialised) { + if (rx_dma_enabled) { osalDbgAssert(rxdma == nullptr, "double DMA allocation"); chSysLock(); rxdma = dmaStreamAllocI(sdef.dma_rx_stream_id, @@ -276,7 +277,7 @@ void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS) (void *)this); osalDbgAssert(rxdma, "stream alloc failed"); chSysUnlock(); -#if defined(STM32F7) || defined(STM32H7) +#if defined(STM32F7) || defined(STM32H7) || defined(STM32F3) dmaStreamSetPeripheral(rxdma, &((SerialDriver*)sdef.serial)->usart->RDR); #else dmaStreamSetPeripheral(rxdma, &((SerialDriver*)sdef.serial)->usart->DR); @@ -285,7 +286,7 @@ void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS) dmaSetRequestSource(rxdma, sdef.dma_rx_channel_id); #endif } - if (sdef.dma_tx) { + if (tx_dma_enabled) { // we only allow for sharing of the TX DMA channel, not the RX // DMA channel, as the RX side is active all the time, so // cannot be shared @@ -300,20 +301,17 @@ void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS) sercfg.speed = _baudrate; // start with options from set_options() - sercfg.cr1 = 0; + sercfg.cr1 = _cr1_options; sercfg.cr2 = _cr2_options; sercfg.cr3 = _cr3_options; #ifndef HAL_UART_NODMA - if (!sdef.dma_tx && !sdef.dma_rx) { - } else { - if (sdef.dma_rx) { - sercfg.cr1 |= USART_CR1_IDLEIE; - sercfg.cr3 |= USART_CR3_DMAR; - } - if (sdef.dma_tx) { - sercfg.cr3 |= USART_CR3_DMAT; - } + if (rx_dma_enabled) { + sercfg.cr1 |= USART_CR1_IDLEIE; + sercfg.cr3 |= USART_CR3_DMAR; + } + if (tx_dma_enabled) { + sercfg.cr3 |= USART_CR3_DMAT; } sercfg.irq_cb = rx_irq_cb; #endif // HAL_UART_NODMA @@ -323,20 +321,14 @@ void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS) sdStart((SerialDriver*)sdef.serial, &sercfg); #ifndef HAL_UART_NODMA - if(sdef.dma_rx) { + if (rx_dma_enabled) { //Configure serial driver to skip handling RX packets //because we will handle them via DMA ((SerialDriver*)sdef.serial)->usart->CR1 &= ~USART_CR1_RXNEIE; - //Start DMA - if(!was_initialised) { - uint32_t dmamode = STM32_DMA_CR_DMEIE | STM32_DMA_CR_TEIE; - dmamode |= STM32_DMA_CR_CHSEL(sdef.dma_rx_channel_id); - dmamode |= STM32_DMA_CR_PL(0); - dmaStreamSetMemory0(rxdma, rx_bounce_buf); - dmaStreamSetTransactionSize(rxdma, RX_BOUNCE_BUFSIZE); - dmaStreamSetMode(rxdma, dmamode | STM32_DMA_CR_DIR_P2M | - STM32_DMA_CR_MINC | STM32_DMA_CR_TCIE); - dmaStreamEnable(rxdma); + // Start DMA + if (!was_initialised) { + dmaStreamDisable(rxdma); + dma_rx_enable(); } } #endif // HAL_UART_NODMA @@ -374,7 +366,7 @@ void UARTDriver::dma_tx_allocate(Shared_DMA *ctx) (void *)this); osalDbgAssert(txdma, "stream alloc failed"); chSysUnlock(); -#if defined(STM32F7) || defined(STM32H7) +#if defined(STM32F7) || defined(STM32H7) || defined(STM32F3) dmaStreamSetPeripheral(txdma, &((SerialDriver*)sdef.serial)->usart->TDR); #else dmaStreamSetPeripheral(txdma, &((SerialDriver*)sdef.serial)->usart->DR); @@ -385,6 +377,21 @@ void UARTDriver::dma_tx_allocate(Shared_DMA *ctx) #endif // HAL_USE_SERIAL } +#ifndef HAL_UART_NODMA +void UARTDriver::dma_rx_enable(void) +{ + uint32_t dmamode = STM32_DMA_CR_DMEIE | STM32_DMA_CR_TEIE; + dmamode |= STM32_DMA_CR_CHSEL(sdef.dma_rx_channel_id); + dmamode |= STM32_DMA_CR_PL(0); + rx_bounce_idx ^= 1; + dmaStreamSetMemory0(rxdma, rx_bounce_buf[rx_bounce_idx]); + dmaStreamSetTransactionSize(rxdma, RX_BOUNCE_BUFSIZE); + dmaStreamSetMode(rxdma, dmamode | STM32_DMA_CR_DIR_P2M | + STM32_DMA_CR_MINC | STM32_DMA_CR_TCIE); + dmaStreamEnable(rxdma); +} +#endif + void UARTDriver::dma_tx_deallocate(Shared_DMA *ctx) { chSysLock(); @@ -394,7 +401,7 @@ void UARTDriver::dma_tx_deallocate(Shared_DMA *ctx) } /* - DMA transmit complettion interrupt handler + DMA transmit completion interrupt handler */ void UARTDriver::tx_complete(void* self, uint32_t flags) { @@ -416,16 +423,21 @@ void UARTDriver::tx_complete(void* self, uint32_t flags) } +#ifndef HAL_UART_NODMA void UARTDriver::rx_irq_cb(void* self) { #if HAL_USE_SERIAL == TRUE UARTDriver* uart_drv = (UARTDriver*)self; - if (!uart_drv->sdef.dma_rx) { + if (!uart_drv->rx_dma_enabled) { return; } #if defined(STM32F7) || defined(STM32H7) //disable dma, triggering DMA transfer complete interrupt uart_drv->rxdma->stream->CR &= ~STM32_DMA_CR_EN; +#elif defined(STM32F3) + //disable dma, triggering DMA transfer complete interrupt + dmaStreamDisable(uart_drv->rxdma); + uart_drv->rxdma->channel->CCR &= ~STM32_DMA_CR_EN; #else volatile uint16_t sr = ((SerialDriver*)(uart_drv->sdef.serial))->usart->SR; if(sr & USART_SR_IDLE) { @@ -437,37 +449,37 @@ void UARTDriver::rx_irq_cb(void* self) #endif // STM32F7 #endif // HAL_USE_SERIAL } +#endif +/* + handle a RX DMA full interrupt + */ void UARTDriver::rxbuff_full_irq(void* self, uint32_t flags) { #if HAL_USE_SERIAL == TRUE UARTDriver* uart_drv = (UARTDriver*)self; - if (uart_drv->_lock_rx_in_timer_tick) { + if (!uart_drv->rx_dma_enabled) { return; } - if (!uart_drv->sdef.dma_rx) { - return; - } - stm32_cacheBufferInvalidate(uart_drv->rx_bounce_buf, RX_BOUNCE_BUFSIZE); - uint8_t len = RX_BOUNCE_BUFSIZE - dmaStreamGetTransactionSize(uart_drv->rxdma); + uint16_t len = RX_BOUNCE_BUFSIZE - dmaStreamGetTransactionSize(uart_drv->rxdma); + const uint8_t bounce_idx = uart_drv->rx_bounce_idx; + + // restart the DMA transfers immediately. This switches to the + // other bounce buffer. We restart the DMA before we copy the data + // out to minimise the time with DMA disabled, which allows us to + // handle much higher receiver baudrates + dmaStreamDisable(uart_drv->rxdma); + uart_drv->dma_rx_enable(); + if (len > 0) { - if (uart_drv->half_duplex) { - uint32_t now = AP_HAL::micros(); - if (now - uart_drv->hd_write_us < uart_drv->hd_read_delay_us) { - len = 0; - } - } - - stm32_cacheBufferInvalidate(uart_drv->rx_bounce_buf, len); - uart_drv->_readbuf.write(uart_drv->rx_bounce_buf, len); - + /* + we have data to copy out + */ + stm32_cacheBufferInvalidate(uart_drv->rx_bounce_buf[bounce_idx], len); + uart_drv->_readbuf.write(uart_drv->rx_bounce_buf[bounce_idx], len); uart_drv->receive_timestamp_update(); } - //restart the DMA transfers - dmaStreamSetMemory0(uart_drv->rxdma, uart_drv->rx_bounce_buf); - dmaStreamSetTransactionSize(uart_drv->rxdma, RX_BOUNCE_BUFSIZE); - dmaStreamEnable(uart_drv->rxdma); if (uart_drv->_wait.thread_ctx && uart_drv->_readbuf.available() >= uart_drv->_wait.n) { chSysLockFromISR(); chEvtSignalI(uart_drv->_wait.thread_ctx, EVT_DATA); @@ -590,12 +602,13 @@ int16_t UARTDriver::read_locked(uint32_t key) return byte; } -/* Empty implementations of Print virtual methods */ +/* write one byte to the port */ size_t UARTDriver::write(uint8_t c) { - if (lock_write_key != 0 || !_write_mutex.take_nonblocking()) { + if (lock_write_key != 0) { return 0; } + _write_mutex.take_blocking(); if (!_initialised) { _write_mutex.give(); @@ -607,7 +620,10 @@ size_t UARTDriver::write(uint8_t c) _write_mutex.give(); return 0; } + // release the semaphore while sleeping + _write_mutex.give(); hal.scheduler->delay(1); + _write_mutex.take_blocking(); } size_t ret = _writebuf.write(&c, 1); if (unbuffered_writes) { @@ -617,25 +633,17 @@ size_t UARTDriver::write(uint8_t c) return ret; } +/* write a block of bytes to the port */ size_t UARTDriver::write(const uint8_t *buffer, size_t size) { if (!_initialised || lock_write_key != 0) { return 0; } - if (_blocking_writes && unbuffered_writes) { - _write_mutex.take_blocking(); - } else { - if (!_write_mutex.take_nonblocking()) { - return 0; - } - } - if (_blocking_writes && !unbuffered_writes) { /* use the per-byte delay loop in write() above for blocking writes */ - _write_mutex.give(); size_t ret = 0; while (size--) { if (write(*buffer++) != 1) break; @@ -644,11 +652,12 @@ size_t UARTDriver::write(const uint8_t *buffer, size_t size) return ret; } + WITH_SEMAPHORE(_write_mutex); + size_t ret = _writebuf.write(buffer, size); if (unbuffered_writes) { write_pending_bytes(); } - _write_mutex.give(); return ret; } @@ -679,14 +688,8 @@ size_t UARTDriver::write_locked(const uint8_t *buffer, size_t size, uint32_t key if (lock_write_key != 0 && key != lock_write_key) { return 0; } - if (!_write_mutex.take_nonblocking()) { - return 0; - } - size_t ret = _writebuf.write(buffer, size); - - _write_mutex.give(); - - return ret; + WITH_SEMAPHORE(_write_mutex); + return _writebuf.write(buffer, size); } /* @@ -717,7 +720,12 @@ void UARTDriver::check_dma_tx_completion(void) { chSysLock(); if (!tx_bounce_buf_ready) { - if (!(txdma->stream->CR & STM32_DMA_CR_EN)) { +#if defined(STM32F3) + bool enabled = (txdma->channel->CCR & STM32_DMA_CR_EN); +#else + bool enabled = (txdma->stream->CR & STM32_DMA_CR_EN); +#endif + if (!enabled) { if (dmaStreamGetTransactionSize(txdma) == 0) { tx_bounce_buf_ready = true; _last_write_completed_us = AP_HAL::micros(); @@ -751,6 +759,7 @@ void UARTDriver::handle_tx_timeout(void *arg) */ void UARTDriver::write_pending_bytes_DMA(uint32_t n) { + WITH_SEMAPHORE(_write_mutex); check_dma_tx_completion(); if (!tx_bounce_buf_ready) { @@ -781,10 +790,7 @@ void UARTDriver::write_pending_bytes_DMA(uint32_t n) } } - if (half_duplex) { - half_duplex_setup_delay(tx_len); - } - + dmaStreamDisable(txdma); tx_bounce_buf_ready = false; osalDbgAssert(txdma != nullptr, "UART TX DMA allocation failed"); stm32_cacheBufferFlush(tx_bounce_buf, tx_len); @@ -806,9 +812,15 @@ void UARTDriver::write_pending_bytes_DMA(uint32_t n) */ void UARTDriver::write_pending_bytes_NODMA(uint32_t n) { + WITH_SEMAPHORE(_write_mutex); + ByteBuffer::IoVec vec[2]; uint16_t nwritten = 0; + if (half_duplex && n > 1) { + half_duplex_setup_tx(); + } + const auto n_vec = _writebuf.peekiovec(vec, n); for (int i = 0; i < n_vec; i++) { int ret = -1; @@ -838,10 +850,6 @@ void UARTDriver::write_pending_bytes_NODMA(uint32_t n) } _total_written += nwritten; - - if (half_duplex) { - half_duplex_setup_delay(nwritten); - } } /* @@ -852,7 +860,7 @@ void UARTDriver::write_pending_bytes(void) uint32_t n; #ifndef HAL_UART_NODMA - if (sdef.dma_tx) { + if (tx_dma_enabled) { check_dma_tx_completion(); } #endif @@ -864,7 +872,7 @@ void UARTDriver::write_pending_bytes(void) } #ifndef HAL_UART_NODMA - if (sdef.dma_tx) { + if (tx_dma_enabled) { write_pending_bytes_DMA(n); } else #endif @@ -878,7 +886,7 @@ void UARTDriver::write_pending_bytes(void) _first_write_started_us = AP_HAL::micros(); } #ifndef HAL_UART_NODMA - if (sdef.dma_tx) { + if (tx_dma_enabled) { // when we are using DMA we have a reliable indication that a write // has completed from the DMA completion interrupt if (_last_write_completed_us != 0) { @@ -909,15 +917,24 @@ void UARTDriver::write_pending_bytes(void) } /* - setup a delay after writing bytes to a half duplex UART to prevent - read-back of the same bytes that we wrote. half-duplex protocols - tend to have quite loose timing, which makes this possible + setup for half duplex tramsmit. To cope with uarts that have level + shifters and pullups we need to play a trick where we temporarily + disable half-duplex while transmitting. That disables the receive + part of the uart on the pin which allows the transmit side to + correctly setup the idle voltage before the transmit starts. */ -void UARTDriver::half_duplex_setup_delay(uint16_t len) +void UARTDriver::half_duplex_setup_tx(void) { - const uint16_t pad_us = 1000; - hd_write_us = AP_HAL::micros(); - hd_read_delay_us = ((1000000UL * len * 10) / _baudrate) + pad_us; +#ifdef HAVE_USB_SERIAL + if (!hd_tx_active) { + chEvtGetAndClearFlags(&hd_listener); + hd_tx_active = true; + SerialDriver *sd = (SerialDriver*)(sdef.serial); + sdStop(sd); + sercfg.cr3 &= ~USART_CR3_HDSEL; + sdStart(sd, &sercfg); + } +#endif } @@ -930,30 +947,48 @@ void UARTDriver::_timer_tick(void) { if (!_initialised) return; +#ifdef HAVE_USB_SERIAL + if (hd_tx_active && (chEvtGetAndClearFlags(&hd_listener) & CHN_OUTPUT_EMPTY) != 0) { + /* + half-duplex transmit has finished. We now re-enable the + HDSEL bit for receive + */ + SerialDriver *sd = (SerialDriver*)(sdef.serial); + sdStop(sd); + sercfg.cr3 |= USART_CR3_HDSEL; + sdStart(sd, &sercfg); + hd_tx_active = false; + } +#endif + #ifndef HAL_UART_NODMA - if (sdef.dma_rx && rxdma) { - _lock_rx_in_timer_tick = true; + if (rx_dma_enabled && rxdma) { + chSysLock(); //Check if DMA is enabled //if not, it might be because the DMA interrupt was silenced //let's handle that here so that we can continue receiving - if (!(rxdma->stream->CR & STM32_DMA_CR_EN)) { +#if defined(STM32F3) + bool enabled = (rxdma->channel->CCR & STM32_DMA_CR_EN); +#else + bool enabled = (rxdma->stream->CR & STM32_DMA_CR_EN); +#endif + if (!enabled) { uint8_t len = RX_BOUNCE_BUFSIZE - dmaStreamGetTransactionSize(rxdma); if (len != 0) { - stm32_cacheBufferInvalidate(rx_bounce_buf, len); - _readbuf.write(rx_bounce_buf, len); + stm32_cacheBufferInvalidate(rx_bounce_buf[rx_bounce_idx], len); + _readbuf.write(rx_bounce_buf[rx_bounce_idx], len); receive_timestamp_update(); if (_rts_is_active) { update_rts_line(); } } - //DMA disabled by idle interrupt never got a chance to be handled - //we will enable it here - dmaStreamSetMemory0(rxdma, rx_bounce_buf); - dmaStreamSetTransactionSize(rxdma, RX_BOUNCE_BUFSIZE); - dmaStreamEnable(rxdma); + // DMA disabled by idle interrupt never got a chance to be handled + // we will enable it here + dmaStreamDisable(rxdma); + dma_rx_enable(); } - _lock_rx_in_timer_tick = false; + chSysUnlock(); } #endif @@ -973,7 +1008,7 @@ void UARTDriver::_timer_tick(void) _in_timer = true; #ifndef HAL_UART_NODMA - if (!sdef.dma_rx) + if (!rx_dma_enabled) #endif { // try to fill the read buffer @@ -1001,15 +1036,10 @@ void UARTDriver::_timer_tick(void) ret = -1; } #endif - if (half_duplex) { - uint32_t now = AP_HAL::micros(); - if (now - hd_write_us < hd_read_delay_us) { - break; - } + if (!hd_tx_active) { + _readbuf.commit((unsigned)ret); + receive_timestamp_update(); } - _readbuf.commit((unsigned)ret); - - receive_timestamp_update(); /* stop reading as we read less than we asked for */ if ((unsigned)ret < vec[i].len) { @@ -1026,9 +1056,8 @@ void UARTDriver::_timer_tick(void) // provided by the write() call, but if the write is larger // than the DMA buffer size then there can be extra bytes to // send here, and they must be sent with the write lock held - _write_mutex.take(HAL_SEMAPHORE_BLOCK_FOREVER); + WITH_SEMAPHORE(_write_mutex); write_pending_bytes(); - _write_mutex.give(); } else { write_pending_bytes(); } @@ -1120,16 +1149,8 @@ void UARTDriver::update_rts_line(void) */ bool UARTDriver::set_unbuffered_writes(bool on) { -#ifdef HAL_UART_NODMA - return false; -#else - if (on && !sdef.dma_tx) { - // we can't implement low latemcy writes safely without TX DMA - return false; - } unbuffered_writes = on; return true; -#endif } /* @@ -1146,7 +1167,7 @@ void UARTDriver::configure_parity(uint8_t v) sdStop((SerialDriver*)sdef.serial); #ifdef USART_CR1_M0 - // cope with F7 where there are 2 bits in CR1_M + // cope with F3 and F7 where there are 2 bits in CR1_M const uint32_t cr1_m0 = USART_CR1_M0; #else const uint32_t cr1_m0 = USART_CR1_M; @@ -1187,9 +1208,9 @@ void UARTDriver::configure_parity(uint8_t v) #endif #ifndef HAL_UART_NODMA - if(sdef.dma_rx) { - //Configure serial driver to skip handling RX packets - //because we will handle them via DMA + if (rx_dma_enabled) { + // Configure serial driver to skip handling RX packets + // because we will handle them via DMA ((SerialDriver*)sdef.serial)->usart->CR1 &= ~USART_CR1_RXNEIE; } #endif @@ -1220,7 +1241,7 @@ void UARTDriver::set_stop_bits(int n) sdStart((SerialDriver*)sdef.serial, &sercfg); #ifndef HAL_UART_NODMA - if(sdef.dma_rx) { + if (rx_dma_enabled) { //Configure serial driver to skip handling RX packets //because we will handle them via DMA ((SerialDriver*)sdef.serial)->usart->CR1 &= ~USART_CR1_RXNEIE; @@ -1261,8 +1282,29 @@ uint64_t UARTDriver::receive_time_constraint_us(uint16_t nbytes) return last_receive_us; } +/* + set user specified PULLUP/PULLDOWN options from SERIALn_OPTIONS +*/ +void UARTDriver::set_pushpull(uint16_t options) +{ +#if HAL_USE_SERIAL == TRUE && !defined(STM32F1) + if ((options & OPTION_PULLDOWN_RX) && sdef.rx_line) { + palLineSetPushPull(sdef.rx_line, PAL_PUSHPULL_PULLDOWN); + } + if ((options & OPTION_PULLDOWN_TX) && sdef.tx_line) { + palLineSetPushPull(sdef.tx_line, PAL_PUSHPULL_PULLDOWN); + } + if ((options & OPTION_PULLUP_RX) && sdef.rx_line) { + palLineSetPushPull(sdef.rx_line, PAL_PUSHPULL_PULLUP); + } + if ((options & OPTION_PULLUP_TX) && sdef.tx_line) { + palLineSetPushPull(sdef.tx_line, PAL_PUSHPULL_PULLUP); + } +#endif +} + // set optional features, return true on success -bool UARTDriver::set_options(uint8_t options) +bool UARTDriver::set_options(uint16_t options) { if (sdef.is_usb) { // no options allowed on USB @@ -1278,19 +1320,33 @@ bool UARTDriver::set_options(uint8_t options) uint32_t cr3 = sd->usart->CR3; bool was_enabled = (sd->usart->CR1 & USART_CR1_UE); -#if defined(STM32F7) || defined(STM32H7) +#if defined(STM32F7) || defined(STM32H7) || defined(STM32F3) // F7 has built-in support for inversion in all uarts + ioline_t rx_line = (options & OPTION_SWAP)?sdef.tx_line:sdef.rx_line; + ioline_t tx_line = (options & OPTION_SWAP)?sdef.rx_line:sdef.tx_line; if (options & OPTION_RXINV) { cr2 |= USART_CR2_RXINV; _cr2_options |= USART_CR2_RXINV; + if (rx_line != 0) { + palLineSetPushPull(rx_line, PAL_PUSHPULL_PULLDOWN); + } } else { cr2 &= ~USART_CR2_RXINV; + if (rx_line != 0) { + palLineSetPushPull(rx_line, PAL_PUSHPULL_PULLUP); + } } if (options & OPTION_TXINV) { cr2 |= USART_CR2_TXINV; _cr2_options |= USART_CR2_TXINV; + if (tx_line != 0) { + palLineSetPushPull(tx_line, PAL_PUSHPULL_PULLDOWN); + } } else { cr2 &= ~USART_CR2_TXINV; + if (tx_line != 0) { + palLineSetPushPull(tx_line, PAL_PUSHPULL_PULLUP); + } } // F7 can also support swapping RX and TX pins if (options & OPTION_SWAP) { @@ -1325,11 +1381,27 @@ bool UARTDriver::set_options(uint8_t options) if (options & OPTION_HDPLEX) { cr3 |= USART_CR3_HDSEL; _cr3_options |= USART_CR3_HDSEL; - half_duplex = true; + if (!half_duplex) { + chEvtRegisterMaskWithFlags(chnGetEventSource((SerialDriver*)sdef.serial), + &hd_listener, + EVT_TRANSMIT_END, + CHN_OUTPUT_EMPTY); + half_duplex = true; + } +#ifndef HAL_UART_NODMA + if (rx_dma_enabled && rxdma) { + dmaStreamDisable(rxdma); + } +#endif + // force DMA off when using half-duplex as the timing may affect other devices + // sharing the DMA channel + rx_dma_enabled = tx_dma_enabled = false; } else { cr3 &= ~USART_CR3_HDSEL; } + set_pushpull(options); + if (sd->usart->CR2 == cr2 && sd->usart->CR3 == cr3) { // no change @@ -1356,4 +1428,34 @@ uint8_t UARTDriver::get_options(void) const return _last_options; } +#if HAL_USE_SERIAL_USB == TRUE +/* + initialise the USB bus, called from both UARTDriver and stdio for startup debug + This can be called before the hal is initialised so must not call any hal functions + */ +void usb_initialise(void) +{ + static bool initialised; + if (initialised) { + return; + } + initialised = true; + sduObjectInit(&SDU1); + sduStart(&SDU1, &serusbcfg1); +#if HAL_HAVE_DUAL_USB_CDC + sduObjectInit(&SDU2); + sduStart(&SDU2, &serusbcfg2); +#endif + /* + * Activates the USB driver and then the USB bus pull-up on D+. + * Note, a delay is inserted in order to not have to disconnect the cable + * after a reset. + */ + usbDisconnectBus(serusbcfg1.usbp); + chThdSleep(chTimeUS2I(1500)); + usbStart(serusbcfg1.usbp, &usbcfg); + usbConnectBus(serusbcfg1.usbp); +} +#endif + #endif //CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS diff --git a/libraries/AP_HAL_ChibiOS/UARTDriver.h b/libraries/AP_HAL_ChibiOS/UARTDriver.h index 5c5731d63a..63832b051d 100644 --- a/libraries/AP_HAL_ChibiOS/UARTDriver.h +++ b/libraries/AP_HAL_ChibiOS/UARTDriver.h @@ -22,7 +22,7 @@ #include "shared_dma.h" #include "Semaphores.h" -#define RX_BOUNCE_BUFSIZE 128U +#define RX_BOUNCE_BUFSIZE 64U #define TX_BOUNCE_BUFSIZE 64U // enough for uartA to uartH, plus IOMCU @@ -54,7 +54,7 @@ public: bool lock_port(uint32_t write_key, uint32_t read_key) override; // control optional features - bool set_options(uint8_t options) override; + bool set_options(uint16_t options) override; uint8_t get_options(void) const override; // write to a locked port. If port is locked and key is not correct then 0 is returned @@ -72,6 +72,8 @@ public: uint8_t dma_tx_stream_id; uint32_t dma_tx_channel_id; #endif + ioline_t tx_line; + ioline_t rx_line; ioline_t rts_line; int8_t rxinv_gpio; uint8_t rxinv_polarity; @@ -117,6 +119,8 @@ public: private: const SerialDef &sdef; + bool rx_dma_enabled; + bool tx_dma_enabled; // thread used for all UARTs static thread_t *uart_thread_ctx; @@ -149,12 +153,13 @@ private: // of ::read() and ::write() in the main loop #ifndef HAL_UART_NODMA bool tx_bounce_buf_ready; - uint8_t *rx_bounce_buf; + volatile uint8_t rx_bounce_idx; + uint8_t *rx_bounce_buf[2]; uint8_t *tx_bounce_buf; #endif ByteBuffer _readbuf{0}; ByteBuffer _writebuf{0}; - Semaphore _write_mutex; + HAL_Semaphore _write_mutex; #ifndef HAL_UART_NODMA const stm32_dma_stream_t* rxdma; const stm32_dma_stream_t* txdma; @@ -164,7 +169,6 @@ private: bool _blocking_writes; bool _initialised; bool _device_initialised; - bool _lock_rx_in_timer_tick = false; #ifndef HAL_UART_NODMA Shared_DMA *dma_handle; #endif @@ -181,17 +185,20 @@ private: uint32_t _first_write_started_us; uint32_t _total_written; - // we remember cr2 and cr2 options from set_options to apply on sdStart() - uint32_t _cr3_options; + // we remember config options from set_options to apply on sdStart() + uint32_t _cr1_options; uint32_t _cr2_options; - uint8_t _last_options; + uint32_t _cr3_options; + uint16_t _last_options; // half duplex control. After writing we throw away bytes for 4 byte widths to // prevent reading our own bytes back +#if CH_CFG_USE_EVENTS == TRUE bool half_duplex; - uint32_t hd_read_delay_us; - uint32_t hd_write_us; - void half_duplex_setup_delay(uint16_t len); + event_listener_t hd_listener; + bool hd_tx_active; + void half_duplex_setup_tx(void); +#endif // set to true for unbuffered writes (low latency writes) bool unbuffered_writes; @@ -212,6 +219,7 @@ private: #ifndef HAL_UART_NODMA void dma_tx_allocate(Shared_DMA *ctx); void dma_tx_deallocate(Shared_DMA *ctx); + void dma_rx_enable(void); #endif void update_rts_line(void); @@ -224,6 +232,12 @@ private: void receive_timestamp_update(void); + // set SERIALn_OPTIONS for pullup/pulldown + void set_pushpull(uint16_t options); + void thread_init(); static void uart_thread(void *); }; + +// access to usb init for stdio.cpp +void usb_initialise(void); diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora/defaults.parm new file mode 100755 index 0000000000..38f10d7f23 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora/defaults.parm @@ -0,0 +1,13 @@ +# setup the temperature compensation +BRD_IMU_TARGTEMP 45 + +# turn on the CAN power monitoring(default) +CAN_P1_DRIVER 1 +BATT_MONITOR 8 + +# setup the parameter for the ADC power module +BATT_VOLT_PIN 16 +BATT_CURR_PIN 17 +BATT_VOLT_MULT 18.000 +BATT_AMP_PERVLT 24.000 + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora/hwdef-bl.dat new file mode 100755 index 0000000000..2ef6c0e150 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora/hwdef-bl.dat @@ -0,0 +1,62 @@ +# hw definition file for processing by chibios_hwdef.py +# for CUAV-Nora board + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# crystal frequency +OSCILLATOR_HZ 16000000 + +# board ID for firmware load +APJ_BOARD_ID 1009 + +FLASH_SIZE_KB 2048 + +# bootloader is installed at zero offset +FLASH_RESERVE_START_KB 0 + +# the location where the bootloader will put the firmware +# the H743 has 128k sectors +FLASH_BOOTLOADER_LOAD_KB 128 + +# ChibiOS system timer +STM32_ST_USE_TIMER 2 + +PD8 LED_RED OUTPUT OPENDRAIN HIGH # red +PC7 LED_ACTIVITY OUTPUT OPENDRAIN HIGH # blue +PC6 LED_BOOTLOADER OUTPUT OPENDRAIN HIGH # green + +define HAL_LED_ON 0 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 UART7 + +# UART7 is debug +PF6 UART7_RX UART7 NODMA +PE8 UART7_TX UART7 NODMA + +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +define HAL_USE_EMPTY_STORAGE 1 +define HAL_STORAGE_SIZE 16384 + +define BOOTLOADER_DEBUG SD7 + + +# Add CS pins to ensure they are high in bootloader +PF10 ADIS16470_CS CS +PF2 RM3100_CS CS +PG6 ICM20689_CS CS SPEED_VERYLOW +PI12 ICM20649_CS CS SPEED_VERYLOW +PF3 BMI088_A_CS CS +PF4 BMI088_G_CS CS +PF5 FRAM_CS CS SPEED_VERYLOW +PG10 MS5611_IMU_CS CS +PI8 MS5611_BOARD_CS CS +PI4 EXT1_CS1 CS +PI10 EXT1_CS2 CS +PI6 EXT1_CS3 CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora/hwdef.dat new file mode 100755 index 0000000000..7b48c78b1b --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora/hwdef.dat @@ -0,0 +1,295 @@ +# hw definition file for processing by chibios_hwdef.py for CUAV-Nora + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# crystal frequency +OSCILLATOR_HZ 16000000 + +# board ID for firmware load +APJ_BOARD_ID 1009 + +FLASH_SIZE_KB 2048 + +# with 2M flash we can afford to optimize for speed +env OPTIMIZE -O2 + +# ChibiOS system timer +STM32_ST_USE_TIMER 2 + +# bootloader takes first sector +FLASH_RESERVE_START_KB 128 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 USART2 USART6 USART1 UART4 UART8 UART7 OTG2 + +# default the 2nd interface to MAVLink2 until MissionPlanner updates drivers +define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2 + +# now we define the pins that USB is connected on +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# Port switching for USB HS and FS,high = USB_FS , LOW = USB_HS +PH15 USB_HS_ENABLE OUTPUT HIGH +define USB_HW_ENABLE_HS 0 + +# these are the pins for SWD debugging with a STlinkv2 or black-magic probe +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# SPI1 - internal sensors +PG11 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PD7 SPI1_MOSI SPI1 + +# SPI2 - FRAM +PI1 SPI2_SCK SPI2 +PI2 SPI2_MISO SPI2 +PI3 SPI2_MOSI SPI2 + +# SPI4 - sensors2 +PE2 SPI4_SCK SPI4 +PE13 SPI4_MISO SPI4 +PE6 SPI4_MOSI SPI4 + +# SPI5 - external1 +PF7 SPI5_SCK SPI5 +PF8 SPI5_MISO SPI5 +PF9 SPI5_MOSI SPI5 + +# SPI6 - external2 +PG13 SPI6_SCK SPI6 +PG12 SPI6_MISO SPI6 +PA7 SPI6_MOSI SPI6 + +# sensor + +PF10 ADIS16470_CS CS +PF2 RM3100_CS CS +PG6 ICM20689_CS CS SPEED_VERYLOW +PI12 ICM20649_CS CS SPEED_VERYLOW +PF3 BMI088_A_CS CS +PF4 BMI088_G_CS CS +PF5 FRAM_CS CS SPEED_VERYLOW +PG10 MS5611_IMU_CS CS +PI8 MS5611_BOARD_CS CS + +# external CS pins, SPI5 connector +PI4 EXT1_CS1 CS +PI10 EXT1_CS2 CS +PI6 EXT1_CS3 CS + +# I2C buses + +# I2C1 is on GPS port +PB8 I2C1_SCL I2C1 +PB9 I2C1_SDA I2C1 + +# I2C2 on GPS2 connector +PF1 I2C2_SCL I2C2 +PF0 I2C2_SDA I2C2 + +# I2C3 for onboard mag +PH7 I2C3_SCL I2C3 +PH8 I2C3_SDA I2C3 + +# I2C4 is on BDMA on DMAMUX2 +PF14 I2C4_SCL I2C4 +PF15 I2C4_SDA I2C4 + +# order of I2C buses +I2C_ORDER I2C3 I2C1 I2C2 I2C4 + +define HAL_I2C_INTERNAL_MASK 1 + +# enable pins +PE3 VDD_3V3_SENSORS_EN OUTPUT LOW + +# start peripheral power off, then enable after init +# this prevents a problem with radios that use RTS for +# bootloader hold +PD11 VDD_5V_HIPOWER_EN OUTPUT HIGH +PG4 VDD_5V_PERIPH_EN OUTPUT HIGH + +PG5 VDD_5V_RC_EN OUTPUT HIGH +PG7 VDD_3V3_SD_CARD_EN OUTPUT HIGH + +# drdy pins +PE7 DRDY1_ADIS16470 INPUT +PH5 DRDY2_ICM20649 INPUT +PB14 DRDY3_BMI088_GYRO1 INPUT +PB15 DRDY4_BMI088_ACC1 INPUT +PJ0 DRDY5_ICM20689 INPUT +PC13 DRDY6_BMI088_GYRO2 INPUT +PI14 DRDY7_BMI088_ACC2 INPUT +PE4 DRDY8_RM3100 INPUT + +# UARTs + +# USART2 is telem1 +PD6 USART2_RX USART2 +PD5 USART2_TX USART2 +PD3 USART2_CTS USART2 +PD4 USART2_RTS USART2 + +# USART1 is GPS1 +PB7 USART1_RX USART1 NODMA +PB6 USART1_TX USART1 NODMA + +# UART4 GPS2 +PD0 UART4_RX UART4 NODMA +PD1 UART4_TX UART4 NODMA + +# USART6 is telem2 +PG9 USART6_RX USART6 +PG14 USART6_TX USART6 +PG15 USART6_CTS USART6 +PG8 USART6_RTS USART6 + +# UART7 is debug +PF6 UART7_RX UART7 NODMA +PE8 UART7_TX UART7 NODMA + +# SBUS, DSM port +PE0 UART8_RX UART8 +PE1 UART8_TX UART8 + +# PWM AUX channels +PH10 TIM5_CH1 TIM5 PWM(1) GPIO(50) +PH11 TIM5_CH2 TIM5 PWM(2) GPIO(51) +PH12 TIM5_CH3 TIM5 PWM(3) GPIO(52) +PI0 TIM5_CH4 TIM5 PWM(4) GPIO(53) +PD12 TIM4_CH1 TIM4 PWM(5) GPIO(54) +PD13 TIM4_CH2 TIM4 PWM(6) GPIO(55) +PD14 TIM4_CH3 TIM4 PWM(7) GPIO(56) +PD15 TIM4_CH4 TIM4 PWM(8) GPIO(57) + +PE9 TIM1_CH1 TIM1 PWM(9) GPIO(58) +PE11 TIM1_CH2 TIM1 PWM(10) GPIO(59) +PA10 TIM1_CH3 TIM1 PWM(11) GPIO(60) +PE14 TIM1_CH4 TIM1 PWM(12) GPIO(61) +PH6 TIM12_CH1 TIM12 PWM(13) GPIO(62) NODMA +PH9 TIM12_CH2 TIM12 PWM(14) GPIO(63) NODMA + +# WS2812 LED +PI5 TIM8_CH1 TIM8 PWM(15) GPIO(64) + +# allow for 15 PWMs by default +define BOARD_PWM_COUNT_DEFAULT 15 + +# PWM output for buzzer +PE5 TIM15_CH1 TIM15 GPIO(77) ALARM + +# RC input +PB4 TIM3_CH1 TIM3 RCININT PULLUP LOW + +# analog in +PA0 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PA1 BATT_CURRENT_SENS ADC1 SCALE(1) + +# ADC3.3/ADC6.6 +PC4 SPARE1_ADC1 ADC1 SCALE(1) +PA4 SPARE2_ADC1 ADC1 SCALE(1) + +PF12 RSSI_IN ADC1 SCALE(1) + +PC5 VDD_5V_SENS ADC1 SCALE(2) +PC1 SCALED_V3V3 ADC1 SCALE(2) + +# CAN bus +PI9 CAN1_RX CAN1 +PH13 CAN1_TX CAN1 + +# 2nd CAN bus. Cannot be used at same time as USB_HS +PB12 CAN2_RX CAN2 +PB13 CAN2_TX CAN2 + +# control for silent (no output) for CAN +PH2 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(70) +PH3 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(71) + +# GPIOs + +PA8 HEATER_EN OUTPUT LOW GPIO(80) +define HAL_HEATER_GPIO_PIN 80 +define HAL_HAVE_IMU_HEATER 1 + +PG1 VDD_BRICK_VALID INPUT PULLUP +PG2 VDD_BRICK2_VALID INPUT PULLUP +PG0 nVBUS INPUT PULLUP +PJ3 VDD_5V_HIPOWER_OC INPUT PULLUP +PJ4 VDD_5V_PERIPH_OC INPUT PULLUP +PB10 nSPI5_RESET_EXTERNAL1 OUTPUT HIGH + +# SPI devices +SPIDEV rm3100 SPI1 DEVID1 RM3100_CS MODE3 2*MHZ 8*MHZ +SPIDEV icm20689 SPI1 DEVID2 ICM20689_CS MODE3 2*MHZ 8*MHZ +SPIDEV bmi088_a SPI4 DEVID2 BMI088_A_CS MODE3 10*MHZ 10*MHZ +SPIDEV bmi088_g SPI4 DEVID3 BMI088_G_CS MODE3 10*MHZ 10*MHZ +SPIDEV ms5611_imu SPI4 DEVID1 MS5611_IMU_CS MODE3 20*MHZ 20*MHZ +SPIDEV ms5611_board SPI6 DEVID1 MS5611_BOARD_CS MODE3 20*MHZ 20*MHZ +SPIDEV icm20649 SPI6 DEVID2 ICM20649_CS MODE3 2*MHZ 8*MHZ +SPIDEV ramtron SPI2 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ + +# two baro +BARO MS56XX SPI:ms5611_imu +BARO MS56XX SPI:ms5611_board + +# three IMUs +IMU Invensense SPI:icm20689 ROTATION_NONE +IMU BMI088 SPI:bmi088_a SPI:bmi088_g ROTATION_PITCH_180_YAW_270 +IMU Invensensev2 SPI:icm20649 ROTATION_NONE + +define HAL_DEFAULT_INS_FAST_SAMPLE 5 + +# compasses + +define HAL_PROBE_EXTERNAL_I2C_COMPASSES +COMPASS IST8310 I2C:ALL_EXTERNAL:0x0E true ROTATION_ROLL_180_YAW_90 +COMPASS IST8310 I2C:ALL_INTERNAL:0x0E false ROTATION_ROLL_180_YAW_90 + +COMPASS RM3100 SPI:rm3100 false ROTATION_NONE + + +# microSD support +PC8 SDMMC1_D0 SDMMC1 +PC9 SDMMC1_D1 SDMMC1 +PC10 SDMMC1_D2 SDMMC1 +PC11 SDMMC1_D3 SDMMC1 +PC12 SDMMC1_CK SDMMC1 +PD2 SDMMC1_CMD SDMMC1 + +# red LED marked as B/E + +PD8 LED_R1 OUTPUT OPENDRAIN HIGH GPIO(0) +PC6 LED_G1 OUTPUT OPENDRAIN LOW GPIO(1) +PC7 LED_B1 OUTPUT OPENDRAIN HIGH GPIO(2) + +define HAL_GPIO_A_LED_PIN 0 +define HAL_GPIO_B_LED_PIN 1 +define HAL_GPIO_C_LED_PIN 2 + +define HAL_GPIO_LED_ON 0 +define HAL_GPIO_LED_OFF 1 + +# use pixracer style 3-LED indicators +define HAL_HAVE_PIXRACER_LED + +# enable RAMTROM parameter storage +define HAL_STORAGE_SIZE 16384 +define HAL_WITH_RAMTRON 1 + +# allow to have have a dedicated safety switch pin +define HAL_HAVE_SAFETY_SWITCH 1 +PE12 LED_SAFETY OUTPUT +PE10 SAFETY_IN INPUT PULLDOWN + +# enable FAT filesystem support (needs a microSD defined via SDMMC) +define HAL_OS_FATFS_IO 1 + +define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" +define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" + +DMA_PRIORITY ADC* SPI1* TIM*UP* +DMA_NOSHARE SPI1* TIM*UP* diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CUAV-X7/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-X7/defaults.parm new file mode 100644 index 0000000000..56c00efb7f --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-X7/defaults.parm @@ -0,0 +1,18 @@ +# temperature control. We need lower P/I values +# to prevent oscillation of the BMI088 temperature +# the ADIS16470 is factory temperature calibrated, +# but the BMI088 isn't, so temperature control is still +# worthwhile +BRD_IMU_TARGTEMP 45 +BRD_IMUHEAT_P 50 +BRD_IMUHEAT_I 0.07 + +# turn on the CAN power monitoring(default) +CAN_P1_DRIVER 1 +BATT_MONITOR 8 + +# setup the parameter for the ADC power module +BATT_VOLT_PIN 16 +BATT_CURR_PIN 17 +BATT_VOLT_MULT 18.000 +BATT_AMP_PERVLT 24.000 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CUAV-X7/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-X7/hwdef-bl.dat new file mode 100644 index 0000000000..f5924c1821 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-X7/hwdef-bl.dat @@ -0,0 +1,62 @@ +# hw definition file for processing by chibios_hwdef.py +# for CUAV-X7 board + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# crystal frequency +OSCILLATOR_HZ 16000000 + +# board ID for firmware load +APJ_BOARD_ID 1010 + +FLASH_SIZE_KB 2048 + +# bootloader is installed at zero offset +FLASH_RESERVE_START_KB 0 + +# the location where the bootloader will put the firmware +# the H743 has 128k sectors +FLASH_BOOTLOADER_LOAD_KB 128 + +# ChibiOS system timer +STM32_ST_USE_TIMER 2 + +PI5 LED_RED OUTPUT OPENDRAIN HIGH # red +PI7 LED_ACTIVITY OUTPUT OPENDRAIN HIGH # blue +PI6 LED_BOOTLOADER OUTPUT OPENDRAIN HIGH # green + +define HAL_LED_ON 0 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 UART7 + +# UART7 is debug +PF6 UART7_RX UART7 NODMA +PE8 UART7_TX UART7 NODMA + +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +define HAL_USE_EMPTY_STORAGE 1 +define HAL_STORAGE_SIZE 16384 + +define BOOTLOADER_DEBUG SD7 + + +# Add CS pins to ensure they are high in bootloader +PF10 ADIS16470_CS CS +PF2 RM3100_CS CS +PG6 ICM20689_CS CS SPEED_VERYLOW +PI12 ICM20649_CS CS SPEED_VERYLOW +PF3 BMI088_A_CS CS +PF4 BMI088_G_CS CS +PF5 FRAM_CS CS SPEED_VERYLOW +PG10 MS5611_IMU_CS CS +PI8 MS5611_BOARD_CS CS +PI4 EXT1_CS1 CS +PI10 EXT1_CS2 CS +PI13 EXT1_CS3 CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CUAV-X7/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-X7/hwdef.dat new file mode 100644 index 0000000000..003cdf5986 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-X7/hwdef.dat @@ -0,0 +1,306 @@ +# hw definition file for processing by chibios_hwdef.py for CUAV-X7 + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# crystal frequency +OSCILLATOR_HZ 16000000 + +# board ID for firmware load +APJ_BOARD_ID 1010 + +FLASH_SIZE_KB 2048 + +# with 2M flash we can afford to optimize for speed +env OPTIMIZE -O2 + +# ChibiOS system timer +STM32_ST_USE_TIMER 2 + +# bootloader takes first sector +FLASH_RESERVE_START_KB 128 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 USART2 USART6 USART1 UART4 UART8 UART7 OTG2 + +# default the 2nd interface to MAVLink2 until MissionPlanner updates drivers +define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2 + +# now we define the pins that USB is connected on +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# Port switching for USB HS and FS,high = USB_FS , LOW = USB_HS +PH15 USB_HS_ENABLE OUTPUT HIGH +define USB_HW_ENABLE_HS 0 + +# these are the pins for SWD debugging with a STlinkv2 or black-magic probe +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# SPI1 - internal sensors +PG11 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PD7 SPI1_MOSI SPI1 + +# SPI2 - FRAM +PI1 SPI2_SCK SPI2 +PI2 SPI2_MISO SPI2 +PI3 SPI2_MOSI SPI2 + +# SPI4 - sensors2 +PE2 SPI4_SCK SPI4 +PE13 SPI4_MISO SPI4 +PE6 SPI4_MOSI SPI4 + +# SPI5 - external1 +PF7 SPI5_SCK SPI5 +PF8 SPI5_MISO SPI5 +PF9 SPI5_MOSI SPI5 + +# SPI6 - external2 +PG13 SPI6_SCK SPI6 +PG12 SPI6_MISO SPI6 +PA7 SPI6_MOSI SPI6 + +# sensor + +PF10 ADIS16470_CS CS +PF2 RM3100_CS CS +PG6 ICM20689_CS CS SPEED_VERYLOW +PI12 ICM20649_CS CS SPEED_VERYLOW +PF3 BMI088_A_CS CS +PF4 BMI088_G_CS CS +PF5 FRAM_CS CS SPEED_VERYLOW +PG10 MS5611_IMU_CS CS +PI8 MS5611_BOARD_CS CS + +# external CS pins, SPI5 connector +PI4 EXT1_CS1 CS +PI10 EXT1_CS2 CS +PI13 EXT1_CS3 CS + +# I2C buses + +# I2C1 is on GPS port +PB8 I2C1_SCL I2C1 +PB9 I2C1_SDA I2C1 + +# I2C2 on GPS2 connector +PF1 I2C2_SCL I2C2 +PF0 I2C2_SDA I2C2 + +# I2C3 for onboard mag +PH7 I2C3_SCL I2C3 +PH8 I2C3_SDA I2C3 + +# I2C4 is on BDMA on DMAMUX2 +PF14 I2C4_SCL I2C4 +PF15 I2C4_SDA I2C4 + +# order of I2C buses +I2C_ORDER I2C3 I2C1 I2C2 I2C4 + +define HAL_I2C_INTERNAL_MASK 1 + +# enable pins +PE3 VDD_3V3_SENSORS_EN OUTPUT LOW + +# start peripheral power off, then enable after init +# this prevents a problem with radios that use RTS for +# bootloader hold +PD11 VDD_5V_HIPOWER_EN OUTPUT HIGH +PG4 VDD_5V_PERIPH_EN OUTPUT HIGH + +PG5 VDD_5V_RC_EN OUTPUT HIGH +PG7 VDD_3V3_SD_CARD_EN OUTPUT HIGH + +# drdy pins +PE7 DRDY1_ADIS16470 INPUT GPIO(93) +PH5 DRDY2_ICM20649 INPUT +PB14 DRDY3_BMI088_GYRO1 INPUT +PB15 DRDY4_BMI088_ACC1 INPUT +PJ0 DRDY5_ICM20689 INPUT +PC13 DRDY6_BMI088_GYRO2 INPUT +PI14 DRDY7_BMI088_ACC2 INPUT +PE4 DRDY8_RM3100 INPUT + +# use GPIO(93) for data ready on ADIS16470 +define ADIS_DRDY_PIN 93 + +# UARTs + +# USART2 is telem1 +PD6 USART2_RX USART2 +PD5 USART2_TX USART2 +PD3 USART2_CTS USART2 +PD4 USART2_RTS USART2 + +# USART1 is GPS1 +PB7 USART1_RX USART1 NODMA +PB6 USART1_TX USART1 NODMA + +# UART4 GPS2 +PD0 UART4_RX UART4 NODMA +PD1 UART4_TX UART4 NODMA + +# USART6 is telem2 +PG9 USART6_RX USART6 +PG14 USART6_TX USART6 +PG15 USART6_CTS USART6 +PG8 USART6_RTS USART6 + +# UART7 is debug +PF6 UART7_RX UART7 NODMA +PE8 UART7_TX UART7 NODMA + +# SBUS, DSM port +PE0 UART8_RX UART8 +PE1 UART8_TX UART8 + +# PWM AUX channels +PH10 TIM5_CH1 TIM5 PWM(1) GPIO(50) +PH11 TIM5_CH2 TIM5 PWM(2) GPIO(51) +PH12 TIM5_CH3 TIM5 PWM(3) GPIO(52) +PI0 TIM5_CH4 TIM5 PWM(4) GPIO(53) +PD12 TIM4_CH1 TIM4 PWM(5) GPIO(54) +PD13 TIM4_CH2 TIM4 PWM(6) GPIO(55) +PD14 TIM4_CH3 TIM4 PWM(7) GPIO(56) +PD15 TIM4_CH4 TIM4 PWM(8) GPIO(57) + +PE9 TIM1_CH1 TIM1 PWM(9) GPIO(58) +PE11 TIM1_CH2 TIM1 PWM(10) GPIO(59) +PA10 TIM1_CH3 TIM1 PWM(11) GPIO(60) +PE14 TIM1_CH4 TIM1 PWM(12) GPIO(61) +PH6 TIM12_CH1 TIM12 PWM(13) GPIO(62) NODMA +PH9 TIM12_CH2 TIM12 PWM(14) GPIO(63) NODMA + +# allow for 14 PWMs by default +define BOARD_PWM_COUNT_DEFAULT 14 + +# PWM output for buzzer +PE5 TIM15_CH1 TIM15 GPIO(77) ALARM + +# RC input +PB4 TIM3_CH1 TIM3 RCININT PULLUP LOW + +# analog in +PA0 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PA1 BATT_CURRENT_SENS ADC1 SCALE(1) + +# ADC3.3/ADC6.6 +PC4 SPARE1_ADC1 ADC1 SCALE(1) +PA4 SPARE2_ADC1 ADC1 SCALE(1) + +PF12 RSSI_IN ADC1 SCALE(1) + +PC5 VDD_5V_SENS ADC1 SCALE(2) +PC1 SCALED_V3V3 ADC1 SCALE(2) + +# CAN bus +PI9 CAN1_RX CAN1 +PH13 CAN1_TX CAN1 + +# 2nd CAN bus. Cannot be used at same time as USB_HS +PB12 CAN2_RX CAN2 +PB13 CAN2_TX CAN2 + +# control for silent (no output) for CAN +PH2 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(70) +PH3 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(71) + +# GPIOs + +PA8 HEATER_EN OUTPUT LOW GPIO(80) +define HAL_HEATER_GPIO_PIN 80 +define HAL_HAVE_IMU_HEATER 1 + +PG1 VDD_BRICK_VALID INPUT PULLUP +PG2 VDD_BRICK2_VALID INPUT PULLUP +PG0 nVBUS INPUT PULLUP +PJ3 VDD_5V_HIPOWER_OC INPUT PULLUP +PJ4 VDD_5V_PERIPH_OC INPUT PULLUP +PB10 nSPI5_RESET_EXTERNAL1 OUTPUT HIGH + +# SPI devices +SPIDEV adis16470 SPI1 DEVID2 ADIS16470_CS MODE3 1*MHZ 2*MHZ +SPIDEV icm20689 SPI1 DEVID2 ICM20689_CS MODE3 2*MHZ 8*MHZ +SPIDEV bmi088_a SPI4 DEVID2 BMI088_A_CS MODE3 10*MHZ 10*MHZ +SPIDEV bmi088_g SPI4 DEVID3 BMI088_G_CS MODE3 10*MHZ 10*MHZ +SPIDEV ms5611_imu SPI4 DEVID1 MS5611_IMU_CS MODE3 20*MHZ 20*MHZ +SPIDEV ms5611_board SPI6 DEVID1 MS5611_BOARD_CS MODE3 20*MHZ 20*MHZ +SPIDEV icm20649 SPI6 DEVID2 ICM20649_CS MODE3 2*MHZ 8*MHZ +SPIDEV ramtron SPI2 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ + +# RM3100 may be on SPI1 or SPI2 (not both). Later board revisions +# have the RM3100 on SPI2, to leave SPI1 free for ADIS1647x +SPIDEV rm3100-1 SPI1 DEVID1 RM3100_CS MODE3 2*MHZ 8*MHZ +SPIDEV rm3100-2 SPI2 DEVID2 RM3100_CS MODE3 2*MHZ 8*MHZ + +# two baro +BARO MS56XX SPI:ms5611_imu +BARO MS56XX SPI:ms5611_board + +# three IMUs, only one of ICM20689 and ADIS16470 will be included +IMU ADIS1647x SPI:adis16470 ROTATION_PITCH_180_YAW_270 ADIS_DRDY_PIN +IMU Invensense SPI:icm20689 ROTATION_NONE +IMU BMI088 SPI:bmi088_a SPI:bmi088_g ROTATION_PITCH_180_YAW_270 +IMU Invensensev2 SPI:icm20649 ROTATION_NONE + +define HAL_DEFAULT_INS_FAST_SAMPLE 5 + +# compasses + +define HAL_PROBE_EXTERNAL_I2C_COMPASSES +COMPASS IST8310 I2C:ALL_EXTERNAL:0x0E true ROTATION_ROLL_180_YAW_90 +COMPASS IST8310 I2C:ALL_INTERNAL:0x0E false ROTATION_ROLL_180_YAW_90 + +# probe for RM3100 on SPI1 or SPI2 +COMPASS RM3100 SPI:rm3100-1 false ROTATION_NONE +COMPASS RM3100 SPI:rm3100-2 false ROTATION_NONE + + +# microSD support +PC8 SDMMC1_D0 SDMMC1 +PC9 SDMMC1_D1 SDMMC1 +PC10 SDMMC1_D2 SDMMC1 +PC11 SDMMC1_D3 SDMMC1 +PC12 SDMMC1_CK SDMMC1 +PD2 SDMMC1_CMD SDMMC1 + +# red LED marked as B/E + +PI5 LED_R1 OUTPUT OPENDRAIN HIGH GPIO(0) +PI6 LED_G1 OUTPUT OPENDRAIN LOW GPIO(1) +PI7 LED_B1 OUTPUT OPENDRAIN HIGH GPIO(2) + +define HAL_GPIO_A_LED_PIN 0 +define HAL_GPIO_B_LED_PIN 1 +define HAL_GPIO_C_LED_PIN 2 + +define HAL_GPIO_LED_ON 0 +define HAL_GPIO_LED_OFF 1 + +# use pixracer style 3-LED indicators +define HAL_HAVE_PIXRACER_LED + +# enable RAMTROM parameter storage +define HAL_STORAGE_SIZE 16384 +define HAL_WITH_RAMTRON 1 + +# allow to have have a dedicated safety switch pin +define HAL_HAVE_SAFETY_SWITCH 1 +PE12 LED_SAFETY OUTPUT +PE10 SAFETY_IN INPUT PULLDOWN + +# enable FAT filesystem support (needs a microSD defined via SDMMC) +define HAL_OS_FATFS_IO 1 + +define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" +define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" + +DMA_PRIORITY ADC* SPI1* TIM*UP* +DMA_NOSHARE SPI1* TIM*UP* + +# default to 45C target temp +define HAL_IMU_TEMP_DEFAULT 45 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CUAV_GPS/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/CUAV_GPS/hwdef-bl.dat index ae70fa0642..ba5234a856 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CUAV_GPS/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CUAV_GPS/hwdef-bl.dat @@ -16,19 +16,6 @@ env AP_PERIPH 1 # crystal frequency OSCILLATOR_HZ 16000000 -STM32_HSE_ENABLED TRUE -STM32_PLLM_VALUE 16 -STM32_PLLN_VALUE 384 -STM32_PLLP_VALUE 4 -STM32_PLLQ_VALUE 8 -STM32_PLLSRC STM32_PLLSRC_HSE -STM32_PREE1 STM32_PREE1_DIV1 -STM32_PREE2 STM32_PREE2_DIV1 -STM32_HPRE STM32_HPRE_DIV1 -STM32_PPRE1 STM32_PPRE1_DIV2 -STM32_PPRE2 STM32_PPRE2_DIV2 - - define CH_CFG_ST_FREQUENCY 1000000 # assume 512k flash part @@ -37,11 +24,8 @@ FLASH_SIZE_KB 512 STDOUT_SERIAL SD1 STDOUT_BAUDRATE 57600 -# board voltage -STM32_VDD 330U - # order of UARTs -UART_ORDER +SERIAL_ORDER # use safety button to stay in bootloader PB3 STAY_IN_BOOTLOADER INPUT PULLDOWN @@ -96,8 +80,8 @@ define STM32_CAN_USE_CAN1 TRUE define CAN_APP_NODE_NAME "org.ardupilot.cuav_gps" -# start with a fixed node ID so the board is usable without DNA -define HAL_CAN_DEFAULT_NODE_ID 116 +# use DNA +define HAL_CAN_DEFAULT_NODE_ID 0 # make bl baudrate match debug baudrate for easier debugging define BOOTLOADER_BAUDRATE 57600 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CUAV_GPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CUAV_GPS/hwdef.dat index c9f7317963..be56507159 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CUAV_GPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CUAV_GPS/hwdef.dat @@ -25,19 +25,6 @@ define HAL_WATCHDOG_ENABLED_DEFAULT true # crystal frequency OSCILLATOR_HZ 16000000 -STM32_HSE_ENABLED TRUE -STM32_PLLM_VALUE 16 -STM32_PLLN_VALUE 384 -STM32_PLLP_VALUE 4 -STM32_PLLQ_VALUE 8 -STM32_PLLSRC STM32_PLLSRC_HSE -STM32_PREE1 STM32_PREE1_DIV1 -STM32_PREE2 STM32_PREE2_DIV1 -STM32_HPRE STM32_HPRE_DIV1 -STM32_PPRE1 STM32_PPRE1_DIV2 -STM32_PPRE2 STM32_PPRE2_DIV2 - - define CH_CFG_ST_FREQUENCY 1000000 # assume 512k flash part @@ -46,11 +33,8 @@ FLASH_SIZE_KB 512 STDOUT_SERIAL SD1 STDOUT_BAUDRATE 57600 -# board voltage -STM32_VDD 330U - # order of UARTs -UART_ORDER USART1 USART2 +SERIAL_ORDER USART1 EMPTY EMPTY USART2 # a LED to flash PB12 LED OUTPUT LOW @@ -82,11 +66,26 @@ define HAL_I2C_INTERNAL_MASK 0 # only one I2C bus I2C_ORDER I2C3 -# IST compass -COMPASS IST8310 I2C:0:0x0E false ROTATION_ROLL_180_YAW_90 +# only one SPI bus in normal config +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 -# BMP388 baro +# SPI CS +PA4 MAG_CS CS +PA10 MS5611_CS CS + +# SPI devices +SPIDEV rm3100 SPI1 DEVID1 MAG_CS MODE0 1*MHZ 1*MHZ +SPIDEV ms5611 SPI1 DEVID2 MS5611_CS MODE3 20*MHZ 20*MHZ + +# compass +COMPASS IST8310 I2C:0:0x0E false ROTATION_ROLL_180_YAW_90 +COMPASS RM3100 SPI:rm3100 false ROTATION_PITCH_180 + +# baro BARO BMP388 I2C:0:0x76 +BARO MS56XX SPI:ms5611 # PWM output for buzzer PB10 TIM2_CH3 TIM2 GPIO(77) LOW ALARM @@ -129,13 +128,11 @@ PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW define HAL_USE_CAN TRUE define STM32_CAN_USE_CAN1 TRUE -# start with a fixed node ID so the board is usable without DNA -define HAL_CAN_DEFAULT_NODE_ID 116 +# use DNA +define HAL_CAN_DEFAULT_NODE_ID 0 define CAN_APP_NODE_NAME "org.ardupilot.cuav_gps" -define CH_DBG_ENABLE_STACK_CHECK TRUE - define HAL_NO_GCS define HAL_NO_LOGGING define HAL_NO_MONITOR_THREAD diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CUAVv5Nano/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/CUAVv5Nano/hwdef-bl.dat index fc8e29c71a..ee71547530 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CUAVv5Nano/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CUAVv5Nano/hwdef-bl.dat @@ -7,14 +7,6 @@ MCU STM32F7xx STM32F767xx # crystal frequency OSCILLATOR_HZ 16000000 -define STM32_LSECLK 32768U -define STM32_LSEDRV (3U << 3U) -define STM32_PLLSRC STM32_PLLSRC_HSE -define STM32_PLLM_VALUE 8 -define STM32_PLLN_VALUE 216 -define STM32_PLLP_VALUE 2 -define STM32_PLLQ_VALUE 9 - # board ID for firmware load APJ_BOARD_ID 50 @@ -34,11 +26,8 @@ PC6 LED_BOOTLOADER OUTPUT HIGH PC7 LED_ACTIVITY OUTPUT HIGH define HAL_LED_ON 0 -# board voltage -STM32_VDD 330U - # order of UARTs (and USB) -UART_ORDER OTG1 USART2 UART7 +SERIAL_ORDER OTG1 USART2 UART7 # USART2 is telem1 PD6 USART2_RX USART2 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CUAVv5Nano/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CUAVv5Nano/hwdef.dat index 93bf786d3e..0f74fda6f5 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CUAVv5Nano/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CUAVv5Nano/hwdef.dat @@ -13,7 +13,7 @@ undef PE3 PE3 VDD_3V3_SENSORS_EN OUTPUT LOW # order of UARTs (and USB). -UART_ORDER OTG1 USART1 USART2 USART3 UART4 USART6 UART7 OTG2 +SERIAL_ORDER OTG1 USART2 USART3 USART1 UART4 USART6 UART7 OTG2 # enable TX on USART6 (disabled for fmuv5 with iomcu) PG14 USART6_TX USART6 NODMA diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack/hwdef.dat index fd85c55423..f973de0f8c 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack/hwdef.dat @@ -24,6 +24,29 @@ PB1 PB1_ADC ADC1 SCALE(1) SPIDEV icm20948_ext SPI4 DEVID1 MPU_EXT_CS MODE3 4*MHZ 8*MHZ SPIDEV icm20602_ext SPI4 DEVID3 GYRO_EXT_CS MODE3 4*MHZ 8*MHZ + +# Sensor Check alias for validating board type +CHECK_MPU9250 spi_check_register("mpu9250", MPUREG_WHOAMI, MPU_WHOAMI_MPU9250) +CHECK_MPU9250_EXT spi_check_register("mpu9250_ext", MPUREG_WHOAMI, MPU_WHOAMI_MPU9250) +CHECK_ICM20602_EXT spi_check_register("icm20602_ext", MPUREG_WHOAMI, MPU_WHOAMI_ICM20602) +CHECK_LSM9DS0_EXT_G spi_check_register("lsm9ds0_ext_g", LSMREG_WHOAMI, LSM_WHOAMI_L3GD20) +CHECK_LSM9DS0_EXT_AM spi_check_register("lsm9ds0_ext_am", LSMREG_WHOAMI, LSM_WHOAMI_LSM303D) +CHECK_ICM20948_EXT spi_check_register("icm20948_ext", INV2REG_WHOAMI, INV2_WHOAMI_ICM20948) +CHECK_MS5611 check_ms5611("ms5611") +CHECK_MS5611_EXT check_ms5611("ms5611_ext") + +# Sensor Check Macros to be used for validating board type +CHECK_IMU0_PRESENT $CHECK_MPU9250_EXT || $CHECK_ICM20602_EXT +CHECK_IMU1_PRESENT ($CHECK_LSM9DS0_EXT_G && $CHECK_LSM9DS0_EXT_AM) || $CHECK_ICM20948_EXT +CHECK_IMU2_PRESENT $CHECK_MPU9250 +CHECK_BARO0_PRESENT $CHECK_MS5611 +CHECK_BARO1_PRESENT $CHECK_MS5611_EXT + +BOARD_VALIDATE $CHECK_IMU0_PRESENT $CHECK_IMU1_PRESENT $CHECK_IMU2_PRESENT $CHECK_BARO0_PRESENT $CHECK_BARO1_PRESENT + +# also define the default board type +define BOARD_TYPE_DEFAULT 3 + # three IMUs, but allow for different varients. First two IMUs are # isolated, 3rd isn't IMU Invensense SPI:mpu9250_ext ROTATION_PITCH_180 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef-bl.dat index bff75d0566..03b2332322 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef-bl.dat @@ -28,11 +28,8 @@ FLASH_BOOTLOADER_LOAD_KB 128 define HAL_LED_ON 0 -# board voltage -STM32_VDD 330U - # order of UARTs (and USB) -UART_ORDER OTG1 UART7 +SERIAL_ORDER OTG1 UART7 # UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters). PE7 UART7_RX UART7 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef.dat index 8b97b09a33..b2d6e72adf 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef.dat @@ -23,16 +23,13 @@ env OPTIMIZE -O2 FLASH_RESERVE_START_KB 128 -# board voltage -STM32_VDD 330U - define HAL_STORAGE_SIZE 16384 # order of I2C buses I2C_ORDER I2C2 I2C1 # order of UARTs (and USB) -UART_ORDER OTG1 UART4 USART2 USART3 UART8 UART7 OTG2 +SERIAL_ORDER OTG1 USART2 USART3 UART4 UART8 UART7 OTG2 # If the board has an IOMCU connected via a UART then this defines the # UART to talk to that MCU. Leave it out for boards with no IOMCU. @@ -248,6 +245,23 @@ IMU Invensense SPI:icm20602_ext ROTATION_ROLL_180_YAW_270 IMU Invensensev2 SPI:icm20948_ext ROTATION_PITCH_180 IMU Invensensev2 SPI:icm20948 ROTATION_YAW_270 +# Sensor Check alias for validating board type +CHECK_ICM20649 spi_check_register("icm20948", INV2REG_WHOAMI, INV2_WHOAMI_ICM20649) +CHECK_ICM20602_EXT spi_check_register("icm20602_ext", MPUREG_WHOAMI, MPU_WHOAMI_ICM20602) +CHECK_ICM20948_EXT spi_check_register("icm20948_ext", INV2REG_WHOAMI, INV2_WHOAMI_ICM20948) +CHECK_MS5611 check_ms5611("ms5611") +CHECK_MS5611_EXT check_ms5611("ms5611_ext") + +# Sensor Check Macros to be used for validating board type +CHECK_IMU0_PRESENT $CHECK_ICM20602_EXT +CHECK_IMU1_PRESENT $CHECK_ICM20948_EXT +CHECK_IMU2_PRESENT $CHECK_ICM20649 +CHECK_BARO0_PRESENT $CHECK_MS5611 +CHECK_BARO1_PRESENT $CHECK_MS5611_EXT + +BOARD_VALIDATE $CHECK_IMU0_PRESENT $CHECK_IMU1_PRESENT $CHECK_IMU2_PRESENT $CHECK_BARO0_PRESENT $CHECK_BARO1_PRESENT + + define HAL_DEFAULT_INS_FAST_SAMPLE 7 # two baros diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeYellow/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeYellow/hwdef-bl.dat index 78f9047535..734405ff5f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeYellow/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeYellow/hwdef-bl.dat @@ -6,20 +6,9 @@ MCU STM32F7xx STM32F777xx # crystal frequency OSCILLATOR_HZ 24000000 -define STM32_LSECLK 32768U -define STM32_LSEDRV (3U << 3U) -define STM32_PLLSRC STM32_PLLSRC_HSE -define STM32_PLLM_VALUE 24 -define STM32_PLLN_VALUE 432 -define STM32_PLLP_VALUE 2 -define STM32_PLLQ_VALUE 9 - # board ID for firmware load APJ_BOARD_ID 120 -# board voltage -STM32_VDD 330U - # flash size FLASH_SIZE_KB 2048 @@ -31,7 +20,7 @@ USB_STRING_PRODUCT "CubeYellow-BL" USB_STRING_SERIAL "%SERIAL%" # order of UARTs (and USB) -UART_ORDER OTG1 USART2 USART3 UART7 +SERIAL_ORDER OTG1 USART2 USART3 UART7 PD5 USART2_TX USART2 PD6 USART2_RX USART2 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeYellow/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeYellow/hwdef.dat index 2d4fb81d00..23bd5a686b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeYellow/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeYellow/hwdef.dat @@ -21,14 +21,6 @@ define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_CHIBIOS_FMUV3 # crystal frequency OSCILLATOR_HZ 24000000 -define STM32_LSECLK 32768U -define STM32_LSEDRV (3U << 3U) -define STM32_PLLSRC STM32_PLLSRC_HSE -define STM32_PLLM_VALUE 24 -define STM32_PLLN_VALUE 432 -define STM32_PLLP_VALUE 2 -define STM32_PLLQ_VALUE 9 - # board ID for firmware load APJ_BOARD_ID 120 @@ -44,9 +36,6 @@ env OPTIMIZE -O2 # now define the voltage the MCU runs at. This is needed for ChibiOS # to set various internal driver limits. It is in 0.01 volt units -# board voltage -STM32_VDD 330U - # this is the STM32 timer that ChibiOS will use for the low level # driver. This must be a 32 bit timer. We currently only support # timers 2, 3, 4, 5 and 21. See hal_st_lld.c in ChibiOS for details @@ -64,9 +53,9 @@ FLASH_SIZE_KB 2048 # in drivers. # serial port for stdout. This is optional. If you leave it out then -# output from printf() lines will be thrown away (you can stil use +# output from printf() lines will be sent to # hal.console->printf() for the ArduPilot console, which is the first -# UART in the UART_ORDER list). The value for STDOUT_SERIAL is a +# UART in the SERIAL_ORDER list. The value for STDOUT_SERIAL is a # serial device name, and must be for a serial device for which pins # are defined in this file. For example, SD7 is for UART7 (SD7 == # "serial device 7" in ChibiOS). @@ -111,7 +100,7 @@ I2C_ORDER I2C2 I2C1 # 6) SERIAL5: extra UART (usually RTOS debug console) # order of UARTs (and USB) -UART_ORDER OTG1 UART4 USART2 USART3 UART8 UART7 OTG2 +SERIAL_ORDER OTG1 USART2 USART3 UART4 UART8 UART7 OTG2 # if the board has an IOMCU connected via a UART then this defines the # UART to talk to that MCU. Leave it out for boards with no IOMCU @@ -469,13 +458,6 @@ define HAL_GPIO_PWM_VOLT_PIN 3 # this defines the default maximum clock on I2C devices. define HAL_I2C_MAX_CLOCK 100000 -# uncomment the lines below to enable strict API -# checking in ChibiOS -# define CH_DBG_ENABLE_ASSERTS TRUE -# define CH_DBG_ENABLE_CHECKS TRUE -# define CH_DBG_SYSTEM_STATE_CHECK TRUE -# define CH_DBG_ENABLE_STACK_CHECK TRUE - # we can't share IO UART (USART6) DMA_NOSHARE USART6_TX USART6_RX ADC1 DMA_PRIORITY USART6* diff --git a/libraries/AP_HAL_ChibiOS/hwdef/DrotekP3Pro/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/DrotekP3Pro/hwdef-bl.dat index 09d15c7cfe..22b4002136 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/DrotekP3Pro/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/DrotekP3Pro/hwdef-bl.dat @@ -10,9 +10,6 @@ APJ_BOARD_ID 13 # crystal frequency OSCILLATOR_HZ 24000000 -# board voltage -STM32_VDD 330U - # ChibiOS system timer STM32_ST_USE_TIMER 5 @@ -26,7 +23,7 @@ FLASH_BOOTLOADER_LOAD_KB 16 FLASH_RESERVE_START_KB 0 # uarts and USB to run bootloader protocol on -UART_ORDER OTG1 USART2 USART3 +SERIAL_ORDER OTG1 USART2 USART3 # this is the pin that senses USB being connected. It is an input pin # setup as OPENDRAIN @@ -62,13 +59,6 @@ define HAL_LED_ON 1 # available (in bytes) define HAL_STORAGE_SIZE 16384 -# uncomment the lines below to enable strict API -# checking in ChibiOS -# define CH_DBG_ENABLE_ASSERTS TRUE -# define CH_DBG_ENABLE_CHECKS TRUE -# define CH_DBG_SYSTEM_STATE_CHECK TRUE -# define CH_DBG_ENABLE_STACK_CHECK TRUE - # Add CS pins to ensure they are high in bootloader PC2 MPU9250_CS CS PC15 20608_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/DrotekP3Pro/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/DrotekP3Pro/hwdef.dat index 66d40285fc..7e89a69420 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/DrotekP3Pro/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/DrotekP3Pro/hwdef.dat @@ -1,8 +1,6 @@ # hw definition file for processing by chibios_hwdef.py # for FMUv4pro hardware (Pixhawk 3 Pro) -define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_CHIBIOS_FMUV4PRO - define BOARD_TYPE_DEFAULT 14 # MCU class and specific type @@ -14,8 +12,6 @@ APJ_BOARD_ID 13 # crystal frequency OSCILLATOR_HZ 24000000 -# board voltage -STM32_VDD 330U # ChibiOS system timer STM32_ST_USE_TIMER 5 @@ -44,7 +40,7 @@ I2C_ORDER I2C1 I2C2 # 6) SERIAL5: extra UART (usually RTOS debug console) # order of UARTs (and USB) -UART_ORDER OTG1 UART4 USART2 USART3 UART8 USART1 UART7 +SERIAL_ORDER OTG1 USART2 USART3 UART4 UART8 USART1 UART7 # UART for IOMCU IOMCU_UART USART6 @@ -233,9 +229,6 @@ define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" define HAL_STORAGE_SIZE 16384 define HAL_WITH_RAMTRON 1 -# fallback to flash is no FRAM fitted -define STORAGE_FLASH_PAGE 22 - # enable FAT filesystem support (needs a microSD defined via SDIO) define HAL_OS_FATFS_IO 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Durandal/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Durandal/hwdef-bl.dat index ce1bc87bb1..5bd9b6af36 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Durandal/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Durandal/hwdef-bl.dat @@ -32,11 +32,9 @@ PC7 LED_BOOTLOADER OUTPUT LOW # blue define HAL_LED_ON 0 -# board voltage -STM32_VDD 330U # order of UARTs (and USB) -UART_ORDER OTG1 UART7 +SERIAL_ORDER OTG1 UART7 # UART7 is debug PF6 UART7_RX UART7 NODMA @@ -48,6 +46,9 @@ PA12 OTG_FS_DP OTG1 PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD +# pullup buzzer for no sound in bootloader +PE5 BUZZER OUTPUT LOW PULLDOWN + define HAL_USE_EMPTY_STORAGE 1 define HAL_STORAGE_SIZE 16384 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Durandal/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Durandal/hwdef.dat index d8fa597351..843e6b6a76 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Durandal/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Durandal/hwdef.dat @@ -24,11 +24,9 @@ env OPTIMIZE -O2 # bootloader takes first sector FLASH_RESERVE_START_KB 128 -# board voltage -STM32_VDD 330U # order of UARTs (and USB) -UART_ORDER OTG1 USART1 USART2 USART3 UART4 USART6 UART7 OTG2 +SERIAL_ORDER OTG1 USART2 USART3 USART1 UART4 USART6 UART7 OTG2 # default the 2nd interface to MAVLink2 until MissionPlanner updates drivers define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/F35Lightning/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/F35Lightning/hwdef-bl.dat index 81f59318b8..0ea2b37333 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/F35Lightning/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/F35Lightning/hwdef-bl.dat @@ -9,7 +9,6 @@ APJ_BOARD_ID 135 # crystal frequency OSCILLATOR_HZ 8000000 -STM32_PLLM_VALUE 8 # bootloader is installed at zero offset FLASH_RESERVE_START_KB 0 @@ -22,11 +21,9 @@ FLASH_BOOTLOADER_LOAD_KB 64 define HAL_STORAGE_SIZE 15360 define STORAGE_FLASH_PAGE 1 -# board voltage -STM32_VDD 330U # order of UARTs -UART_ORDER OTG1 USART1 USART2 UART5 +SERIAL_ORDER OTG1 USART1 USART2 UART5 PA11 OTG_FS_DM OTG1 PA12 OTG_FS_DP OTG1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/F35Lightning/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/F35Lightning/hwdef.dat index c6e5f4bc86..c4abb41e06 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/F35Lightning/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/F35Lightning/hwdef.dat @@ -9,10 +9,6 @@ APJ_BOARD_ID 135 # crystal frequency OSCILLATOR_HZ 8000000 -STM32_PLLM_VALUE 8 - -# board voltage -STM32_VDD 330U # ChibiOS system timer STM32_ST_USE_TIMER 5 @@ -29,7 +25,7 @@ FLASH_RESERVE_START_KB 64 I2C_ORDER I2C1 # order of UARTs (UART3RX used for RCInput, UART4RX and USART6RX not pinned out) -UART_ORDER OTG1 USART2 USART1 UART5 EMPTY UART4 USART6 +SERIAL_ORDER OTG1 USART1 UART5 USART2 EMPTY UART4 USART6 # USB sensing #PA9 VBUS INPUT OPENDRAIN @@ -151,7 +147,7 @@ define HAL_PROBE_EXTERNAL_I2C_BAROS #define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" # OSD support -define OSD_ENABLED ENABLED +define OSD_ENABLED 1 define HAL_OSD_TYPE_DEFAULT 1 ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin diff --git a/libraries/AP_HAL_ChibiOS/hwdef/F4BY/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/F4BY/hwdef-bl.dat index 6c9c9c24fa..803ebbfca3 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/F4BY/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/F4BY/hwdef-bl.dat @@ -6,11 +6,6 @@ MCU STM32F4xx STM32F407xx APJ_BOARD_ID 20 OSCILLATOR_HZ 8000000 -STM32_PLLM_VALUE 8 - - -# board voltage -STM32_VDD 330U STM32_ST_USE_TIMER 5 @@ -18,7 +13,7 @@ STM32_ST_USE_TIMER 5 FLASH_SIZE_KB 1024 # order of UARTs (and USB) -UART_ORDER OTG1 USART2 +SERIAL_ORDER OTG1 USART2 PE3 LED_BOOTLOADER OUTPUT PE2 LED_ACTIVITY OUTPUT diff --git a/libraries/AP_HAL_ChibiOS/hwdef/F4BY/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/F4BY/hwdef.dat index 9510b1f9fc..9498b1968e 100755 --- a/libraries/AP_HAL_ChibiOS/hwdef/F4BY/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/F4BY/hwdef.dat @@ -6,8 +6,7 @@ MCU STM32F4xx STM32F407xx # board ID for firmware load APJ_BOARD_ID 20 -define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_CHIBIOS_F4BY - + # USB setup USB_VENDOR 0x27AC # Swift-Flyer USB_PRODUCT 0x0201 # fmu usb driver @@ -19,10 +18,6 @@ FLASH_SIZE_KB 1024 # crystal frequency OSCILLATOR_HZ 8000000 -STM32_PLLM_VALUE 8 - -# board voltage -STM32_VDD 330U # this is the STM32 timer that ChibiOS will use for the low level # driver. This must be a 32 bit timer. We currently only support @@ -53,7 +48,7 @@ PA14 JTCK-SWCLK SWD # setup as OPENDRAIN PA9 VBUS INPUT OPENDRAIN -UART_ORDER OTG1 USART3 USART2 USART1 UART5 +SERIAL_ORDER OTG1 USART2 USART1 USART3 UART5 # UART1 as board 2.1.5 for serial 3 gps PB6 USART1_TX USART1 @@ -75,7 +70,6 @@ PC12 UART5_TX UART5 NODMA PD2 UART5_RX UART5 NODMA define HAL_STORAGE_SIZE 16384 -define STORAGE_FLASH_PAGE 22 #SPI1 for MPU PA5 SPI1_SCK SPI1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteF4/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF4/hwdef-bl.dat index 73a6a71d8c..5d2f999fd0 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/KakuteF4/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF4/hwdef-bl.dat @@ -8,7 +8,6 @@ APJ_BOARD_ID 122 # crystal frequency OSCILLATOR_HZ 8000000 -STM32_PLLM_VALUE 8 FLASH_SIZE_KB 1024 @@ -22,11 +21,9 @@ define HAL_LED_ON 0 # the location where the bootloader will put the firmware FLASH_BOOTLOADER_LOAD_KB 64 -# board voltage -STM32_VDD 330U # order of UARTs -UART_ORDER OTG1 +SERIAL_ORDER OTG1 PA11 OTG_FS_DM OTG1 PA12 OTG_FS_DP OTG1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteF4/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF4/hwdef.dat index d8fa820b67..607252de65 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/KakuteF4/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF4/hwdef.dat @@ -1,8 +1,6 @@ # hw definition file for KakuteF4 hardware -# STATUS: -# This port is mostly complete. Main missing feature are OSD, -# dataflash + # MCU class and specific type MCU STM32F4xx STM32F405xx @@ -15,15 +13,12 @@ APJ_BOARD_ID 122 # crystal frequency OSCILLATOR_HZ 8000000 -STM32_PLLM_VALUE 8 define STM32_ST_USE_TIMER 4 define CH_CFG_ST_RESOLUTION 16 FLASH_SIZE_KB 1024 -# board voltage -STM32_VDD 330U # only one I2C bus I2C_ORDER I2C1 @@ -73,7 +68,7 @@ define HAL_BATT_VOLT_SCALE 10.1 define HAL_BATT_CURR_SCALE 17.0 # order of UARTs (and USB) -UART_ORDER OTG1 UART4 USART6 USART1 UART5 USART3 +SERIAL_ORDER OTG1 USART6 USART1 UART4 UART5 USART3 # rcinput is PB11 PB11 TIM2_CH4 TIM2 RCININT FLOAT LOW @@ -150,7 +145,7 @@ BARO BMP280 I2C:0:0x76 define HAL_LOGGING_DATAFLASH # setup for OSD -define OSD_ENABLED ENABLED +define OSD_ENABLED 1 define HAL_OSD_TYPE_DEFAULT 1 ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7/hwdef-bl.dat index f9156b9c82..28a374b8c7 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7/hwdef-bl.dat @@ -13,12 +13,6 @@ OSCILLATOR_HZ 8000000 define STM32_LSECLK 32768U define STM32_LSEDRV (3U << 3U) -define STM32_PLLSRC STM32_PLLSRC_HSE -define STM32_PLLM_VALUE 8 -define STM32_PLLN_VALUE 432 -define STM32_PLLP_VALUE 2 -define STM32_PLLQ_VALUE 9 - FLASH_SIZE_KB 1024 # bootloader starts at zero offset @@ -27,11 +21,9 @@ FLASH_RESERVE_START_KB 0 # the location where the bootloader will put the firmware FLASH_BOOTLOADER_LOAD_KB 96 -# board voltage -STM32_VDD 330U # order of UARTs (and USB) -UART_ORDER OTG1 +SERIAL_ORDER OTG1 # PA10 IO-debug-console PA11 OTG_FS_DM OTG1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7/hwdef.dat index 1a32e32a5a..19d8ed9de6 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7/hwdef.dat @@ -11,28 +11,17 @@ APJ_BOARD_ID 123 # crystal frequency, setup to use external oscillator OSCILLATOR_HZ 8000000 -define STM32_LSECLK 32768U -define STM32_LSEDRV (3U << 3U) - -define STM32_PLLSRC STM32_PLLSRC_HSE -define STM32_PLLM_VALUE 8 -define STM32_PLLN_VALUE 432 -define STM32_PLLP_VALUE 2 -define STM32_PLLQ_VALUE 9 - FLASH_SIZE_KB 1024 # leave 2 sectors free FLASH_RESERVE_START_KB 96 -# board voltage -STM32_VDD 330U # only one I2C bus I2C_ORDER I2C1 # order of UARTs (and USB), USART3 should be in second place to map order with the board's silk screen -UART_ORDER OTG1 USART3 USART1 USART2 UART4 UART7 USART6 +SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 UART7 USART6 # buzzer PD15 TIM4_CH4 TIM4 GPIO(77) ALARM @@ -99,9 +88,13 @@ PB10 USART3_TX USART3 PA0 UART4_TX UART4 NODMA PA1 UART4_RX UART4 NODMA -# USART6, RX only for RCIN -PC7 TIM8_CH2 TIM8 RCININT FLOAT LOW -PC6 USART6_TX USART6 NODMA LOW +# RC input defaults to timer capture +PC7 TIM8_CH2 TIM8 RCININT PULLDOWN + +# alternative config using USART for protocols +# like FPort +PC7 USART6_RX USART6 NODMA ALT(1) +PC6 USART6_TX USART6 NODMA # UART7 USED BY ESC FROM ORIGINAL DESIGN PE7 UART7_RX UART7 @@ -148,7 +141,7 @@ define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" # setup for OSD -define OSD_ENABLED ENABLED +define OSD_ENABLED 1 define HAL_OSD_TYPE_DEFAULT 1 ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin @@ -157,3 +150,4 @@ define STM32_PWM_USE_ADVANCED TRUE # we are low on flash on this board define HAL_MINIMIZE_FEATURES 1 +define HAL_WITH_DSP 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7Mini/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7Mini/hwdef.dat index 71dfa0b9fa..9bd8f43dc0 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7Mini/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7Mini/hwdef.dat @@ -11,28 +11,17 @@ APJ_BOARD_ID 145 # crystal frequency, setup to use external oscillator OSCILLATOR_HZ 8000000 -define STM32_LSECLK 32768U -define STM32_LSEDRV (3U << 3U) - -define STM32_PLLSRC STM32_PLLSRC_HSE -define STM32_PLLM_VALUE 8 -define STM32_PLLN_VALUE 432 -define STM32_PLLP_VALUE 2 -define STM32_PLLQ_VALUE 9 - FLASH_SIZE_KB 1024 # leave 2 sectors free FLASH_RESERVE_START_KB 96 -# board voltage -STM32_VDD 330U # only one I2C bus I2C_ORDER I2C1 # order of UARTs (and USB), USART3 should be in second place to map order with the board's silk screen -UART_ORDER OTG1 USART3 USART1 USART2 UART4 EMPTY USART6 UART7 +SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 EMPTY USART6 UART7 # buzzer PD15 TIM4_CH4 TIM4 GPIO(77) ALARM @@ -99,9 +88,13 @@ PB10 USART3_TX USART3 PA0 UART4_TX UART4 NODMA PA1 UART4_RX UART4 NODMA -# USART6, RX only for RCIN -PC7 TIM8_CH2 TIM8 RCININT FLOAT LOW -PC6 USART6_TX USART6 NODMA LOW +# RC input defaults to timer capture +PC7 TIM8_CH2 TIM8 RCININT PULLDOWN +PC6 USART6_TX USART6 NODMA + +# alt config to allow RCIN on UART for bi-directional +# protocols like FPort +PC7 USART6_RX USART6 NODMA ALT(1) # UART7, RX only for ESC Telemetry PE7 UART7_RX UART7 @@ -147,10 +140,24 @@ IMU Invensense SPI:mpu6000 ROTATION_YAW_180 BARO BMP280 I2C:0:0x76 # setup for OSD -define OSD_ENABLED ENABLED +define OSD_ENABLED 1 define HAL_OSD_TYPE_DEFAULT 1 ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin define BOARD_PWM_COUNT_DEFAULT 6 define STM32_PWM_USE_ADVANCED TRUE +# disable SMBUS and fuel battery monitors to save flash +define HAL_BATTMON_SMBUS_ENABLE 0 +define HAL_BATTMON_FUEL_ENABLE 0 + +# disable parachute and sprayer to save flash +define HAL_PARACHUTE_ENABLED 0 +define HAL_SPRAYER_ENABLED 0 + +# reduce max size of embedded params for apj_tool.py +define AP_PARAM_MAX_EMBEDDED_PARAM 1024 + +# we are low on flash on this board +define HAL_MINIMIZE_FEATURES 1 +define HAL_WITH_DSP 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-Wing/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-Wing/hwdef-bl.dat index 5c95b78bb3..8ab64c6389 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-Wing/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-Wing/hwdef-bl.dat @@ -9,7 +9,6 @@ APJ_BOARD_ID 127 # crystal frequency OSCILLATOR_HZ 8000000 -STM32_PLLM_VALUE 8 # bootloader is installed at zero offset FLASH_RESERVE_START_KB 0 @@ -22,11 +21,9 @@ FLASH_BOOTLOADER_LOAD_KB 64 define HAL_STORAGE_SIZE 15360 define STORAGE_FLASH_PAGE 1 -# board voltage -STM32_VDD 330U # order of UARTs -UART_ORDER OTG1 USART1 USART3 UART4 UART5 USART6 +SERIAL_ORDER OTG1 USART1 USART3 UART4 UART5 USART6 PA0 UART4_TX UART4 PA1 UART4_RX UART4 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-Wing/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-Wing/hwdef.dat index 2b63687cbb..6138e536c6 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-Wing/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-Wing/hwdef.dat @@ -22,14 +22,11 @@ # MCU class and specific type MCU STM32F4xx STM32F405xx -define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_CHIBIOS_MATEKF405WING - # board ID for firmware load APJ_BOARD_ID 127 # crystal frequency OSCILLATOR_HZ 8000000 -STM32_PLLM_VALUE 8 define STM32_ST_USE_TIMER 5 define CH_CFG_ST_RESOLUTION 32 @@ -41,14 +38,12 @@ FLASH_SIZE_KB 1024 define HAL_STORAGE_SIZE 15360 define STORAGE_FLASH_PAGE 1 -# board voltage -STM32_VDD 330U # I2C Buses I2C_ORDER I2C1 I2C2 # order of UARTs -UART_ORDER OTG1 USART3 USART1 EMPTY UART4 UART5 USART6 +SERIAL_ORDER OTG1 USART1 EMPTY USART3 UART4 UART5 USART6 USART2 ################################################# ### PIN DEFINITIONS ### @@ -57,10 +52,12 @@ UART_ORDER OTG1 USART3 USART1 EMPTY UART4 UART5 USART6 PA0 UART4_TX UART4 PA1 UART4_RX UART4 -# USART 2 is used for RC Input -# PA2 USART2_TX USART2 -# PA3 USART2_RX USART2 -PA3 TIM2_CH4 TIM2 RCININT FLOAT LOW +# default to timer for RC input +PA3 TIM9_CH2 TIM9 RCININT FLOAT LOW + +# alternative using USART2 +PA2 USART2_TX USART2 NODMA +PA3 USART2_RX USART2 NODMA ALT(1) PA4 MPU_CS CS @@ -92,6 +89,8 @@ PC9 TIM8_CH4 TIM8 PWM(6) GPIO(55) PB14 TIM1_CH2N TIM1 PWM(7) GPIO(56) PB15 TIM1_CH3N TIM1 PWM(8) GPIO(57) PA8 TIM1_CH1 TIM1 PWM(9) GPIO(58) +PA15 TIM2_CH1 TIM2 PWM(10) GPIO(59) #on LED pin,allows odd motor groups + # SD CARD SPI PB3 SPI3_SCK SPI3 @@ -174,14 +173,22 @@ define HAL_PROBE_EXTERNAL_I2C_COMPASSES define HAL_I2C_INTERNAL_MASK 0 define HAL_COMPASS_AUTO_ROT_DEFAULT 2 -define OSD_ENABLED ENABLED +define OSD_ENABLED 1 define HAL_OSD_TYPE_DEFAULT 1 ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin -define BOARD_PWM_COUNT_DEFAULT 9 +define BOARD_PWM_COUNT_DEFAULT 10 define STM32_PWM_USE_ADVANCED TRUE # disable SMBUS and fuel battery monitors to save flash define HAL_BATTMON_SMBUS_ENABLE 0 define HAL_BATTMON_FUEL_ENABLE 0 + +# disable parachute and sprayer to save flash +define HAL_PARACHUTE_ENABLED 0 +define HAL_SPRAYER_ENABLED 0 + +# reduce max size of embedded params for apj_tool.py +define AP_PARAM_MAX_EMBEDDED_PARAM 1024 +define HAL_WITH_DSP FALSE diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405/hwdef-bl.dat index 7ea5290050..7a15dd51e8 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405/hwdef-bl.dat @@ -9,7 +9,6 @@ APJ_BOARD_ID 125 # crystal frequency OSCILLATOR_HZ 8000000 -STM32_PLLM_VALUE 8 FLASH_SIZE_KB 1024 @@ -24,11 +23,9 @@ define HAL_LED_ON 0 # the location where the bootloader will put the firmware FLASH_BOOTLOADER_LOAD_KB 64 -# board voltage -STM32_VDD 330U # order of UARTs -UART_ORDER OTG1 +SERIAL_ORDER OTG1 PA11 OTG_FS_DM OTG1 PA12 OTG_FS_DP OTG1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405/hwdef.dat index 2fe3ac3534..7b6003c1ea 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405/hwdef.dat @@ -2,9 +2,6 @@ # tested on the MatekF405-OSD board # with thanks to betaflight for pinout -# STATUS: -# This port is mostly complete. Main missing feature are OSD, -# dataflash # MCU class and specific type MCU STM32F4xx STM32F405xx @@ -14,21 +11,18 @@ APJ_BOARD_ID 125 # crystal frequency OSCILLATOR_HZ 8000000 -STM32_PLLM_VALUE 8 define STM32_ST_USE_TIMER 4 define CH_CFG_ST_RESOLUTION 16 FLASH_SIZE_KB 1024 -# board voltage -STM32_VDD 330U # only one I2C bus I2C_ORDER I2C1 # order of UARTs (and USB) -UART_ORDER OTG1 USART1 USART3 UART4 UART5 +SERIAL_ORDER OTG1 USART3 UART4 USART1 UART5 USART2 # LEDs PB9 LED_BLUE OUTPUT LOW GPIO(0) @@ -88,12 +82,12 @@ define BOARD_RSSI_ANA_PIN 9 PA9 USART1_TX USART1 PA10 USART1_RX USART1 -# USART2 (RCIN) -#PA2 USART3_TX USART3 -#PA3 USART3_RX USART3 +# RC input using timer +PA3 TIM9_CH2 TIM9 RCININT PULLDOWN -# rcinput -PA3 TIM9_CH2 TIM9 RCININT FLOAT LOW +# alternative RC input using UART +PA2 USART2_TX USART2 NODMA +PA3 USART2_RX USART2 NODMA ALT(1) # USART3 PC10 USART3_TX USART3 @@ -162,14 +156,18 @@ define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" # 8 PWM available by default define BOARD_PWM_COUNT_DEFAULT 8 -# uncomment the lines below to enable strict API -# checking in ChibiOS -#define CH_DBG_ENABLE_ASSERTS TRUE -#define CH_DBG_ENABLE_CHECKS TRUE -#define CH_DBG_SYSTEM_STATE_CHECK TRUE -#define CH_DBG_ENABLE_STACK_CHECK TRUE - # setup for OSD -define OSD_ENABLED ENABLED +define OSD_ENABLED 1 define HAL_OSD_TYPE_DEFAULT 1 ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin + +# disable SMBUS and fuel battery monitors to save flash +define HAL_BATTMON_SMBUS_ENABLE 0 +define HAL_BATTMON_FUEL_ENABLE 0 + +# disable parachute and sprayer to save flash +define HAL_PARACHUTE_ENABLED 0 +define HAL_SPRAYER_ENABLED 0 + +# reduce max size of embedded params for apj_tool.py +define AP_PARAM_MAX_EMBEDDED_PARAM 1024 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekF765-Wing/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekF765-Wing/hwdef-bl.dat index a2686e3803..e3a292d068 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekF765-Wing/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekF765-Wing/hwdef-bl.dat @@ -10,15 +10,6 @@ APJ_BOARD_ID 143 # crystal frequency, setup to use external oscillator OSCILLATOR_HZ 8000000 -define STM32_LSECLK 32768U -define STM32_LSEDRV (3U << 3U) - -define STM32_PLLSRC STM32_PLLSRC_HSE -define STM32_PLLM_VALUE 8 -define STM32_PLLN_VALUE 432 -define STM32_PLLP_VALUE 2 -define STM32_PLLQ_VALUE 9 - FLASH_SIZE_KB 2048 # bootloader starts at zero offset @@ -27,11 +18,9 @@ FLASH_RESERVE_START_KB 0 # the location where the bootloader will put the firmware FLASH_BOOTLOADER_LOAD_KB 96 -# board voltage -STM32_VDD 330U # order of UARTs (and USB). Allow bootloading on USB and telem1 -UART_ORDER OTG1 UART7 +SERIAL_ORDER OTG1 UART7 # UART7 (telem1) PE7 UART7_RX UART7 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekF765-Wing/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekF765-Wing/hwdef.dat index 615904d2dc..575328ef3a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekF765-Wing/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekF765-Wing/hwdef.dat @@ -10,22 +10,11 @@ APJ_BOARD_ID 143 # crystal frequency, setup to use external oscillator OSCILLATOR_HZ 8000000 -define STM32_LSECLK 32768U -define STM32_LSEDRV (3U << 3U) - -define STM32_PLLSRC STM32_PLLSRC_HSE -define STM32_PLLM_VALUE 8 -define STM32_PLLN_VALUE 432 -define STM32_PLLP_VALUE 2 -define STM32_PLLQ_VALUE 9 - FLASH_SIZE_KB 2048 # leave 2 sectors free FLASH_RESERVE_START_KB 96 -# board voltage -STM32_VDD 330U STM32_ST_USE_TIMER 12 define CH_CFG_ST_RESOLUTION 16 @@ -34,7 +23,7 @@ define CH_CFG_ST_RESOLUTION 16 I2C_ORDER I2C2 I2C1 # order of UARTs (and USB) -UART_ORDER OTG1 USART2 UART7 USART1 USART3 UART8 UART4 +SERIAL_ORDER OTG1 UART7 USART1 USART2 USART3 UART8 UART4 USART6 # tonealarm support PB9 TIM11_CH1 TIM11 GPIO(32) ALARM @@ -122,9 +111,14 @@ PD0 UART4_RX UART4 NODMA # UART5 (RX only, for ESC telem), disabled for now until we add uartH support # PB8 UART5_RX UART5 NODMA -# USART6 (RC input) +# USART6 (RC input), SERIAL7 PC7 TIM3_CH2 TIM3 RCININT FLOAT LOW -PC6 USART6_TX USART6 NODMA LOW +PC6 USART6_TX USART6 NODMA + +# as an alternative config setup the RX6 pin as a uart. This allows +# for bi-directional UART based receiver protocols such as FPort +# without any extra hardware +PC7 USART6_RX USART6 NODMA ALT(1) # UART7 (telem1) PE7 UART7_RX UART7 @@ -201,7 +195,7 @@ define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" # setup for OSD -define OSD_ENABLED ENABLED +define OSD_ENABLED 1 define HAL_OSD_TYPE_DEFAULT 1 ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekH743/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekH743/hwdef-bl.dat new file mode 100644 index 0000000000..4603c7d49c --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekH743/hwdef-bl.dat @@ -0,0 +1,50 @@ +# hw definition file for processing by chibios_pins.py +# for Matek H743-WING bootloader + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# board ID for firmware load +APJ_BOARD_ID 1013 + +# crystal frequency, setup to use external oscillator +OSCILLATOR_HZ 8000000 + +FLASH_SIZE_KB 2048 + +# bootloader starts at zero offset +FLASH_RESERVE_START_KB 0 + +# reserve space for flash storage in last 2 sectors +FLASH_RESERVE_END_KB 256 + +# the location where the bootloader will put the firmware +# the H743 has 128k sectors +FLASH_BOOTLOADER_LOAD_KB 128 + + +# order of UARTs (and USB). Allow bootloading on USB and telem1 +SERIAL_ORDER OTG1 UART7 + +# UART7 (telem1) +PE7 UART7_RX UART7 NODMA +PE8 UART7_TX UART7 NODMA + +# PA10 IO-debug-console +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +PE3 LED_BOOTLOADER OUTPUT LOW +define HAL_LED_ON 0 + +define HAL_USE_EMPTY_STORAGE 1 +define HAL_STORAGE_SIZE 16384 + +# Add CS pins to ensure they are high in bootloader +PC15 IMU1_CS CS +PB12 MAX7456_CS CS +PD4 MS5611_CS CS +PE11 IMU2_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekH743/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekH743/hwdef.dat new file mode 100644 index 0000000000..62b57576e3 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekH743/hwdef.dat @@ -0,0 +1,210 @@ +# hw definition file for processing by chibios_pins.py +# for Matek H743-WING + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# board ID for firmware load +APJ_BOARD_ID 1013 + +# crystal frequency, setup to use external oscillator +OSCILLATOR_HZ 8000000 + +FLASH_SIZE_KB 2048 +env OPTIMIZE -O2 + +# bootloader takes first sector +FLASH_RESERVE_START_KB 128 + + +# ChibiOS system timer +STM32_ST_USE_TIMER 12 +define CH_CFG_ST_RESOLUTION 16 + +# USB +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# SPI1 for IMU1 (MPU6000) +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PD7 SPI1_MOSI SPI1 +PC15 IMU1_CS CS + +# SPI2 for MAX7456 OSD +PB12 MAX7456_CS CS +PB13 SPI2_SCK SPI2 +PB14 SPI2_MISO SPI2 +PB15 SPI2_MOSI SPI2 + +# SPI3 for MS5611 +PD4 MS5611_CS CS +PB3 SPI3_SCK SPI3 +PB4 SPI3_MISO SPI3 +PB5 SPI3_MOSI SPI3 + +# SPI4 for IMU2 (ICM20602) +PE11 IMU2_CS CS +PE12 SPI4_SCK SPI4 +PE13 SPI4_MISO SPI4 +PE14 SPI4_MOSI SPI4 + +# two I2C bus +I2C_ORDER I2C1 I2C2 + +# I2C1 +PB6 I2C1_SCL I2C1 +PB7 I2C1_SDA I2C1 + +# I2C2 +PB10 I2C2_SCL I2C2 +PB11 I2C2_SDA I2C2 + +# ADC +PC0 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PC1 BATT_CURRENT_SENS ADC1 SCALE(1) +PA4 BATT2_VOLTAGE_SENS ADC1 SCALE(1) +PA7 BATT2_CURRENT_SENS ADC1 SCALE(1) + +define HAL_BATT_MONITOR_DEFAULT 4 +define HAL_BATT_VOLT_PIN 10 +define HAL_BATT_CURR_PIN 11 +define HAL_BATT2_VOLT_PIN 18 +define HAL_BATT2_CURR_PIN 7 +define HAL_BATT_VOLT_SCALE 11.0 +define HAL_BATT_CURR_SCALE 40.0 +define HAL_BATT2_VOLT_SCALE 11.0 + +PC4 PRESSURE_SENS ADC1 SCALE(2) +define HAL_DEFAULT_AIRSPEED_PIN 4 + +PC5 RSSI_ADC ADC1 +define BOARD_RSSI_ANA_PIN 8 + +# LED +# green LED1 marked as B/E +# blue LED0 marked as ACT +PE3 LED0 OUTPUT LOW GPIO(90) # blue +PE4 LED1 OUTPUT LOW GPIO(91) # green +define HAL_GPIO_A_LED_PIN 91 +define HAL_GPIO_B_LED_PIN 90 +define HAL_GPIO_LED_OFF 1 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 UART7 USART1 USART2 USART3 UART8 UART4 USART6 + +# USART1 (telem2) +PA10 USART1_RX USART1 +PA9 USART1_TX USART1 + +# USART2 (GPS1) +PD5 USART2_TX USART2 +PD6 USART2_RX USART2 + +# USART3 (GPS2) +PD9 USART3_RX USART3 +PD8 USART3_TX USART3 + +# UART4 (spare) +PB9 UART4_TX UART4 +PB8 UART4_RX UART4 + +# USART6 (RC input), SERIAL7 +PC7 TIM3_CH2 TIM3 RCININT FLOAT LOW +PC6 USART6_TX USART6 NODMA + +# as an alternative config setup the RX6 pin as a uart. This allows +# for bi-directional UART based receiver protocols such as FPort +# without any extra hardware +PC7 USART6_RX USART6 NODMA ALT(1) + +# UART7 (telem1) +PE7 UART7_RX UART7 +PE8 UART7_TX UART7 +PE10 UART7_CTS UART7 +PE9 UART7_RTS UART7 + +# UART8 (spare) +PE0 UART8_RX UART8 +PE1 UART8_TX UART8 + +# CAN bus +PD0 CAN1_RX CAN1 +PD1 CAN1_TX CAN1 +PD3 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(70) + +# Motors +PB0 TIM8_CH2N TIM8 PWM(1) GPIO(50) +PB1 TIM8_CH3N TIM8 PWM(2) GPIO(51) +PA0 TIM5_CH1 TIM5 PWM(3) GPIO(52) +PA1 TIM5_CH2 TIM5 PWM(4) GPIO(53) +PA2 TIM5_CH3 TIM5 PWM(5) GPIO(54) +PA3 TIM5_CH4 TIM5 PWM(6) GPIO(55) +PD12 TIM4_CH1 TIM4 PWM(7) GPIO(56) +PD13 TIM4_CH2 TIM4 PWM(8) GPIO(57) +PD14 TIM4_CH3 TIM4 PWM(9) GPIO(58) +PD15 TIM4_CH4 TIM4 PWM(10) GPIO(59) +PE5 TIM15_CH1 TIM15 PWM(11) GPIO(60) +PE6 TIM15_CH2 TIM15 PWM(12) GPIO(61) +PA8 TIM1_CH1 TIM1 PWM(13) GPIO(62) # for WS2812 LED + +# Beeper +PA15 TIM2_CH1 TIM2 GPIO(32) ALARM + +# microSD support +PC8 SDMMC1_D0 SDMMC1 +PC9 SDMMC1_D1 SDMMC1 +PC10 SDMMC1_D2 SDMMC1 +PC11 SDMMC1_D3 SDMMC1 +PC12 SDMMC1_CK SDMMC1 +PD2 SDMMC1_CMD SDMMC1 + +# GPIOs +PD10 PINIO1 OUTPUT GPIO(81) LOW +PD11 PINIO2 OUTPUT GPIO(82) LOW + +DMA_PRIORITY S* + +define HAL_STORAGE_SIZE 16384 + +# use last 2 pages for flash storage +# H743 has 16 pages of 128k each +define STORAGE_FLASH_PAGE 14 + +# spi devices +SPIDEV ms5611 SPI3 DEVID1 MS5611_CS MODE3 20*MHZ 20*MHZ +SPIDEV mpu6000 SPI1 DEVID1 IMU1_CS MODE3 1*MHZ 4*MHZ +SPIDEV icm20602 SPI4 DEVID1 IMU2_CS MODE3 1*MHZ 4*MHZ +SPIDEV osd SPI2 DEVID4 MAX7456_CS MODE0 10*MHZ 10*MHZ + +# no built-in compass, but probe the i2c bus for all possible +# external compass types +define ALLOW_ARM_NO_COMPASS +define HAL_COMPASS_DEFAULT HAL_COMPASS_NONE +define HAL_PROBE_EXTERNAL_I2C_COMPASSES +define HAL_I2C_INTERNAL_MASK 1 +define HAL_COMPASS_AUTO_ROT_DEFAULT 2 + +# two IMUs. We put icm20602 first as we can sample accel at 4kHz +IMU Invensense SPI:icm20602 ROTATION_ROLL_180_YAW_270 +IMU Invensense SPI:mpu6000 ROTATION_ROLL_180_YAW_270 +define HAL_DEFAULT_INS_FAST_SAMPLE 1 + +# one BARO +BARO MS56XX SPI:ms5611 + +define HAL_OS_FATFS_IO 1 +define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" +define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" + +# setup for OSD +define OSD_ENABLED 1 +define HAL_OSD_TYPE_DEFAULT 1 +ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin + +define BOARD_PWM_COUNT_DEFAULT 13 + + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/NucleoH743/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/NucleoH743/hwdef-bl.dat index 72bfb03140..9f15330619 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/NucleoH743/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/NucleoH743/hwdef-bl.dat @@ -22,11 +22,9 @@ FLASH_RESERVE_START_KB 0 # the H743 has 128k sectors FLASH_BOOTLOADER_LOAD_KB 128 -# board voltage -STM32_VDD 330U # order of UARTs (and USB) -UART_ORDER OTG1 +SERIAL_ORDER OTG1 # UART7 is debug PF6 UART7_RX UART7 NODMA diff --git a/libraries/AP_HAL_ChibiOS/hwdef/NucleoH743/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/NucleoH743/hwdef.dat index e6b1acdaa2..7fad7119b1 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/NucleoH743/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/NucleoH743/hwdef.dat @@ -17,11 +17,9 @@ FLASH_SIZE_KB 2048 FLASH_RESERVE_START_KB 128 -# board voltage -STM32_VDD 330U # order of UARTs (and USB) -UART_ORDER OTG1 UART7 +SERIAL_ORDER OTG1 EMPTY EMPTY UART7 PA11 OTG_FS_DM OTG1 PA12 OTG_FS_DP OTG1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/OMNIBUSF7V2/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/OMNIBUSF7V2/hwdef-bl.dat index a98a4db488..52763b48da 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/OMNIBUSF7V2/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/OMNIBUSF7V2/hwdef-bl.dat @@ -10,15 +10,6 @@ APJ_BOARD_ID 121 # crystal frequency, setup to use external oscillator OSCILLATOR_HZ 8000000 -define STM32_LSECLK 32768U -define STM32_LSEDRV (3U << 3U) - -define STM32_PLLSRC STM32_PLLSRC_HSE -define STM32_PLLM_VALUE 8 -define STM32_PLLN_VALUE 432 -define STM32_PLLP_VALUE 2 -define STM32_PLLQ_VALUE 9 - FLASH_SIZE_KB 1024 # bootloader is installed at zero offset @@ -27,10 +18,8 @@ FLASH_RESERVE_START_KB 0 # the location where the bootloader will put the firmware FLASH_BOOTLOADER_LOAD_KB 96 -# board voltage -STM32_VDD 330U -UART_ORDER OTG1 +SERIAL_ORDER OTG1 # PA10 IO-debug-console PA11 OTG_FS_DM OTG1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/OMNIBUSF7V2/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/OMNIBUSF7V2/hwdef.dat index 1c193b5f11..7794757d53 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/OMNIBUSF7V2/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/OMNIBUSF7V2/hwdef.dat @@ -5,36 +5,23 @@ # MCU class and specific type MCU STM32F7xx STM32F745xx -define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_CHIBIOS_OMNIBUSF7V2 - # board ID for firmware load APJ_BOARD_ID 121 # crystal frequency, setup to use external oscillator OSCILLATOR_HZ 8000000 -define STM32_LSECLK 32768U -define STM32_LSEDRV (3U << 3U) - -define STM32_PLLSRC STM32_PLLSRC_HSE -define STM32_PLLM_VALUE 8 -define STM32_PLLN_VALUE 432 -define STM32_PLLP_VALUE 2 -define STM32_PLLQ_VALUE 9 - FLASH_SIZE_KB 1024 # reserve one sector for bootloader and 2 for storage FLASH_RESERVE_START_KB 96 -# board voltage -STM32_VDD 330U # only one I2C bus I2C_ORDER I2C2 # order of UARTs (and USB) -UART_ORDER OTG1 USART6 USART1 USART3 +SERIAL_ORDER OTG1 USART1 USART3 USART6 USART2 PA11 OTG_FS_DM OTG1 PA12 OTG_FS_DP OTG1 @@ -94,8 +81,11 @@ IMU Invensense SPI:mpu6500 ROTATION_YAW_90 PA10 USART1_RX USART1 PA9 USART1_TX USART1 -# USART2 for RC input, RX only -PA3 TIM9_CH2 TIM9 RCININT FLOAT LOW +# RC input using timer by default +PA3 TIM9_CH2 TIM9 RCININT PULLDOWN + +# alternative RC input using USART2 +PA3 USART2_RX USART2 NODMA ALT(1) # USART3 PD9 USART3_RX USART3 @@ -138,7 +128,7 @@ define HAL_COMPASS_AUTO_ROT_DEFAULT 2 # one baro BARO BMP280 SPI:bmp280 -define OSD_ENABLED ENABLED +define OSD_ENABLED 1 define HAL_OSD_TYPE_DEFAULT 1 ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin diff --git a/libraries/AP_HAL_ChibiOS/hwdef/OmnibusNanoV6/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/OmnibusNanoV6/hwdef-bl.dat index 9a06df416b..c937c5700f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/OmnibusNanoV6/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/OmnibusNanoV6/hwdef-bl.dat @@ -9,7 +9,6 @@ APJ_BOARD_ID 133 # crystal frequency OSCILLATOR_HZ 8000000 -STM32_PLLM_VALUE 8 FLASH_SIZE_KB 1024 @@ -26,11 +25,9 @@ define HAL_LED_ON 0 # the location where the bootloader will put the firmware FLASH_BOOTLOADER_LOAD_KB 64 -# board voltage -STM32_VDD 330U # order of UARTs -UART_ORDER OTG1 +SERIAL_ORDER OTG1 PA11 OTG_FS_DM OTG1 PA12 OTG_FS_DP OTG1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/OmnibusNanoV6/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/OmnibusNanoV6/hwdef.dat index c797a7fb05..2d0d70091d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/OmnibusNanoV6/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/OmnibusNanoV6/hwdef.dat @@ -9,10 +9,6 @@ APJ_BOARD_ID 133 # crystal frequency OSCILLATOR_HZ 8000000 -STM32_PLLM_VALUE 8 - -# board voltage -STM32_VDD 330U STM32_ST_USE_TIMER 5 @@ -24,7 +20,7 @@ FLASH_RESERVE_START_KB 64 I2C_ORDER I2C2 # order of UARTs -UART_ORDER OTG1 USART6 USART1 UART4 +SERIAL_ORDER OTG1 USART1 UART4 USART6 #adc PC1 BAT_CURR_SENS ADC1 SCALE(1) @@ -104,8 +100,6 @@ SPIDEV dataflash SPI2 DEVID1 FLASH_CS MODE3 32*MHZ 32*MHZ # enable logging to dataflash define HAL_LOGGING_DATAFLASH -define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_CHIBIOS_OMNIBUSNANOV6 - # one IMU IMU Invensense SPI:mpu6000 ROTATION_YAW_90 @@ -136,7 +130,7 @@ define BOARD_RSSI_ANA_PIN 0 define HAL_GPIO_A_LED_PIN 41 -define OSD_ENABLED ENABLED +define OSD_ENABLED 1 define HAL_OSD_TYPE_DEFAULT 1 #To complementary channels work we define this @@ -144,10 +138,5 @@ define STM32_PWM_USE_ADVANCED TRUE define BOARD_PWM_COUNT_DEFAULT 4 -#define CH_DBG_ENABLE_ASSERTS TRUE -#define CH_DBG_ENABLE_CHECKS TRUE -#define CH_DBG_SYSTEM_STATE_CHECK TRUE -#define CH_DBG_ENABLE_STACK_CHECK TRUE - #font for the osd ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin diff --git a/libraries/AP_HAL_ChibiOS/hwdef/PH4-mini/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/PH4-mini/hwdef.dat index 8018db18dd..9bb0ca92d6 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/PH4-mini/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/PH4-mini/hwdef.dat @@ -9,7 +9,7 @@ include ../fmuv5/hwdef.dat STM32_ST_USE_TIMER 5 # order of UARTs (and USB). Telem2 is UART4 on the mini, USART3 is not available -UART_ORDER OTG1 USART1 USART2 UART4 USART6 UART7 OTG2 +SERIAL_ORDER OTG1 USART2 UART4 USART1 USART6 UART7 OTG2 # enable TX on USART6 (disabled for fmuv5 with iomcu) PG14 USART6_TX USART6 NODMA diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk1-1M/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk1-1M/hwdef.dat index 4b40312f58..91534d170f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk1-1M/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk1-1M/hwdef.dat @@ -5,3 +5,4 @@ include ../Pixhawk1/hwdef.dat FLASH_SIZE_KB 1024 define HAL_MINIMIZE_FEATURES 1 +undef STORAGE_FLASH_PAGE diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk4/README.md b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk4/README.md index 4f5a2eb5d4..1caf9ceec1 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk4/README.md +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk4/README.md @@ -10,7 +10,7 @@ The Pixhawk4 flight controller is sold by [Holybro](http://www.holybro.com/produ - builtin I2C IST8310 magnetometer - microSD card slot - 6 UARTs plus USB - - 14 PWM outputs + - 16 PWM outputs - Four I2C and two CAN ports - External Buzzer - external safety Switch @@ -27,7 +27,7 @@ The Pixhawk4 flight controller is sold by [Holybro](http://www.holybro.com/produ - SERIAL1 -> UART2 (Telem1) - SERIAL2 -> UART3 (Telem2) - SERIAL3 -> UART1 (GPS) - - SERIAL4 -> UART4 (GPS2) + - SERIAL4 -> UART4 (GPS2, marked UART/I2CB) - SERIAL5 -> UART6 (spare) - SERIAL6 -> UART7 (spare, debug) @@ -157,7 +157,7 @@ outputs support all PWM output formats, but not DShot. The remaining 8 outputs (labelled AUX1 to AUX8) are the "auxillary" outputs. These are directly attached to the STM32F765 and support all -PWM protocols. The first 6 of the auxillary PWM outputs support DShot. +PWM protocols. The first 4 of the auxillary PWM outputs support DShot. The 8 main PWM outputs are in 3 groups: @@ -165,7 +165,7 @@ The 8 main PWM outputs are in 3 groups: - PWM 3 and 4 in group2 - PWM 5, 6, 7 and 8 in group3 -The 8 auxillary PWM outputs are in 2 groups: +The 8 auxillary PWM outputs are in 3 groups: - PWM 1, 2, 3 and 4 in group1 - PWM 5 and 6 in group2 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/R9Pilot/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/R9Pilot/hwdef-bl.dat new file mode 100644 index 0000000000..7f14f28674 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/R9Pilot/hwdef-bl.dat @@ -0,0 +1,44 @@ +# hw definition file for processing by chibios_pins.py +# for FrSky R9Pilot bootloader + +# MCU class and specific type +MCU STM32F7xx STM32F767xx + +# board ID for firmware load +APJ_BOARD_ID 1008 + +# crystal frequency, setup to use external oscillator +OSCILLATOR_HZ 8000000 + +FLASH_SIZE_KB 2048 + +# bootloader starts at zero offset +FLASH_RESERVE_START_KB 0 + +# the location where the bootloader will put the firmware +FLASH_BOOTLOADER_LOAD_KB 96 + + +# order of UARTs (and USB). Allow bootloading on USB +SERIAL_ORDER OTG1 + +# PA10 IO-debug-console +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +PE0 LED_BOOTLOADER OUTPUT LOW +define HAL_LED_ON 0 + +define HAL_USE_EMPTY_STORAGE 1 +define HAL_STORAGE_SIZE 16384 + + +# Add CS pins to ensure they are high in bootloader +PA4 BARO_CS CS +PA1 BARO_CS2 CS +PB12 EXT_CS CS +PA15 IMU_CS CS +PE4 SDCARD_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/R9Pilot/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/R9Pilot/hwdef.dat new file mode 100644 index 0000000000..1ae592249d --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/R9Pilot/hwdef.dat @@ -0,0 +1,184 @@ +# hw definition file for processing by chibios_pins.py +# for FrSky R9Pilot + +# MCU class and specific type +MCU STM32F7xx STM32F767xx + +# board ID for firmware load +APJ_BOARD_ID 1008 + +# crystal frequency, setup to use external oscillator +OSCILLATOR_HZ 8000000 + +FLASH_SIZE_KB 2048 + +# leave 2 sectors free +FLASH_RESERVE_START_KB 96 + + +# one I2C bus (I2C2 can be used with loss of USART3) +I2C_ORDER I2C3 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 USART2 USART3 USART1 UART5 USART6 UART7 UART8 + +# USB +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 +PC4 VBUS INPUT OPENDRAIN + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# SPI1 for baro +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 +PA4 BARO_CS CS +PA1 BARO_CS2 CS + +# SPI2 external (gyro box, 7 pin ribbon cable) +PB13 SPI2_SCK SPI2 +PB14 SPI2_MISO SPI2 +PB15 SPI2_MOSI SPI2 +PB12 EXT_CS CS + +# SPI3 for on-board IMU +PC10 SPI3_SCK SPI3 +PC11 SPI3_MISO SPI3 +PC12 SPI3_MOSI SPI3 +PA15 IMU_CS CS +PE8 MPU3_INT INPUT + +# SPI4 for microSD +PE4 SDCARD_CS CS +PE2 SPI4_SCK SPI4 +PE5 SPI4_MISO SPI4 +PE6 SPI4_MOSI SPI4 + +# I2C3 +PA8 I2C3_SCL I2C3 +PC9 I2C3_SDA I2C3 + +# I2C2 (if not USART3) +# PB10 I2C2_SCL I2C2 +# PB11 I2C2_SDA I2C2 + +# USART1 for GPS +PA10 USART1_RX USART1 +PA9 USART1_TX USART1 + +# USART2 for telem1 +PD5 USART2_TX USART2 +PD6 USART2_RX USART2 + +# USART3 for telem2 +PB11 USART3_RX USART3 +PB10 USART3_TX USART3 + +# UART5 spare uart +PB5 UART5_RX UART5 +PB6 UART5_TX UART5 + +# USART6, Pixel OSD +PC7 USART6_RX USART6 +PC6 USART6_TX USART6 + +# UART7, used for SBUS input +PB3 UART7_RX UART7 +PB4 UART7_TX UART7 + +# alternatively use UART7 RX for RCInput using timer +PB3 TIM2_CH2 TIM2 RCININT PULLDOWN LOW ALT(1) + +# UART8, marked "RX RFD", connected to RXSR receiver via +# 7-pin ribbon cable +PE1 UART8_TX UART8 NODMA + +PC3 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PC2 BATT_CURRENT_SENS ADC1 SCALE(1) + +# define default battery setup +define HAL_BATT_VOLT_PIN 13 +define HAL_BATT_CURR_PIN 12 +define HAL_BATT_VOLT_SCALE 10.1 +define HAL_BATT_CURR_SCALE 17.0 + +# analog RSSI +PC5 RSSI_ADC ADC1 +define BOARD_RSSI_ANA_PIN 15 + +# analog pitot option (not on prototype boards) +PC0 PRESSURE_SENS ADC1 SCALE(2) +define HAL_DEFAULT_AIRSPEED_PIN 10 + +PE0 LED0 OUTPUT LOW GPIO(90) # blue +PA3 LED1 OUTPUT LOW GPIO(91) # green +define HAL_GPIO_A_LED_PIN 91 +define HAL_GPIO_B_LED_PIN 90 +define HAL_GPIO_LED_OFF 1 + +# PWM outputs +PB0 TIM3_CH3 TIM3 PWM(1) GPIO(50) +PB1 TIM3_CH4 TIM3 PWM(2) GPIO(51) +PE9 TIM1_CH1 TIM1 PWM(3) GPIO(52) +PE11 TIM1_CH2 TIM1 PWM(4) GPIO(53) +PE14 TIM1_CH4 TIM1 PWM(5) GPIO(54) +PB7 TIM4_CH2 TIM4 PWM(6) GPIO(55) +PB8 TIM4_CH3 TIM4 PWM(7) GPIO(56) +PB9 TIM4_CH4 TIM4 PWM(8) GPIO(57) + +# tonealarm support +PA0 TIM5_CH1 TIM5 GPIO(32) ALARM + +# GPIOs +PE3 SD_DETECT INPUT + +# switch1 +PC8 SW1 GPIO(70) + +DMA_PRIORITY SPI* ADC* + +define HAL_STORAGE_SIZE 16384 +define STORAGE_FLASH_PAGE 1 + +# spi devices +SPIDEV icm20602 SPI3 DEVID1 IMU_CS MODE3 1*MHZ 8*MHZ +SPIDEV spl06 SPI1 DEVID1 BARO_CS MODE3 1*MHZ 1*MHZ +SPIDEV imu2 SPI2 DEVID1 EXT_CS MODE3 1*MHZ 8*MHZ +SPIDEV sdcard SPI4 DEVID1 SDCARD_CS MODE0 400*KHZ 25*MHZ + +# no built-in compass, but probe the i2c bus for all possible +# external compass types +define ALLOW_ARM_NO_COMPASS +define HAL_COMPASS_DEFAULT HAL_COMPASS_NONE +define HAL_PROBE_EXTERNAL_I2C_COMPASSES +define HAL_I2C_INTERNAL_MASK 0 + +# one main IMU +IMU Invensense SPI:icm20602 ROTATION_PITCH_180_YAW_90 + +# optional 2nd IMU, support any invensense part, board +# may come with a ICM20601 IMU in a plastic case, called +# "gyro box" +IMU Invensense SPI:imu2 ROTATION_YAW_90 + +# also support newer Invensense IMUs +IMU Invensensev2 SPI:imu2 ROTATION_YAW_90 + +define HAL_DEFAULT_INS_FAST_SAMPLE 3 + +# one BARO, multiple possible choices for different +# board varients +BARO SPL06 SPI:spl06 + +# dummy for testing +# BARO Dummy + +# FAT filesystem on microSD +define HAL_OS_FATFS_IO 1 +define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" +define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" + +define BOARD_PWM_COUNT_DEFAULT 8 + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SuccexF4/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/SuccexF4/hwdef-bl.dat new file mode 100644 index 0000000000..b58c077b67 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/SuccexF4/hwdef-bl.dat @@ -0,0 +1,43 @@ +# hw definition file for processing by chibios_pins.py +# for SuccexF4 bootloader + +# MCU class and specific type +MCU STM32F4xx STM32F405xx + +# board ID for firmware load +APJ_BOARD_ID 1011 + +# crystal frequency +OSCILLATOR_HZ 8000000 + +FLASH_SIZE_KB 1024 + +# don't allow bootloader to use more than 16k +FLASH_USE_MAX_KB 16 + +# bootloader is installed at zero offset +FLASH_RESERVE_START_KB 0 + +# LEDs +PB5 LED_BOOTLOADER OUTPUT LOW +define HAL_LED_ON 0 + +# the location where the bootloader will put the firmware +FLASH_BOOTLOADER_LOAD_KB 64 + + +# order of UARTs +SERIAL_ORDER OTG1 + +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +define HAL_USE_EMPTY_STORAGE 1 +define HAL_STORAGE_SIZE 15360 + + +# Add CS pins to ensure they are high in bootloader +PA4 ICM20689_1_CS CS +PC3 ICM20689_2_CS CS +PB12 AT7456E_CS CS +PA15 FLASH_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SuccexF4/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/SuccexF4/hwdef.dat new file mode 100644 index 0000000000..817ad11248 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/SuccexF4/hwdef.dat @@ -0,0 +1,136 @@ +# hw definition file for processing by chibios_pins.py +# SuccexF4 + +MCU STM32F4xx STM32F405xx + +HAL_CHIBIOS_ARCH_F405 1 + +# board ID for firmware load +APJ_BOARD_ID 1011 + +# crystal frequency +OSCILLATOR_HZ 8000000 + +STM32_ST_USE_TIMER 5 + +# flash size +FLASH_SIZE_KB 1024 +FLASH_RESERVE_START_KB 64 + +# ADC +PC1 BAT_CURR_SENS ADC1 SCALE(1) +PC2 BAT_VOLT_SENS ADC1 SCALE(1) + +# PWM outputs +PB0 TIM1_CH2N TIM1 PWM(1) GPIO(50) +PB1 TIM1_CH3N TIM1 PWM(2) GPIO(51) +PC9 TIM8_CH4 TIM8 PWM(3) GPIO(52) +PC8 TIM8_CH3 TIM8 PWM(4) GPIO(53) + +# Two IMUs on SPI1 +PC4 ICM20689_1_DRDY INPUT +PA8 ICM20689_2_DRDY INPUT +PA4 ICM20689_1_CS CS +PC3 ICM20689_2_CS CS +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 + +# OSD on SPI2 +PB12 AT7456E_CS CS +PB13 SPI2_SCK SPI2 +PB14 SPI2_MISO SPI2 +PB15 SPI2_MOSI SPI2 + +# FLASH on SPI3 +PA15 FLASH_CS CS +PC10 SPI3_SCK SPI3 +PC11 SPI3_MISO SPI3 +PC12 SPI3_MOSI SPI3 + +# Order of I2C buses +I2C_ORDER I2C1 + +# UART ports and I2C bus +SERIAL_ORDER OTG1 USART1 USART2 USART3 USART6 + +# Note that this board needs pull-ups on I2C pins +PB8 I2C1_SCL I2C1 PULLUP +PB9 I2C1_SDA I2C1 PULLUP + +PA10 USART1_RX USART1 +PA9 USART1_TX USART1 + +PA3 USART2_RX USART2 +PA2 USART2_TX USART2 + +PB11 USART3_RX USART3 +PB10 USART3_TX USART3 + +PC7 USART6_RX USART6 +PC6 USART6_TX USART6 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# LED and buzzer +PB4 TIM3_CH1 TIM3 GPIO(56) ALARM +PB5 LED OUTPUT HIGH GPIO(57) +define HAL_GPIO_A_LED_PIN 57 + +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 +PC5 VBUS INPUT OPENDRAIN + +# LED strip pad as RC input +PB6 TIM4_CH1 TIM4 RCININT PULLDOWN LOW + +# SPI Device table +SPIDEV icm20689_1 SPI1 DEVID1 ICM20689_1_CS MODE3 1*MHZ 8*MHZ +SPIDEV icm20689_2 SPI1 DEVID2 ICM20689_2_CS MODE3 1*MHZ 8*MHZ +SPIDEV osd SPI2 DEVID3 AT7456E_CS MODE0 10*MHZ 10*MHZ +SPIDEV dataflash SPI3 DEVID4 FLASH_CS MODE3 32*MHZ 32*MHZ + +# Two IMUs +IMU Invensense SPI:icm20689_1 ROTATION_YAW_270 +IMU Invensense SPI:icm20689_2 ROTATION_NONE + +# one baro +BARO BMP280 I2C:0:0x76 +define HAL_PROBE_EXTERNAL_I2C_BAROS +define HAL_BARO_ALLOW_INIT_NO_BARO + +# no built-in compass, but probe the i2c bus for all possible +# external compass types +define ALLOW_ARM_NO_COMPASS +define HAL_COMPASS_DEFAULT HAL_COMPASS_NONE +define HAL_PROBE_EXTERNAL_I2C_COMPASSES +define HAL_I2C_INTERNAL_MASK 0 +define HAL_COMPASS_AUTO_ROT_DEFAULT 2 + +define STORAGE_FLASH_PAGE 1 +define HAL_STORAGE_SIZE 15360 + +# enable logging to dataflash +define HAL_LOGGING_DATAFLASH + +# define default battery setup +define HAL_BATT_VOLT_PIN 12 +define HAL_BATT_CURR_PIN 11 +define HAL_BATT_VOLT_SCALE 11 +define HAL_BATT_CURR_SCALE 18.2 + +define OSD_ENABLED 1 +define HAL_OSD_TYPE_DEFAULT 1 + +define BOARD_PWM_COUNT_DEFAULT 4 + +#font for the osd +ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin + +# disable parachute and sprayer to save flash +define HAL_PARACHUTE_ENABLED 0 +define HAL_SPRAYER_ENABLED 0 + +# reduce max size of embedded params for apj_tool.py +define AP_PARAM_MAX_EMBEDDED_PARAM 1024 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/TBS-Colibri-F7/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/TBS-Colibri-F7/hwdef-bl.dat index 4c9eb4fed3..5e9ec17024 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/TBS-Colibri-F7/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/TBS-Colibri-F7/hwdef-bl.dat @@ -7,14 +7,6 @@ MCU STM32F7xx STM32F767xx # crystal frequency OSCILLATOR_HZ 16000000 -define STM32_LSECLK 32768U -define STM32_LSEDRV (3U << 3U) -define STM32_PLLSRC STM32_PLLSRC_HSE -define STM32_PLLM_VALUE 8 -define STM32_PLLN_VALUE 216 -define STM32_PLLP_VALUE 2 -define STM32_PLLQ_VALUE 9 - # board ID for firmware load APJ_BOARD_ID 50 @@ -39,11 +31,9 @@ PC6 LED_BOOTLOADER OUTPUT HIGH PC7 LED_ACTIVITY OUTPUT HIGH define HAL_LED_ON 0 -# board voltage -STM32_VDD 330U # order of UARTs (and USB) -UART_ORDER OTG1 USART2 UART7 +SERIAL_ORDER OTG1 USART2 UART7 # USART2 is telem1 PD6 USART2_RX USART2 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/TBS-Colibri-F7/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/TBS-Colibri-F7/hwdef.dat index 3e79a34b00..b4a9eb0525 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/TBS-Colibri-F7/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/TBS-Colibri-F7/hwdef.dat @@ -13,7 +13,7 @@ undef PE3 PE3 VDD_3V3_SENSORS_EN OUTPUT LOW # order of UARTs (and USB). Telem2 is UART4 on the mini, USART3 is not available -UART_ORDER OTG1 USART1 USART2 UART4 USART6 UART7 OTG2 +SERIAL_ORDER OTG1 USART2 UART4 USART1 USART6 UART7 OTG2 # enable TX on USART6 (disabled for fmuv5 with iomcu) PG14 USART6_TX USART6 NODMA diff --git a/libraries/AP_HAL_ChibiOS/hwdef/VRBrain-v51/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/VRBrain-v51/hwdef-bl.dat index c7e7d9162a..3f715df0dd 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/VRBrain-v51/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/VRBrain-v51/hwdef-bl.dat @@ -10,13 +10,10 @@ APJ_BOARD_ID 1151 # crystal frequency OSCILLATOR_HZ 8000000 -STM32_PLLM_VALUE 8 # flash size FLASH_SIZE_KB 1024 -# board voltage -STM32_VDD 330U # USB setup USB_VENDOR 0x27AC @@ -38,7 +35,7 @@ STM32_ST_USE_TIMER 5 # order of UARTs (and USB) -UART_ORDER OTG1 +SERIAL_ORDER OTG1 PA9 VBUS INPUT diff --git a/libraries/AP_HAL_ChibiOS/hwdef/VRBrain-v51/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/VRBrain-v51/hwdef.dat index e6e323b9cc..669138d008 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/VRBrain-v51/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/VRBrain-v51/hwdef.dat @@ -11,13 +11,10 @@ APJ_BOARD_ID 1151 # crystal frequency OSCILLATOR_HZ 8000000 -STM32_PLLM_VALUE 8 # flash size FLASH_SIZE_KB 1024 -# board voltage -STM32_VDD 330U # USB setup USB_VENDOR 0x27AC @@ -32,7 +29,7 @@ STM32_ST_USE_TIMER 5 I2C_ORDER I2C2 I2C1 # order of UARTs (and USB) -UART_ORDER OTG1 USART1 USART3 USART2 +SERIAL_ORDER OTG1 USART3 USART2 USART1 STDOUT_SERIAL SD3 STDOUT_BAUDRATE 57600 @@ -136,7 +133,6 @@ define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" define HAL_STORAGE_SIZE 16384 -define STORAGE_FLASH_PAGE 22 # enable RAMTROM parameter storage define HAL_WITH_RAMTRON 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/VRBrain-v52/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/VRBrain-v52/hwdef-bl.dat index 5e4c3b85b0..ced545715e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/VRBrain-v52/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/VRBrain-v52/hwdef-bl.dat @@ -10,13 +10,10 @@ APJ_BOARD_ID 1152 # crystal frequency OSCILLATOR_HZ 8000000 -STM32_PLLM_VALUE 8 # flash size FLASH_SIZE_KB 1024 -# board voltage -STM32_VDD 330U # USB setup USB_VENDOR 0x27AC @@ -38,7 +35,7 @@ STM32_ST_USE_TIMER 5 # order of UARTs (and USB) -UART_ORDER OTG1 +SERIAL_ORDER OTG1 PA9 VBUS INPUT diff --git a/libraries/AP_HAL_ChibiOS/hwdef/VRBrain-v52/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/VRBrain-v52/hwdef.dat index e1ca735d17..5ef6ce184e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/VRBrain-v52/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/VRBrain-v52/hwdef.dat @@ -11,13 +11,10 @@ APJ_BOARD_ID 1152 # crystal frequency OSCILLATOR_HZ 8000000 -STM32_PLLM_VALUE 8 # flash size FLASH_SIZE_KB 1024 -# board voltage -STM32_VDD 330U # USB setup USB_VENDOR 0x27AC @@ -32,7 +29,7 @@ STM32_ST_USE_TIMER 5 I2C_ORDER I2C2 I2C1 # order of UARTs (and USB) -UART_ORDER OTG1 USART1 USART3 USART2 +SERIAL_ORDER OTG1 USART3 USART2 USART1 STDOUT_SERIAL SD3 STDOUT_BAUDRATE 57600 @@ -136,7 +133,6 @@ define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" define HAL_STORAGE_SIZE 16384 -define STORAGE_FLASH_PAGE 22 # enable RAMTROM parameter storage define HAL_WITH_RAMTRON 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/VRBrain-v54/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/VRBrain-v54/hwdef-bl.dat index 505df5b73a..c90ad61822 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/VRBrain-v54/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/VRBrain-v54/hwdef-bl.dat @@ -15,8 +15,6 @@ OSCILLATOR_HZ 24000000 # flash size FLASH_SIZE_KB 2048 -# board voltage -STM32_VDD 330U # USB setup USB_VENDOR 0x27AC @@ -38,7 +36,7 @@ STM32_ST_USE_TIMER 5 # order of UARTs (and USB) -UART_ORDER OTG1 +SERIAL_ORDER OTG1 PA9 VBUS INPUT diff --git a/libraries/AP_HAL_ChibiOS/hwdef/VRBrain-v54/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/VRBrain-v54/hwdef.dat index efdb98d8c6..349964400e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/VRBrain-v54/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/VRBrain-v54/hwdef.dat @@ -16,8 +16,6 @@ OSCILLATOR_HZ 24000000 # flash size FLASH_SIZE_KB 2048 -# board voltage -STM32_VDD 330U # USB setup USB_VENDOR 0x27AC @@ -32,7 +30,7 @@ STM32_ST_USE_TIMER 5 I2C_ORDER I2C2 I2C1 # order of UARTs (and USB) -UART_ORDER OTG1 USART1 USART3 USART2 +SERIAL_ORDER OTG1 USART3 USART2 USART1 STDOUT_SERIAL SD3 STDOUT_BAUDRATE 57600 @@ -136,7 +134,6 @@ define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" define HAL_STORAGE_SIZE 16384 -define STORAGE_FLASH_PAGE 22 # enable RAMTROM parameter storage define HAL_WITH_RAMTRON 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/VRCore-v10/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/VRCore-v10/hwdef-bl.dat index 4e5643981c..d89cd0f85d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/VRCore-v10/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/VRCore-v10/hwdef-bl.dat @@ -10,13 +10,10 @@ APJ_BOARD_ID 1910 # crystal frequency OSCILLATOR_HZ 8000000 -STM32_PLLM_VALUE 8 # flash size FLASH_SIZE_KB 1024 -# board voltage -STM32_VDD 330U # USB setup USB_VENDOR 0x27AC @@ -38,7 +35,7 @@ STM32_ST_USE_TIMER 5 # order of UARTs (and USB) -UART_ORDER OTG1 +SERIAL_ORDER OTG1 PA9 VBUS INPUT diff --git a/libraries/AP_HAL_ChibiOS/hwdef/VRCore-v10/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/VRCore-v10/hwdef.dat index 5853892dc3..4f8d056ba5 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/VRCore-v10/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/VRCore-v10/hwdef.dat @@ -11,13 +11,10 @@ APJ_BOARD_ID 1910 # crystal frequency OSCILLATOR_HZ 8000000 -STM32_PLLM_VALUE 8 # flash size FLASH_SIZE_KB 1024 -# board voltage -STM32_VDD 330U # USB setup USB_VENDOR 0x27AC @@ -32,7 +29,7 @@ STM32_ST_USE_TIMER 5 I2C_ORDER I2C2 I2C1 # order of UARTs (and USB) -UART_ORDER OTG1 USART1 USART3 USART2 +SERIAL_ORDER OTG1 USART3 USART2 USART1 STDOUT_SERIAL SD3 STDOUT_BAUDRATE 57600 @@ -136,7 +133,6 @@ define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" define HAL_STORAGE_SIZE 16384 -define STORAGE_FLASH_PAGE 22 # enable RAMTROM parameter storage define HAL_WITH_RAMTRON 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/VRUBrain-v51/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/VRUBrain-v51/hwdef-bl.dat index 7fd19bbcdc..0c6feabbd1 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/VRUBrain-v51/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/VRUBrain-v51/hwdef-bl.dat @@ -10,13 +10,10 @@ APJ_BOARD_ID 1351 # crystal frequency OSCILLATOR_HZ 8000000 -STM32_PLLM_VALUE 8 # flash size FLASH_SIZE_KB 1024 -# board voltage -STM32_VDD 330U # USB setup USB_VENDOR 0x27AC @@ -38,7 +35,7 @@ STM32_ST_USE_TIMER 5 # order of UARTs (and USB) -UART_ORDER OTG1 +SERIAL_ORDER OTG1 PA9 VBUS INPUT diff --git a/libraries/AP_HAL_ChibiOS/hwdef/VRUBrain-v51/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/VRUBrain-v51/hwdef.dat index 2de2ce1c15..dc4832bfdc 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/VRUBrain-v51/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/VRUBrain-v51/hwdef.dat @@ -11,13 +11,10 @@ APJ_BOARD_ID 1351 # crystal frequency OSCILLATOR_HZ 8000000 -STM32_PLLM_VALUE 8 # flash size FLASH_SIZE_KB 1024 -# board voltage -STM32_VDD 330U # USB setup USB_VENDOR 0x27AC @@ -32,7 +29,7 @@ STM32_ST_USE_TIMER 5 I2C_ORDER I2C2 I2C1 # order of UARTs (and USB) -UART_ORDER OTG1 USART1 USART3 USART2 +SERIAL_ORDER OTG1 USART3 USART2 USART1 STDOUT_SERIAL SD3 STDOUT_BAUDRATE 57600 @@ -143,6 +140,8 @@ FLASH_RESERVE_START_KB 64 # enable RAMTROM parameter storage #define HAL_WITH_RAMTRON 1 +define AP_PARAM_MAX_EMBEDDED_PARAM 1024 + # enable FAT filesystem define HAL_OS_FATFS_IO 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef-bl.dat index dd09260706..2219182062 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef-bl.dat @@ -9,7 +9,7 @@ FLASH_RESERVE_START_KB 0 FLASH_BOOTLOADER_LOAD_KB 34 # board ID for firmware load -APJ_BOARD_ID 1003 +APJ_BOARD_ID 1005 # setup build for a peripheral firmware env AP_PERIPH 1 @@ -17,7 +17,9 @@ env AP_PERIPH 1 define HAL_BOARD_AP_PERIPH_ZUBAXGNSS define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_ZubaxGNSS" -define HAL_CAN_DEFAULT_NODE_ID 114 + +# use DNA +define HAL_CAN_DEFAULT_NODE_ID 0 # crystal frequency OSCILLATOR_HZ 16000000 @@ -40,8 +42,6 @@ RAM_RESERVE_START 256 PB10 USART3_TX USART3 SPEED_HIGH NODMA PB11 USART3_RX USART3 SPEED_HIGH NODMA -# board voltage -STM32_VDD 330U PB7 PERIPH_RESET OUTPUT HIGH @@ -120,7 +120,7 @@ define AP_PARAM_MAX_EMBEDDED_PARAM 0 PA2 USART2_TX USART2 SPEED_HIGH NODMA PA3 USART2_RX USART2 SPEED_HIGH NODMA -UART_ORDER +SERIAL_ORDER define HAL_STORAGE_SIZE 800 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef.dat index 4de76fc34a..45a6d2c51a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef.dat @@ -20,7 +20,7 @@ define STORAGE_FLASH_PAGE 126 define HAL_STORAGE_SIZE 800 # board ID for firmware load -APJ_BOARD_ID 1003 +APJ_BOARD_ID 1005 # setup build for a peripheral firmware env AP_PERIPH 1 @@ -42,8 +42,6 @@ FLASH_RESERVE_END_KB 2 STDOUT_SERIAL SD3 STDOUT_BAUDRATE 115200 -# board voltage -STM32_VDD 330U # enable pin for GPS PB7 GPS_ENABLE OUTPUT HIGH @@ -93,7 +91,7 @@ PC12 SPI3_MOSI SPI3 SPEED_HIGH ######################### # order of UARTs -UART_ORDER USART3 USART2 +SERIAL_ORDER USART3 EMPTY EMPTY USART2 SPIDEV ms5611 SPI3 DEVID1 BARO_CS MODE3 8*MHZ 8*MHZ SPIDEV lis3mdl SPI3 DEVID2 MAG_CS MODE3 500*KHZ 500*KHZ @@ -131,8 +129,6 @@ define STM32_I2C_USE_I2C1 TRUE define HAL_UART_MIN_TX_SIZE 256 define HAL_UART_MIN_RX_SIZE 128 -define CH_DBG_ENABLE_STACK_CHECK TRUE - define HAL_UART_STACK_SIZE 256 define STORAGE_THD_WA_SIZE 512 @@ -156,7 +152,8 @@ BARO MS56XX SPI:ms5611 define HAL_BARO_ALLOW_INIT_NO_BARO -define HAL_CAN_DEFAULT_NODE_ID 114 +# use DNA +define HAL_CAN_DEFAULT_NODE_ID 0 define HAL_NO_GCS define HAL_NO_LOGGING diff --git a/libraries/AP_HAL_ChibiOS/hwdef/airbotf4/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/airbotf4/hwdef-bl.dat index a8e4bdf5bc..530766766b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/airbotf4/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/airbotf4/hwdef-bl.dat @@ -9,7 +9,6 @@ APJ_BOARD_ID 128 # crystal frequency OSCILLATOR_HZ 8000000 -STM32_PLLM_VALUE 8 FLASH_SIZE_KB 1024 @@ -26,11 +25,9 @@ define HAL_LED_ON 0 # the location where the bootloader will put the firmware FLASH_BOOTLOADER_LOAD_KB 64 -# board voltage -STM32_VDD 330U # order of UARTs -UART_ORDER OTG1 +SERIAL_ORDER OTG1 PA11 OTG_FS_DM OTG1 PA12 OTG_FS_DP OTG1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/airbotf4/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/airbotf4/hwdef.dat index 2a83a040a6..f6aa9b7b5f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/airbotf4/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/airbotf4/hwdef.dat @@ -11,10 +11,6 @@ APJ_BOARD_ID 128 # crystal frequency OSCILLATOR_HZ 8000000 -STM32_PLLM_VALUE 8 - -# board voltage -STM32_VDD 330U STM32_ST_USE_TIMER 5 @@ -26,7 +22,7 @@ FLASH_RESERVE_START_KB 64 I2C_ORDER I2C2 # order of UARTs -UART_ORDER OTG1 USART6 USART1 +SERIAL_ORDER OTG1 USART1 EMPTY USART6 #adc PC1 BAT_CURR_SENS ADC1 SCALE(1) @@ -81,8 +77,6 @@ SPIDEV dataflash SPI3 DEVID1 FLASH_CS MODE3 32*MHZ 32*MHZ # enable logging to dataflash define HAL_LOGGING_DATAFLASH -define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_CHIBIOS_AIRBOTF4 - # one IMU IMU Invensense SPI:mpu6000_cs ROTATION_YAW_180 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/board.c b/libraries/AP_HAL_ChibiOS/hwdef/common/board.c index 227dad2e15..44824d232a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/board.c +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/board.c @@ -47,7 +47,7 @@ const PALConfig pal_default_config = {VAL_GPIOE_ODR, VAL_GPIOE_CRL, VAL_GPIOE_CRH}, }; -#else //Other than STM32F1 series +#else //Other than STM32F1/F3 series /** * @brief Type of STM32 GPIO port setup. @@ -173,6 +173,9 @@ static void stm32_gpio_init(void) { #if defined(STM32H7) rccResetAHB4(STM32_GPIO_EN_MASK); rccEnableAHB4(STM32_GPIO_EN_MASK, true); +#elif defined(STM32F3) + rccResetAHB(STM32_GPIO_EN_MASK); + rccEnableAHB(STM32_GPIO_EN_MASK, true); #else rccResetAHB1(STM32_GPIO_EN_MASK); rccEnableAHB1(STM32_GPIO_EN_MASK, true); diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/chconf.h b/libraries/AP_HAL_ChibiOS/hwdef/common/chconf.h index 7162b1e9be..831f5dd352 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/chconf.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/chconf.h @@ -266,7 +266,7 @@ * @note Requires @p CH_CFG_USE_MUTEXES. */ #if !defined(CH_CFG_USE_MUTEXES_RECURSIVE) -#define CH_CFG_USE_MUTEXES_RECURSIVE FALSE +#define CH_CFG_USE_MUTEXES_RECURSIVE TRUE #endif /** @@ -575,7 +575,7 @@ * @p panic_msg variable set to @p NULL. */ #if !defined(CH_DBG_ENABLE_STACK_CHECK) -#define CH_DBG_ENABLE_STACK_CHECK FALSE +#define CH_DBG_ENABLE_STACK_CHECK TRUE #endif /** @@ -725,9 +725,20 @@ #define CH_CFG_SYSTEM_HALT_HOOK(reason) do { \ extern void memory_flush_all(void); \ memory_flush_all(); \ + extern void system_halt_hook(void); \ + system_halt_hook(); \ } while(0) #endif +/** + * @brief stack overflow event hook. + * @details This hook is invoked when we have a stack overflow on task switch + */ +#define CH_CFG_STACK_OVERFLOW_HOOK(tp) { \ + extern void stack_overflow(thread_t *tp); \ + stack_overflow(tp); \ +} + /** * @brief Trace hook. * @details This hook is invoked each time a new record is written in the diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/common.ld b/libraries/AP_HAL_ChibiOS/hwdef/common/common.ld index a1644a499b..bdabc12869 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/common.ld +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/common.ld @@ -70,6 +70,9 @@ SECTIONS .text : ALIGN(4) SUBALIGN(4) { + /* we want app_descriptor near the start of flash so a false + positive isn't found by the bootloader (eg. ROMFS) */ + KEEP(*(.app_descriptor)); *(.text) *(.text.*) *(.rodata) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/flash.c b/libraries/AP_HAL_ChibiOS/hwdef/common/flash.c index 9595e5fafe..b25153fe1a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/flash.c +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/flash.c @@ -53,6 +53,8 @@ #include #include "stm32_util.h" +#include + // #pragma GCC optimize("O0") /* @@ -118,10 +120,18 @@ static const uint32_t flash_memmap[STM32_FLASH_NPAGES] = { KB(32), KB(32), KB(32 #elif defined(STM32F105_MCUCONF) #define STM32_FLASH_NPAGES (BOARD_FLASH_SIZE/2) #define STM32_FLASH_FIXED_PAGE_SIZE 2 +#elif defined(STM32F303_MCUCONF) +#define STM32_FLASH_NPAGES (BOARD_FLASH_SIZE/2) +#define STM32_FLASH_FIXED_PAGE_SIZE 2 #else #error "Unsupported processor for flash.c" #endif +#ifdef STORAGE_FLASH_PAGE +static_assert(STORAGE_FLASH_PAGE < STM32_FLASH_NPAGES, + "STORAGE_FLASH_PAGE out of range"); +#endif + // keep a cache of the page addresses #ifndef STM32_FLASH_FIXED_PAGE_SIZE static uint32_t flash_pageaddr[STM32_FLASH_NPAGES]; @@ -366,7 +376,7 @@ bool stm32_flash_erasepage(uint32_t page) FLASH->CR2 |= FLASH_CR_START; while (FLASH->SR2 & FLASH_SR_QW) ; } -#elif defined(STM32F1) +#elif defined(STM32F1) || defined(STM32F3) FLASH->CR = FLASH_CR_PER; FLASH->AR = stm32_flash_getpageaddr(page); FLASH->CR |= FLASH_CR_STRT; @@ -438,7 +448,8 @@ static bool stm32_flash_write_h7(uint32_t addr, const void *buf, uint32_t count) } stm32_flash_unlock(); while (count >= 32) { - if (!stm32h7_flash_write32(addr, b)) { + if (memcmp((void*)addr, b, 32) != 0 && + !stm32h7_flash_write32(addr, b)) { return false; } // check contents @@ -556,7 +567,7 @@ uint32_t _flash_fail_addr; uint32_t _flash_fail_count; uint8_t *_flash_fail_buf; -#if defined(STM32F1) +#if defined(STM32F1) || defined(STM32F3) static bool stm32_flash_write_f1(uint32_t addr, const void *buf, uint32_t count) { uint8_t *b = (uint8_t *)buf; @@ -616,11 +627,11 @@ failed: #endif return false; } -#endif // STM32F1 +#endif // STM32F1 or STM32F3 bool stm32_flash_write(uint32_t addr, const void *buf, uint32_t count) { -#if defined(STM32F1) +#if defined(STM32F1) || defined(STM32F3) return stm32_flash_write_f1(addr, buf, count); #elif defined(STM32F4) || defined(STM32F7) return stm32_flash_write_f4f7(addr, buf, count); diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/halconf.h b/libraries/AP_HAL_ChibiOS/hwdef/common/halconf.h index 0f2fae5190..538f2100a7 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/halconf.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/halconf.h @@ -263,7 +263,7 @@ * @brief Enforces the driver to use direct callbacks rather than OSAL events. */ #if !defined(CAN_ENFORCE_USE_CALLBACKS) || defined(__DOXYGEN__) -#define CAN_ENFORCE_USE_CALLBACKS FALSE +#define CAN_ENFORCE_USE_CALLBACKS TRUE #endif /*===========================================================================*/ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/hrt.c b/libraries/AP_HAL_ChibiOS/hwdef/common/hrt.c index 21f9cc002f..ded6dc57bd 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/hrt.c +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/hrt.c @@ -41,16 +41,12 @@ for micros64() */ -#if CH_CFG_ST_FREQUENCY != 1000000U && CH_CFG_ST_FREQUENCY != 1000U -#error "unsupported tick frequency" -#endif - #if CH_CFG_ST_RESOLUTION == 16 static uint32_t system_time_u32_us(void) { systime_t now = chVTGetSystemTimeX(); -#if CH_CFG_ST_FREQUENCY == 1000U - now *= 1000U; +#if CH_CFG_ST_FREQUENCY != 1000000U + #error "must use 32 bit timer if system clock not 1MHz" #endif static systime_t last_systime; static uint32_t timer_base_us32; @@ -63,8 +59,8 @@ static uint32_t system_time_u32_us(void) static uint32_t system_time_u32_us(void) { systime_t now = chVTGetSystemTimeX(); -#if CH_CFG_ST_FREQUENCY == 1000U - now *= 1000U; +#if CH_CFG_ST_FREQUENCY != 1000000U + now *= 1000000U/CH_CFG_ST_FREQUENCY; #endif return now; } diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/malloc.c b/libraries/AP_HAL_ChibiOS/hwdef/common/malloc.c index 543df832a2..a266f9c3d8 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/malloc.c +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/malloc.c @@ -287,3 +287,18 @@ void memory_flush_all(void) stm32_cacheBufferFlush(memory_regions[i].address, memory_regions[i].size); } } + +/* + replacement for strdup + */ +char *strdup(const char *str) +{ + const size_t len = strlen(str); + char *ret = malloc(len+1); + if (!ret) { + return NULL; + } + memcpy(ret, str, len); + ret[len] = 0; + return ret; +} diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/mcuconf.h b/libraries/AP_HAL_ChibiOS/hwdef/common/mcuconf.h index 1ffd5d8982..8900caa486 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/mcuconf.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/mcuconf.h @@ -39,6 +39,8 @@ #if defined(STM32F1) #include "stm32f1_mcuconf.h" +#elif defined(STM32F3) +#include "stm32f3_mcuconf.h" #elif defined(STM32F4) || defined(STM32F7) #include "stm32f47_mcuconf.h" #elif defined(STM32H7) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.c b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.c index fb72506126..58e481426c 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.c +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.c @@ -260,8 +260,10 @@ enum rtc_boot_magic check_fast_reboot(void) // set RTC register for a fast reboot void set_fast_reboot(enum rtc_boot_magic v) { - uint32_t vv = (uint32_t)v; - set_rtc_backup(0, &vv, 1); + if (check_fast_reboot() != v) { + uint32_t vv = (uint32_t)v; + set_rtc_backup(0, &vv, 1); + } } #else // NO_FASTBOOT @@ -319,7 +321,7 @@ void peripheral_power_enable(void) #endif } -#if defined(STM32F7) || defined(STM32H7) || defined(STM32F4) +#if defined(STM32F7) || defined(STM32H7) || defined(STM32F4) || defined(STM32F3) /* read mode of a pin. This allows a pin config to be read, changed and then written back @@ -340,7 +342,18 @@ iomode_t palReadLineMode(ioline_t line) } return ret; } -#endif + +/* + set pin as pullup, pulldown or floating + */ +void palLineSetPushPull(ioline_t line, enum PalPushPull pp) +{ + ioportid_t port = PAL_PORT(line); + uint8_t pad = PAL_PAD(line); + port->PUPDR = (port->PUPDR & ~(3<<(pad*2))) | (pp<<(pad*2)); +} + +#endif // F7, H7, F4 void stm32_cacheBufferInvalidate(const void *p, size_t size) { @@ -351,3 +364,88 @@ void stm32_cacheBufferFlush(const void *p, size_t size) { cacheBufferFlush(p, size); } + + +#ifdef HAL_GPIO_PIN_FAULT +/* + optional support for hard-fault debugging using soft-serial output to a pin + To use this setup a pin like this: + + Pxx FAULT OUTPUT HIGH + + for some pin Pxx + + On a STM32F405 the baudrate will be around 42kBaud. Use the + auto-baud function on your logic analyser to decode +*/ +/* + send one bit out a debug line + */ +static void fault_send_bit(ioline_t line, uint8_t b) +{ + palWriteLine(line, b); + for (uint32_t i=0; i<1000; i++) { + palWriteLine(line, b); + } +} + +/* + send a byte out a debug line + */ +static void fault_send_byte(ioline_t line, uint8_t b) +{ + fault_send_bit(line, 0); // start bit + for (uint8_t i=0; i<8; i++) { + uint8_t bit = (b & (1U<name); + // if we get here then we are armed and got a stack overflow. We + // will report an internal error and keep trying to fly. We are + // quite likely to crash anyway due to memory corruption. The + // watchdog data should record the thread name and fault type +#else + (void)tp; +#endif +} diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.h b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.h index 2705e053f0..6fa15ea235 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.h @@ -58,7 +58,8 @@ enum rtc_boot_magic { RTC_BOOT_OFF = 0, RTC_BOOT_HOLD = 0xb0070001, RTC_BOOT_FAST = 0xb0070002, - RTC_BOOT_CANBL = 0xb0080000 // ORd with 8 bit local node ID + RTC_BOOT_CANBL = 0xb0080000, // ORd with 8 bit local node ID + RTC_BOOT_FWOK = 0xb0093a26 // indicates FW ran for 30s }; // see if RTC registers is setup for a fast reboot @@ -77,8 +78,16 @@ void malloc_init(void); read mode of a pin. This allows a pin config to be read, changed and then written back */ -#if defined(STM32F7) || defined(STM32H7) || defined(STM32F4) +#if defined(STM32F7) || defined(STM32H7) || defined(STM32F4) || defined(STM32F3) iomode_t palReadLineMode(ioline_t line); + +enum PalPushPull { + PAL_PUSHPULL_NOPULL=0, + PAL_PUSHPULL_PULLUP=1, + PAL_PUSHPULL_PULLDOWN=2 +}; + +void palLineSetPushPull(ioline_t line, enum PalPushPull pp); #endif // set n RTC backup registers starting at given idx @@ -90,6 +99,17 @@ void get_rtc_backup(uint8_t idx, uint32_t *v, uint8_t n); void stm32_cacheBufferInvalidate(const void *p, size_t size); void stm32_cacheBufferFlush(const void *p, size_t size); +#ifdef HAL_GPIO_PIN_FAULT +// printf for fault handlers +void fault_printf(const char *fmt, ...); +#endif + +// halt hook for printing panic message +void system_halt_hook(void); + +// hook for stack overflow +void stack_overflow(thread_t *tp); + #ifdef __cplusplus } #endif diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32f3_mcuconf.h b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32f3_mcuconf.h new file mode 100644 index 0000000000..02a107bfb0 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32f3_mcuconf.h @@ -0,0 +1,174 @@ +/* + ChibiOS - Copyright (C) 2006..2016 Giovanni Di Sirio + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + http://www.apache.org/licenses/LICENSE-2.0 + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. +*/ + +#pragma once +/* + * STM32F303 drivers configuration. + * The following settings override the default settings present in + * the various device driver implementation headers. + * Note that the settings for each driver only have effect if the whole + * driver is enabled in halconf.h. + * + * IRQ priorities: + * 15...0 Lowest...Highest. + * + * DMA priorities: + * 0...3 Lowest...Highest. + */ + +#define STM32F3xx_MCUCONF + +/* + * HAL driver system settings. + */ +#define STM32_NO_INIT FALSE +#define STM32_HSI_ENABLED FALSE +#define STM32_LSI_ENABLED FALSE +#define STM32_HSE_ENABLED TRUE +#define STM32_LSE_ENABLED FALSE + +#if STM32_HSECLK == 8000000U +#define STM32_SW STM32_SW_PLL +#define STM32_PLLSRC STM32_PLLSRC_HSE +#define STM32_PLLXTPRE STM32_PLLXTPRE_DIV1 +#define STM32_PLLMUL_VALUE 9 +#define STM32_PPRE1 STM32_PPRE1_DIV2 +#define STM32_PPRE2 STM32_PPRE2_DIV2 +#define STM32_ADCPRE STM32_ADCPRE_DIV4 +#define STM32_HPRE STM32_HPRE_DIV1 +#elif STM32_HSECLK == 24000000U +#define STM32_SW STM32_SW_PLL +#define STM32_PLLSRC STM32_PLLSRC_HSE +#define STM32_PLLXTPRE STM32_PLLXTPRE_DIV1 +#define STM32_PLLMUL_VALUE 3 +#define STM32_PPRE1 STM32_PPRE1_DIV2 +#define STM32_PPRE2 STM32_PPRE2_DIV2 +#define STM32_ADCPRE STM32_ADCPRE_DIV4 +#define STM32_HPRE STM32_HPRE_DIV1 +#else +#error "Unsupported STM32F1xx clock frequency" +#endif + +#define STM32_MCOSEL STM32_MCOSEL_NOCLOCK +#define STM32_RTCSEL STM32_RTCSEL_HSEDIV +#define STM32_PVD_ENABLE FALSE +#define STM32_PLS STM32_PLS_LEV0 + +/* + * ADC driver system settings. + */ +#define STM32_ADC_ADC1_DMA_PRIORITY 2 +#define STM32_ADC_ADC1_IRQ_PRIORITY 6 + +/* + * EXT driver system settings. + */ +#define STM32_EXT_EXTI0_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI1_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI2_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI3_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI4_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI5_9_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI10_15_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI16_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI17_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI18_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI19_IRQ_PRIORITY 6 + +/* + * GPT driver system settings. + */ +#define STM32_GPT_TIM1_IRQ_PRIORITY 7 +#define STM32_GPT_TIM2_IRQ_PRIORITY 7 +#define STM32_GPT_TIM3_IRQ_PRIORITY 7 +#define STM32_GPT_TIM4_IRQ_PRIORITY 7 +#define STM32_GPT_TIM5_IRQ_PRIORITY 7 +#define STM32_GPT_TIM8_IRQ_PRIORITY 7 + +/* + * I2C driver system settings. + */ +#define STM32_I2C_BUSY_TIMEOUT 50 +#define STM32_I2C_I2C1_IRQ_PRIORITY 5 +#define STM32_I2C_I2C2_IRQ_PRIORITY 5 +#define STM32_I2C_I2C1_DMA_PRIORITY 3 +#define STM32_I2C_I2C2_DMA_PRIORITY 3 +#define STM32_I2C_DMA_ERROR_HOOK(i2cp) osalSysHalt("DMA failure") + +/* + * ICU driver system settings. + */ +#define STM32_ICU_TIM1_IRQ_PRIORITY 7 +#define STM32_ICU_TIM2_IRQ_PRIORITY 7 +#define STM32_ICU_TIM3_IRQ_PRIORITY 7 +#define STM32_ICU_TIM4_IRQ_PRIORITY 7 +#define STM32_ICU_TIM5_IRQ_PRIORITY 7 +#define STM32_ICU_TIM8_IRQ_PRIORITY 7 + +/* + * PWM driver system settings. + */ +#define STM32_PWM_TIM1_IRQ_PRIORITY 7 +#define STM32_PWM_TIM2_IRQ_PRIORITY 7 +#define STM32_PWM_TIM3_IRQ_PRIORITY 7 +#define STM32_PWM_TIM4_IRQ_PRIORITY 7 +#define STM32_PWM_TIM5_IRQ_PRIORITY 7 +#define STM32_PWM_TIM8_IRQ_PRIORITY 7 + +/* + * RTC driver system settings. + */ +#define STM32_RTC_IRQ_PRIORITY 15 + +/* + * SERIAL driver system settings. + */ +#define STM32_SERIAL_USART1_PRIORITY 12 +#define STM32_SERIAL_USART2_PRIORITY 12 +#define STM32_SERIAL_USART3_PRIORITY 12 + +/* + * SPI driver system settings. + */ +#define STM32_SPI_SPI1_DMA_PRIORITY 1 +#define STM32_SPI_SPI2_DMA_PRIORITY 1 +#define STM32_SPI_SPI1_IRQ_PRIORITY 10 +#define STM32_SPI_SPI2_IRQ_PRIORITY 10 +#define STM32_SPI_DMA_ERROR_HOOK(spip) osalSysHalt("DMA failure") + +/* + * ST driver system settings. + */ +#define STM32_ST_IRQ_PRIORITY 8 +#ifndef STM32_ST_USE_TIMER +#define STM32_ST_USE_TIMER 2 +#endif +/* + * UART driver system settings. + */ +#define STM32_UART_USART1_IRQ_PRIORITY 12 +#define STM32_UART_USART2_IRQ_PRIORITY 12 +#define STM32_UART_USART3_IRQ_PRIORITY 12 +#define STM32_UART_USART1_DMA_PRIORITY 0 +#define STM32_UART_USART2_DMA_PRIORITY 0 +#define STM32_UART_USART3_DMA_PRIORITY 0 +#define STM32_UART_DMA_ERROR_HOOK(uartp) osalSysHalt("DMA failure") + +/* + * WDG driver system settings. + */ +#define STM32_WDG_USE_IWDG FALSE + +#ifndef STM32_ADC_USE_ADC1 +#define STM32_ADC_USE_ADC1 FALSE +#endif diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32f47_mcuconf.h b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32f47_mcuconf.h index 015b3856a4..a8120d85c9 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32f47_mcuconf.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32f47_mcuconf.h @@ -81,28 +81,60 @@ #ifndef STM32_PLLSRC #define STM32_PLLSRC STM32_PLLSRC_HSE #endif -#ifndef STM32_PLLM_VALUE -#define STM32_PLLM_VALUE 24 -#endif -#ifndef STM32_PLLN_VALUE -#define STM32_PLLN_VALUE 336 -#endif -#ifndef STM32_PLLP_VALUE -#define STM32_PLLP_VALUE 2 -#endif -#ifndef STM32_PLLQ_VALUE -#define STM32_PLLQ_VALUE 7 -#endif -#ifndef STM32_HPRE +#if !defined(HAL_CUSTOM_CLOCK_TREE) +#if defined(STM32F7xx_MCUCONF) +// F7 clock config +#if STM32_HSECLK == 8000000U +#define STM32_PLLM_VALUE 8 +#define STM32_PLLN_VALUE 432 +#define STM32_PLLP_VALUE 2 +#define STM32_PLLQ_VALUE 9 +#elif STM32_HSECLK == 16000000U +#define STM32_PLLM_VALUE 8 +#define STM32_PLLN_VALUE 216 +#define STM32_PLLP_VALUE 2 +#define STM32_PLLQ_VALUE 9 +#elif STM32_HSECLK == 24000000U +#define STM32_PLLM_VALUE 24 +#define STM32_PLLN_VALUE 432 +#define STM32_PLLP_VALUE 2 +#define STM32_PLLQ_VALUE 9 +#else +#error "Unsupported F7 HSE clock" +#endif +#else // F4 +// F4 clock config +#if STM32_HSECLK == 8000000U +#define STM32_PLLM_VALUE 8 +#define STM32_PLLN_VALUE 336 +#define STM32_PLLP_VALUE 2 +#define STM32_PLLQ_VALUE 7 +#elif STM32_HSECLK == 16000000U +#define STM32_PLLM_VALUE 16 +#define STM32_PLLN_VALUE 384 +#define STM32_PLLP_VALUE 4 +#define STM32_PLLQ_VALUE 8 +#elif STM32_HSECLK == 24000000U +#define STM32_PLLM_VALUE 24 +#define STM32_PLLN_VALUE 336 +#define STM32_PLLP_VALUE 2 +#define STM32_PLLQ_VALUE 7 +#else +#error "Unsupported F4 HSE clock" +#endif +#endif // MCU +#endif // HAL_CUSTOM_CLOCK_TREE + +// we don't use LSE, but we need the defines +#define STM32_LSECLK 32768U +#define STM32_LSEDRV (3U << 3U) + +#define STM32_VDD 330U + #define STM32_HPRE STM32_HPRE_DIV1 -#endif -#ifndef STM32_PPRE1 #define STM32_PPRE1 STM32_PPRE1_DIV4 -#endif -#ifndef STM32_PPRE2 #define STM32_PPRE2 STM32_PPRE2_DIV2 -#endif #define STM32_RTCSEL STM32_RTCSEL_LSI #define STM32_RTCPRE_VALUE 8 #define STM32_MCO1SEL STM32_MCO1SEL_HSI diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32h7_mcuconf.h b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32h7_mcuconf.h index f30d6845dc..a232436459 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32h7_mcuconf.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32h7_mcuconf.h @@ -87,6 +87,11 @@ #define STM32_PLL1_DIVM_VALUE 3 #define STM32_PLL2_DIVM_VALUE 3 #define STM32_PLL3_DIVM_VALUE 6 +#elif STM32_HSECLK == 25000000U +// this gives 400MHz system clock +#define STM32_PLL1_DIVM_VALUE 2 +#define STM32_PLL2_DIVM_VALUE 2 +#define STM32_PLL3_DIVM_VALUE 5 #else #error "Unsupported HSE clock" #endif @@ -100,14 +105,30 @@ #define STM32_PLL2_DIVN_VALUE 25 #define STM32_PLL2_DIVP_VALUE 2 -#define STM32_PLL2_DIVQ_VALUE 2 +#define STM32_PLL2_DIVQ_VALUE 4 #define STM32_PLL2_DIVR_VALUE 2 #define STM32_PLL3_DIVN_VALUE 72 #define STM32_PLL3_DIVP_VALUE 3 #define STM32_PLL3_DIVQ_VALUE 6 #define STM32_PLL3_DIVR_VALUE 9 -#endif // 8MHz clock multiples + +#elif STM32_HSECLK == 25000000U +#define STM32_PLL1_DIVN_VALUE 64 +#define STM32_PLL1_DIVP_VALUE 2 +#define STM32_PLL1_DIVQ_VALUE 8 +#define STM32_PLL1_DIVR_VALUE 2 + +#define STM32_PLL2_DIVN_VALUE 12 +#define STM32_PLL2_DIVP_VALUE 1 +#define STM32_PLL2_DIVQ_VALUE 2 +#define STM32_PLL2_DIVR_VALUE 2 + +#define STM32_PLL3_DIVN_VALUE 48 +#define STM32_PLL3_DIVP_VALUE 3 +#define STM32_PLL3_DIVQ_VALUE 5 +#define STM32_PLL3_DIVR_VALUE 8 +#endif // clock selection #define STM32_PLL1_ENABLED TRUE #define STM32_PLL1_P_ENABLED TRUE @@ -158,10 +179,10 @@ #define STM32_QSPISEL STM32_QSPISEL_HCLK #define STM32_FMCSEL STM32_QSPISEL_HCLK #define STM32_SWPSEL STM32_SWPSEL_PCLK1 -#define STM32_FDCANSEL STM32_FDCANSEL_PLL1_Q_CK +#define STM32_FDCANSEL STM32_FDCANSEL_PLL2_Q_CK #define STM32_DFSDM1SEL STM32_DFSDM1SEL_PCLK2 #define STM32_SPDIFSEL STM32_SPDIFSEL_PLL1_Q_CK -#define STM32_SPI45SEL STM32_SPI45SEL_PLL2_Q_CK +#define STM32_SPI45SEL STM32_SPI45SEL_PCLK2 #define STM32_SPI123SEL STM32_SPI123SEL_PLL1_Q_CK #define STM32_SAI23SEL STM32_SAI23SEL_PLL1_Q_CK #define STM32_SAI1SEL STM32_SAI1SEL_PLL1_Q_CK @@ -172,7 +193,7 @@ #define STM32_RNGSEL STM32_RNGSEL_HSI48_CK #define STM32_USART16SEL STM32_USART16SEL_PCLK2 #define STM32_USART234578SEL STM32_USART234578SEL_PCLK1 -#define STM32_SPI6SEL STM32_SPI6SEL_PLL2_Q_CK +#define STM32_SPI6SEL STM32_SPI6SEL_PCLK4 #define STM32_SAI4BSEL STM32_SAI4BSEL_PLL1_Q_CK #define STM32_SAI4ASEL STM32_SAI4ASEL_PLL1_Q_CK #define STM32_ADCSEL STM32_ADCSEL_PLL3_R_CK diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/watchdog.c b/libraries/AP_HAL_ChibiOS/hwdef/common/watchdog.c index b73d5bb5a4..a450643d20 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/watchdog.c +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/watchdog.c @@ -11,7 +11,7 @@ #define IWDG_BASE 0x58004800 #elif defined(STM32F7) || defined(STM32F4) #define IWDG_BASE 0x40003000 -#elif defined(STM32F1) +#elif defined(STM32F1) || defined(STM32F3) #define IWDG_BASE 0x40003000 #else #error "Unsupported IWDG MCU config" @@ -33,7 +33,7 @@ #define WDG_RESET_STATUS (*(__IO uint32_t *)(RCC_BASE + 0x74)) #define WDG_RESET_CLEAR (1U<<24) #define WDG_RESET_IS_IWDG (1U<<29) -#elif defined(STM32F1) +#elif defined(STM32F1) || defined(STM32F3) #define WDG_RESET_STATUS (*(__IO uint32_t *)(RCC_BASE + 0x24)) #define WDG_RESET_CLEAR (1U<<24) #define WDG_RESET_IS_IWDG (1U<<29) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/watchdog.h b/libraries/AP_HAL_ChibiOS/hwdef/common/watchdog.h index f9a53fd7cb..4395bc08c0 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/watchdog.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/watchdog.h @@ -1,3 +1,4 @@ +#pragma once #ifdef __cplusplus extern "C" { diff --git a/libraries/AP_HAL_ChibiOS/hwdef/crazyflie2/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/crazyflie2/hwdef-bl.dat new file mode 100644 index 0000000000..42ba2e4a3d --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/crazyflie2/hwdef-bl.dat @@ -0,0 +1,46 @@ +# hw definition file for processing by chibios_pins.py +# for crazyflie2.0 + +# MCU class and specific type +MCU STM32F4xx STM32F405xx + +# board ID for firmware load +APJ_BOARD_ID 12 + +# crystal frequency +OSCILLATOR_HZ 8000000 + +define STM32_ST_USE_TIMER 5 + +FLASH_SIZE_KB 1024 + +# don't allow bootloader to use more than 16k +FLASH_USE_MAX_KB 16 + +# bootloader is installed at zero offset +FLASH_RESERVE_START_KB 0 + +# LEDs +PD2 LED_BOOTLOADER OUTPUT HIGH +PC0 LED_ACTIVITY OUTPUT HIGH +define HAL_LED_ON 0 + +# the location where the bootloader will put the firmware +FLASH_BOOTLOADER_LOAD_KB 64 + + +# order of UARTs +SERIAL_ORDER OTG1 + +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +define HAL_USE_EMPTY_STORAGE 1 +define HAL_STORAGE_SIZE 15360 + + +# Add CS pins to ensure they are high in bootloader +PC12 E_CS0 CS +PB4 E_CS1 CS +PB5 E_CS2 CS +PB8 E_CS3 CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/crazyflie2/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/crazyflie2/hwdef.dat index 5e747a1b6e..341c5e7532 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/crazyflie2/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/crazyflie2/hwdef.dat @@ -7,18 +7,13 @@ MCU STM32F4xx STM32F405xx # board ID for firmware load APJ_BOARD_ID 12 -define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_CHIBIOS_CRAZYFLIE2 - # crystal frequency OSCILLATOR_HZ 8000000 -STM32_PLLM_VALUE 8 define STM32_ST_USE_TIMER 5 FLASH_SIZE_KB 1024 -# board voltage -STM32_VDD 330U # use USB for stdout #STDOUT_SERIAL SD3 @@ -95,7 +90,7 @@ I2C_ORDER I2C3 I2C1 define HAL_I2C_MAX_CLOCK 400000 # order of UARTs (and USB) -UART_ORDER OTG1 USART2 USART3 USART6 +SERIAL_ORDER OTG1 USART3 USART6 USART2 define HAL_STORAGE_SIZE 15360 define STORAGE_FLASH_PAGE 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f103-ADSB/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/f103-ADSB/hwdef-bl.dat index 8122650811..afd64aba59 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f103-ADSB/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f103-ADSB/hwdef-bl.dat @@ -2,5 +2,6 @@ include ../f103-periph/hwdef-bl.dat define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_adsb" -define HAL_CAN_DEFAULT_NODE_ID 116 +# use DNA +define HAL_CAN_DEFAULT_NODE_ID 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f103-ADSB/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f103-ADSB/hwdef.dat index f318767e99..328ac1c59b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f103-ADSB/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f103-ADSB/hwdef.dat @@ -5,7 +5,8 @@ include ../f103-periph/hwdef.dat define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_adsb" -define HAL_CAN_DEFAULT_NODE_ID 116 +# use DNA +define HAL_CAN_DEFAULT_NODE_ID 0 define HAL_AIRSPEED_BUS_DEFAULT 0 define AIRSPEED_MAX_SENSORS 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f103-GPS/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/f103-GPS/hwdef-bl.dat index f4e4b03fc0..38cbbcfd5f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f103-GPS/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f103-GPS/hwdef-bl.dat @@ -1,6 +1,6 @@ include ../f103-periph/hwdef-bl.dat -# start with a fixed node ID so the board is usable without DNA -define HAL_CAN_DEFAULT_NODE_ID 117 +# use DNA +define HAL_CAN_DEFAULT_NODE_ID 0 define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_gps" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f103-GPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f103-GPS/hwdef.dat index a37c450e3d..5b8026e6f1 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f103-GPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f103-GPS/hwdef.dat @@ -1,10 +1,21 @@ include ../f103-periph/hwdef.dat -# start with a fixed node ID so the board is usable without DNA -define HAL_CAN_DEFAULT_NODE_ID 117 +# use DNA +define HAL_CAN_DEFAULT_NODE_ID 0 define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_gps" +# added rm3100 mag on SPI +SPIDEV rm3100 SPI1 DEVID1 MAG_CS MODE0 1*MHZ 1*MHZ +COMPASS RM3100 SPI:rm3100 false ROTATION_NONE + +# and support all external compass types +define HAL_PROBE_EXTERNAL_I2C_COMPASSES + +# increase TX size for RTCM +undef HAL_UART_MIN_TX_SIZE +define HAL_UART_MIN_TX_SIZE 256 + # GPS+MAG define HAL_PERIPH_ENABLE_GPS define HAL_PERIPH_ENABLE_MAG diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f103-HWESC/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/f103-HWESC/hwdef-bl.dat new file mode 100644 index 0000000000..1f2f387025 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/f103-HWESC/hwdef-bl.dat @@ -0,0 +1,6 @@ +include ../f103-periph/hwdef-bl.dat + +# start with a fixed node ID so the board is usable without DNA +define HAL_CAN_DEFAULT_NODE_ID 0 + +define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_HWESC" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f103-HWESC/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f103-HWESC/hwdef.dat new file mode 100644 index 0000000000..17cba31d02 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/f103-HWESC/hwdef.dat @@ -0,0 +1,7 @@ +include ../f103-periph/hwdef.dat + +define HAL_CAN_DEFAULT_NODE_ID 0 + +define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_HWESC" + +define HAL_PERIPH_ENABLE_HWESC diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f103-RangeFinder/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/f103-RangeFinder/hwdef-bl.dat index 3d0788ef2f..c78e072e08 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f103-RangeFinder/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f103-RangeFinder/hwdef-bl.dat @@ -2,6 +2,7 @@ include ../f103-periph/hwdef-bl.dat define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_rangefinder" -define HAL_CAN_DEFAULT_NODE_ID 115 +# use DNA +define HAL_CAN_DEFAULT_NODE_ID 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f103-RangeFinder/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f103-RangeFinder/hwdef.dat index 1ad383b269..a49453db7a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f103-RangeFinder/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f103-RangeFinder/hwdef.dat @@ -2,7 +2,8 @@ include ../f103-periph/hwdef.dat define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_rangefinder" -define HAL_CAN_DEFAULT_NODE_ID 115 +# use DNA +define HAL_CAN_DEFAULT_NODE_ID 0 define HAL_AIRSPEED_BUS_DEFAULT 0 define AIRSPEED_MAX_SENSORS 1 @@ -11,3 +12,6 @@ define HAL_PERIPH_ENABLE_RANGEFINDER define RANGEFINDER_MAX_INSTANCES 1 define HAL_SERIAL3_PROTOCOL SerialProtocol_Rangefinder + +# we're too low on flash with old compler for bootloader +define HAL_NO_ROMFS_SUPPORT diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f103-Trigger/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/f103-Trigger/hwdef-bl.dat new file mode 100644 index 0000000000..f8564062cf --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/f103-Trigger/hwdef-bl.dat @@ -0,0 +1,6 @@ +include ../f103-periph/hwdef-bl.dat + +# use DNA +define HAL_CAN_DEFAULT_NODE_ID 0 + +define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_trigger" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f103-Trigger/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f103-Trigger/hwdef.dat new file mode 100644 index 0000000000..371426a728 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/f103-Trigger/hwdef.dat @@ -0,0 +1,27 @@ +# PWM input to Hardpoint output trigger firmware + +include ../f103-periph/hwdef.dat + +# use DNA +define HAL_CAN_DEFAULT_NODE_ID 0 + +define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_trigger" + +# PWM input to hardpoint out +define HAL_PERIPH_ENABLE_PWM_HARDPOINT + +define HAL_PWM_HARDPOINT_ID_DEFAULT 101 + +# we need 10us resolution for PWM capture +undef CH_CFG_ST_FREQUENCY +define CH_CFG_ST_FREQUENCY 100000 +define CH_CFG_ST_RESOLUTION 16 + +# use USART1_RX as input for PWM trigger +undef PA10 +PA10 PWM_TRIGGER INPUT PULLDOWN GPIO(77) +define PWM_HARDPOINT_PIN 77 + +# no I2C +undef I2C_ORDER + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f103-periph/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/f103-periph/hwdef-bl.dat index f1a82cb65e..6f1e8b464d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f103-periph/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f103-periph/hwdef-bl.dat @@ -23,11 +23,9 @@ FLASH_SIZE_KB 128 STDOUT_SERIAL SD1 STDOUT_BAUDRATE 57600 -# board voltage -STM32_VDD 330U # order of UARTs -UART_ORDER +SERIAL_ORDER define HAL_USE_UART FALSE PA4 LED_BOOTLOADER OUTPUT LOW diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f103-periph/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f103-periph/hwdef.dat index b259565bdc..28c1a70ff1 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f103-periph/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f103-periph/hwdef.dat @@ -27,11 +27,9 @@ define CH_CFG_ST_FREQUENCY 1000 # assume the 128k flash part for now FLASH_SIZE_KB 128 -# board voltage -STM32_VDD 330U # order of UARTs -UART_ORDER USART2 USART1 +SERIAL_ORDER EMPTY EMPTY EMPTY USART1 # a LED to flash PA4 LED OUTPUT LOW @@ -40,9 +38,9 @@ PA4 LED OUTPUT LOW PA9 USART1_TX USART1 SPEED_HIGH NODMA PA10 USART1_RX USART1 SPEED_HIGH NODMA -# USART2 for debug -PA2 USART2_TX USART2 SPEED_HIGH NODMA -PA3 USART2_RX USART2 SPEED_HIGH NODMA +# USART2 for debug (disabled) +# PA2 USART2_TX USART2 SPEED_HIGH NODMA +# PA3 USART2_RX USART2 SPEED_HIGH NODMA define HAL_UART_NODMA @@ -57,8 +55,6 @@ PA5 SPI1_SCK SPI1 PA6 SPI1_MISO SPI1 PA7 SPI1_MOSI SPI1 -SPIDEV rm3100 SPI1 DEVID1 MAG_CS MODE0 1*MHZ 1*MHZ - # analog input # PA5 VIN5 ADC1 define HAL_USE_ADC TRUE @@ -99,10 +95,13 @@ PA12 CAN_TX CAN define HAL_USE_CAN TRUE define STM32_CAN_USE_CAN1 TRUE +# reduce memory overheads +define HAL_CAN_POOL_SIZE 2500 + define HAL_USE_I2C TRUE define STM32_I2C_USE_I2C1 TRUE -define HAL_UART_MIN_TX_SIZE 256 +define HAL_UART_MIN_TX_SIZE 128 define HAL_UART_MIN_RX_SIZE 128 define HAL_UART_STACK_SIZE 256 @@ -120,21 +119,19 @@ define HAL_BUILD_AP_PERIPH # only one I2C bus I2C_ORDER I2C1 -COMPASS RM3100 SPI:rm3100 false ROTATION_NONE - define HAL_I2C_CLEAR_ON_TIMEOUT 0 define HAL_DEVICE_THREAD_STACK 256 define AP_PARAM_MAX_EMBEDDED_PARAM 0 -define HAL_PROBE_EXTERNAL_I2C_COMPASSES define HAL_I2C_INTERNAL_MASK 0 # disable dual GPS and GPS blending to save flash space define GPS_MAX_RECEIVERS 1 define GPS_MAX_INSTANCES 1 define HAL_COMPASS_MAX_SENSORS 1 +define HAL_WITH_DSP FALSE # use the app descriptor needed by MissionPlanner for CAN upload env APP_DESCRIPTOR MissionPlanner @@ -142,8 +139,6 @@ env APP_DESCRIPTOR MissionPlanner # reserve 256 bytes for comms between app and bootloader RAM_RESERVE_START 256 -# define CH_DBG_ENABLE_STACK_CHECK TRUE - # keep ROMFS uncompressed as we don't have enough RAM # to uncompress the bootloader at runtime env ROMFS_UNCOMPRESSED True diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-GPS/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-GPS/hwdef-bl.dat new file mode 100644 index 0000000000..3de68eaae6 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-GPS/hwdef-bl.dat @@ -0,0 +1,6 @@ +include ../f303-periph/hwdef-bl.dat + +# use DNA +define HAL_CAN_DEFAULT_NODE_ID 0 + +define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_gps" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-GPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-GPS/hwdef.dat new file mode 100644 index 0000000000..eda4af0e5c --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-GPS/hwdef.dat @@ -0,0 +1,18 @@ +include ../f303-periph/hwdef.dat + +# use DNA +define HAL_CAN_DEFAULT_NODE_ID 0 + +define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_gps" + +# added rm3100 mag on SPI +SPIDEV rm3100 SPI1 DEVID1 MAG_CS MODE0 1*MHZ 1*MHZ +COMPASS RM3100 SPI:rm3100 false ROTATION_NONE + +# and support all external compass types +define HAL_PROBE_EXTERNAL_I2C_COMPASSES + +# GPS+MAG +define HAL_PERIPH_ENABLE_GPS +define HAL_PERIPH_ENABLE_MAG +define HAL_PERIPH_ENABLE_NCP5623_LED diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-HWESC/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-HWESC/hwdef-bl.dat new file mode 100644 index 0000000000..cf33eec70e --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-HWESC/hwdef-bl.dat @@ -0,0 +1,5 @@ +include ../f303-periph/hwdef-bl.dat + +define HAL_CAN_DEFAULT_NODE_ID 0 + +define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_HWESC" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-HWESC/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-HWESC/hwdef.dat new file mode 100644 index 0000000000..49530a472a --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-HWESC/hwdef.dat @@ -0,0 +1,7 @@ +include ../f303-periph/hwdef.dat + +define HAL_CAN_DEFAULT_NODE_ID 0 + +define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_HWESC" + +define HAL_PERIPH_ENABLE_HWESC diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-M10025/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-M10025/hwdef-bl.dat new file mode 100644 index 0000000000..6c3b41dc14 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-M10025/hwdef-bl.dat @@ -0,0 +1,6 @@ +include ../f303-periph/hwdef-bl.dat + +# start as DNA +define HAL_CAN_DEFAULT_NODE_ID 0 + +define CAN_APP_NODE_NAME "org.ardupilot.mro_m10025" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-M10025/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-M10025/hwdef.dat new file mode 100644 index 0000000000..03c35c9709 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-M10025/hwdef.dat @@ -0,0 +1,26 @@ +include ../f303-periph/hwdef.dat + +# start as DNA +define HAL_CAN_DEFAULT_NODE_ID 0 + +define CAN_APP_NODE_NAME "org.ardupilot.mro_m10025" + +# added rm3100 mag on SPI +SPIDEV rm3100 SPI1 DEVID1 MAG_CS MODE0 1*MHZ 1*MHZ +COMPASS RM3100 SPI:rm3100 false ROTATION_NONE + +# an I2C baro (DPS310) +BARO DPS280 I2C:0:0x77 + +# GPS+MAG+LED+Baro +define HAL_PERIPH_ENABLE_GPS +define HAL_PERIPH_ENABLE_MAG +define HAL_PERIPH_ENABLE_NCP5623_LED +define HAL_PERIPH_ENABLE_BARO +# I2C Airspeed sensor must use a different address than 0x77 +define HAL_PERIPH_ENABLE_AIRSPEED + +# Safety button +PC13 SAFE_BUTTON INPUT PULLUP +# Button is active LOW +define HAL_SAFE_BUTTON_ON 0 \ No newline at end of file diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-M10070/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-M10070/hwdef-bl.dat new file mode 100644 index 0000000000..e5757e0284 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-M10070/hwdef-bl.dat @@ -0,0 +1,9 @@ +include ../f303-periph/hwdef-bl.dat + +# mRo Location One CAN GPS +# M10084 + +# start as DNA +define HAL_CAN_DEFAULT_NODE_ID 0 + +define CAN_APP_NODE_NAME "io.mrobotics.m10070_loc1_BL" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-M10070/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-M10070/hwdef.dat new file mode 100644 index 0000000000..f7ed2a4aa9 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-M10070/hwdef.dat @@ -0,0 +1,29 @@ +include ../f303-periph/hwdef.dat + +# mRo Location One CAN GPS +# M10084 + +# start as DNA +define HAL_CAN_DEFAULT_NODE_ID 0 + +define CAN_APP_NODE_NAME "io.mrobotics.m10070_loc1" + +# added rm3100 mag on SPI +SPIDEV rm3100 SPI1 DEVID1 MAG_CS MODE0 1*MHZ 1*MHZ +COMPASS RM3100 SPI:rm3100 false ROTATION_ROLL_180_YAW_90 + +# GPS+MAG+LED+Baro +define HAL_PERIPH_ENABLE_GPS +define HAL_PERIPH_ENABLE_MAG +define HAL_PERIPH_ENABLE_NCP5623_LED + +# Optional I2C Airspeed sensor connected to I2C connector +define HAL_PERIPH_ENABLE_AIRSPEED + +# Safety button +PC13 SAFE_BUTTON INPUT PULLUP +# Button is active LOW +define HAL_SAFE_BUTTON_ON 0 + +define HAL_PROBE_EXTERNAL_I2C_COMPASSES + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-Universal/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-Universal/hwdef-bl.dat new file mode 100644 index 0000000000..4dd98ce2a6 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-Universal/hwdef-bl.dat @@ -0,0 +1,6 @@ +include ../f303-periph/hwdef-bl.dat + +# use DNA +define HAL_CAN_DEFAULT_NODE_ID 0 + +define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_universal" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-Universal/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-Universal/hwdef.dat new file mode 100644 index 0000000000..be9ca44bba --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-Universal/hwdef.dat @@ -0,0 +1,29 @@ +include ../f303-periph/hwdef.dat + +# use DNA +define HAL_CAN_DEFAULT_NODE_ID 0 + +define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_universal" + +# and support all external compass and baro types +define HAL_PROBE_EXTERNAL_I2C_COMPASSES +define HAL_PROBE_EXTERNAL_I2C_BAROS + +# enable all features +define HAL_PERIPH_ENABLE_GPS +define HAL_PERIPH_ENABLE_MAG +define HAL_PERIPH_ENABLE_BARO +define HAL_PERIPH_ENABLE_AIRSPEED +define HAL_PERIPH_ENABLE_ADSB +define HAL_PERIPH_ENABLE_NCP5623_LED +define HAL_PERIPH_ENABLE_RANGEFINDER + +define RANGEFINDER_MAX_INSTANCES 1 +define ADSB_PORT hal.uartB + +define HAL_AIRSPEED_BUS_DEFAULT 0 +define AIRSPEED_MAX_SENSORS 1 + +# default ADSB off by setting 0 baudrate +define HAL_PERIPH_ADSB_BAUD_DEFAULT 0 + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-periph/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-periph/hwdef-bl.dat new file mode 100644 index 0000000000..456686e5d1 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-periph/hwdef-bl.dat @@ -0,0 +1,98 @@ +# hw definition file for processing by chibios_pins.py + +# MCU class and specific type +MCU STM32F303 STM32F303xC + +FLASH_RESERVE_START_KB 0 +FLASH_BOOTLOADER_LOAD_KB 26 + +# board ID for firmware load +APJ_BOARD_ID 1004 + +# setup build for a peripheral firmware +env AP_PERIPH 1 + +# crystal frequency +OSCILLATOR_HZ 8000000 + +define CH_CFG_ST_FREQUENCY 1000 + +# assume 256k flash part +FLASH_SIZE_KB 256 + +STDOUT_SERIAL SD1 +STDOUT_BAUDRATE 57600 + + +# order of UARTs +SERIAL_ORDER +define HAL_USE_UART FALSE + +PA4 LED_BOOTLOADER OUTPUT LOW +define HAL_LED_ON 1 + +# USART1 +PA9 USART1_TX USART1 SPEED_HIGH NODMA +PA10 USART1_RX USART1 SPEED_HIGH NODMA + +# USART2 +PA2 USART2_TX USART2 SPEED_HIGH NODMA +PA3 USART2_RX USART2 SPEED_HIGH NODMA + +define HAL_USE_SERIAL TRUE + +define STM32_SERIAL_USE_USART1 TRUE +define STM32_SERIAL_USE_USART2 TRUE +define STM32_SERIAL_USE_USART3 FALSE + +PA13 SWDIO-JTMS SWD +PA14 SWCLK-JTCK SWD + +define HAL_NO_GPIO_IRQ +define CH_CFG_ST_TIMEDELTA 0 +#define CH_CFG_USE_DYNAMIC FALSE +define SERIAL_BUFFERS_SIZE 32 +define HAL_USE_EMPTY_IO TRUE +define PORT_INT_REQUIRED_STACK 64 + +# avoid timer and RCIN threads to save memory +define HAL_NO_TIMER_THREAD +define HAL_NO_RCIN_THREAD + +define HAL_USE_RTC FALSE +define DISABLE_SERIAL_ESC_COMM TRUE +define NO_DATAFLASH TRUE + +define DMA_RESERVE_SIZE 0 + +define PERIPH_FW TRUE +MAIN_STACK 0x800 +PROCESS_STACK 0x800 +define HAL_DISABLE_LOOP_DELAY + +define HAL_USE_EMPTY_STORAGE 1 +define HAL_STORAGE_SIZE 16384 + +# enable CAN support +PA11 CAN_RX CAN +PA12 CAN_TX CAN +define HAL_USE_CAN TRUE +define STM32_CAN_USE_CAN1 TRUE + +# make bl baudrate match debug baudrate for easier debugging +define BOOTLOADER_BAUDRATE 57600 + +# use a small bootloader timeout +define HAL_BOOTLOADER_TIMEOUT 1000 + +# use PB6 (normally I2C1_SCL) as "hold in bootloader" pin +# this has a hw pullup, so if we set it as input floating +# and look for it low then we know user has pulled it down and +# want to stay in the bootloader +PB6 STAY_IN_BOOTLOADER INPUT FLOATING + +# reserve 256 bytes for comms between app and bootloader +RAM_RESERVE_START 256 + +# Add CS pins to ensure they are high in bootloader +PB0 MAG_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-periph/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-periph/hwdef.dat new file mode 100644 index 0000000000..6482fed0db --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-periph/hwdef.dat @@ -0,0 +1,136 @@ +g# hw definition file for processing by chibios_pins.py + +# MCU class and specific type +MCU STM32F303 STM32F303xC + +# bootloader starts firmware at 26k +FLASH_RESERVE_START_KB 26 + +# store parameters in pages 11 and 12 +define STORAGE_FLASH_PAGE 11 +define HAL_STORAGE_SIZE 800 + +# board ID for firmware load +APJ_BOARD_ID 1004 + +# setup build for a peripheral firmware +env AP_PERIPH 1 + +# enable watchdog +define HAL_WATCHDOG_ENABLED_DEFAULT true + +# crystal frequency +OSCILLATOR_HZ 8000000 + +define CH_CFG_ST_FREQUENCY 100000 +define CH_CFG_ST_TIMEDELTA 0 + +# assume the 256k flash part for now +FLASH_SIZE_KB 256 + + +# order of UARTs +SERIAL_ORDER USART2 EMPTY EMPTY USART1 + +# a LED to flash +PA4 LED OUTPUT LOW + +define HAL_CAN_POOL_SIZE 6000 + +# USART1, connected to GPS +PA9 USART1_TX USART1 SPEED_HIGH +PA10 USART1_RX USART1 SPEED_HIGH + +# USART2 for debug +PA2 USART2_TX USART2 SPEED_HIGH NODMA +PA3 USART2_RX USART2 SPEED_HIGH NODMA + +# only one I2C bus in normal config +PB6 I2C1_SCL I2C1 +PB7 I2C1_SDA I2C1 + +PB0 MAG_CS CS + +# spi bus for compass +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 + +# analog input +# PA5 VIN5 ADC1 +define HAL_USE_ADC FALSE +define STM32_ADC_USE_ADC1 FALSE +define HAL_DISABLE_ADC_DRIVER TRUE + +define HAL_NO_GPIO_IRQ +define SERIAL_BUFFERS_SIZE 512 +define PORT_INT_REQUIRED_STACK 64 + +# avoid timer and RCIN threads to save memory +define HAL_NO_RCIN_THREAD + +define HAL_USE_RTC FALSE +define DISABLE_SERIAL_ESC_COMM TRUE +define NO_DATAFLASH TRUE + +define DMA_RESERVE_SIZE 0 + +define PERIPH_FW TRUE + +# MAIN_STACK is stack of initial thread +MAIN_STACK 0x80 + +# PROCESS_STACK controls stack for main thread +PROCESS_STACK 0x800 +define HAL_DISABLE_LOOP_DELAY + +# enable CAN support +PA11 CAN_RX CAN +PA12 CAN_TX CAN +define HAL_USE_CAN TRUE +define STM32_CAN_USE_CAN1 TRUE + +define HAL_USE_I2C TRUE +define STM32_I2C_USE_I2C1 TRUE + +define HAL_UART_MIN_TX_SIZE 256 +define HAL_UART_MIN_RX_SIZE 128 + +define HAL_UART_STACK_SIZE 256 + +define STORAGE_THD_WA_SIZE 256 +define IO_THD_WA_SIZE 256 + +define HAL_NO_GCS +define HAL_NO_LOGGING +define HAL_NO_MONITOR_THREAD + +define HAL_MINIMIZE_FEATURES 0 + +define HAL_BUILD_AP_PERIPH + +# only one I2C bus +I2C_ORDER I2C1 + +define HAL_I2C_CLEAR_ON_TIMEOUT 0 + +define HAL_DEVICE_THREAD_STACK 256 + +define AP_PARAM_MAX_EMBEDDED_PARAM 0 + +define HAL_I2C_INTERNAL_MASK 0 + +# disable dual GPS and GPS blending to save flash space +define GPS_MAX_RECEIVERS 1 +define GPS_MAX_INSTANCES 1 +define HAL_COMPASS_MAX_SENSORS 1 + +# use the app descriptor needed by MissionPlanner for CAN upload +env APP_DESCRIPTOR MissionPlanner + +# reserve 256 bytes for comms between app and bootloader +RAM_RESERVE_START 256 + +# keep ROMFS uncompressed as we don't have enough RAM +# to uncompress the bootloader at runtime +env ROMFS_UNCOMPRESSED True diff --git a/libraries/AP_HAL_ChibiOS/hwdef/fmuv2/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/fmuv2/hwdef.dat index e67593b4c1..f07eddc94e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/fmuv2/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/fmuv2/hwdef.dat @@ -10,3 +10,6 @@ FLASH_SIZE_KB 1024 # 1M, but it prepares us for when large features such as scripting are # added to the build define HAL_MINIMIZE_FEATURES 1 + +# we don't have a flash page spare to write parameters to: +undef STORAGE_FLASH_PAGE diff --git a/libraries/AP_HAL_ChibiOS/hwdef/fmuv3/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/fmuv3/hwdef-bl.dat index 263e3858dd..9fa422a3fd 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/fmuv3/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/fmuv3/hwdef-bl.dat @@ -10,8 +10,6 @@ APJ_BOARD_ID 9 # crystal frequency OSCILLATOR_HZ 24000000 -# board voltage -STM32_VDD 330U # ChibiOS system timer STM32_ST_USE_TIMER 5 @@ -33,7 +31,7 @@ USB_STRING_SERIAL "%SERIAL%" define BOOTLOADER_BAUDRATE 115200 # uarts and USB to run bootloader protocol on -UART_ORDER OTG1 USART2 USART3 UART7 +SERIAL_ORDER OTG1 USART2 USART3 UART7 # this is the pin that senses USB being connected. It is an input pin # setup as OPENDRAIN @@ -77,13 +75,6 @@ define HAL_CHIBIOS_ARCH_FMUV3 1 # available (in bytes) define HAL_STORAGE_SIZE 16384 -# uncomment the lines below to enable strict API -# checking in ChibiOS -# define CH_DBG_ENABLE_ASSERTS TRUE -# define CH_DBG_ENABLE_CHECKS TRUE -# define CH_DBG_SYSTEM_STATE_CHECK TRUE -# define CH_DBG_ENABLE_STACK_CHECK TRUE - # Add CS pins to ensure they are high in bootloader PC1 MAG_CS CS PC2 MPU_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/fmuv3/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/fmuv3/hwdef.dat index ddb0d997dc..ed8e9f8df5 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/fmuv3/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/fmuv3/hwdef.dat @@ -77,8 +77,6 @@ OSCILLATOR_HZ 24000000 # Now define the voltage the MCU runs at. This is needed for ChibiOS # to set various internal driver limits. It is in 0.01 volt units. -# board voltage -STM32_VDD 330U # This is the STM32 timer that ChibiOS will use for the low level # driver. This must be a 32 bit timer. We currently only support @@ -98,7 +96,7 @@ FLASH_SIZE_KB 2048 # Serial port for stdout. This is optional. If you leave it out then # output from printf() lines will go to the ArduPilot console, which is the -# first UART in the UART_ORDER list. But note that some startup code +# first UART in the SERIAL_ORDER list. But note that some startup code # runs before USB is set up. # The value for STDOUT_SERIAL is a serial device name, and must be for a # serial device for which pins are defined in this file. For example, SD7 @@ -127,21 +125,21 @@ USB_STRING_PRODUCT "%BOARD%" # order of I2C buses I2C_ORDER I2C2 I2C1 -# Now the UART order. These map to the hal.uartA to hal.uartF -# objects. If you use a shorter list then HAL_Empty::UARTDriver +# Now the serial ordering. These map to the SERIALn_ parameter numbers +# If you use a shorter list then HAL_Empty::UARTDriver # objects are substituted for later UARTs, or you can leave a gap by # listing one or more of the uarts as EMPTY. # The normal usage of this ordering is: # 1) SERIAL0: console (primary mavlink, usually USB) -# 2) SERIAL3: primary GPS -# 3) SERIAL1: telem1 -# 4) SERIAL2: telem2 +# 2) SERIAL1: telem1 +# 3) SERIAL2: telem2 +# 4) SERIAL3: primary GPS # 5) SERIAL4: GPS2 # 6) SERIAL5: extra UART (usually RTOS debug console) # order of UARTs (and USB) -UART_ORDER OTG1 UART4 USART2 USART3 UART8 UART7 +SERIAL_ORDER OTG1 USART2 USART3 UART4 UART8 UART7 # If the board has an IOMCU connected via a UART then this defines the # UART to talk to that MCU. Leave it out for boards with no IOMCU. @@ -442,12 +440,6 @@ define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" # available (in bytes). define HAL_STORAGE_SIZE 16384 -# Now define fallback storage location is flash if no FRAM -# fitted. This needs to be carefully chosen to align with your -# bootloader. The flash storage system needs two sectors, and the -# sectors must be at least 20% larger than HAL_STORAGE_SIZE. -define STORAGE_FLASH_PAGE 22 - # allow to have have a dedicated safety switch pin define HAL_HAVE_SAFETY_SWITCH 1 @@ -474,16 +466,9 @@ define HAL_BATT_CURR_SCALE 17.0 # This defines the default maximum clock on I2C devices. define HAL_I2C_MAX_CLOCK 100000 -# Uncomment the lines below to enable strict API -# checking in ChibiOS. -# define CH_DBG_ENABLE_ASSERTS TRUE -# define CH_DBG_ENABLE_CHECKS TRUE -# define CH_DBG_SYSTEM_STATE_CHECK TRUE -# define CH_DBG_ENABLE_STACK_CHECK TRUE - # We can't share the IO UART (USART6). -DMA_NOSHARE USART6_TX USART6_RX ADC1 -DMA_PRIORITY USART6* +DMA_NOSHARE USART6_TX ADC1 +DMA_PRIORITY USART6* SPI* # List of files to put in ROMFS. For fmuv3 we need an IO firmware so # we can automatically update the IOMCU firmware on boot. The format diff --git a/libraries/AP_HAL_ChibiOS/hwdef/fmuv4/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/fmuv4/hwdef-bl.dat index 2e01810333..3ffc78329f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/fmuv4/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/fmuv4/hwdef-bl.dat @@ -10,8 +10,6 @@ APJ_BOARD_ID 11 # crystal frequency OSCILLATOR_HZ 24000000 -# board voltage -STM32_VDD 330U # ChibiOS system timer STM32_ST_USE_TIMER 5 @@ -20,7 +18,7 @@ STM32_ST_USE_TIMER 5 FLASH_SIZE_KB 2048 # order of UARTs (and USB) -UART_ORDER OTG1 USART2 +SERIAL_ORDER OTG1 USART2 PB1 LED_BOOTLOADER OUTPUT PB3 LED_ACTIVITY OUTPUT diff --git a/libraries/AP_HAL_ChibiOS/hwdef/fmuv4/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/fmuv4/hwdef.dat index d2572940e3..c339479a2b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/fmuv4/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/fmuv4/hwdef.dat @@ -12,8 +12,6 @@ APJ_BOARD_ID 11 # crystal frequency OSCILLATOR_HZ 24000000 -# board voltage -STM32_VDD 330U # ChibiOS system timer STM32_ST_USE_TIMER 5 @@ -35,7 +33,7 @@ define HAL_I2C_BUS_BASE 1 define HAL_I2C_INTERNAL_MASK 0 # order of UARTs (and USB) -UART_ORDER OTG1 UART4 USART2 USART3 UART8 USART1 UART7 +SERIAL_ORDER OTG1 USART2 USART3 UART4 UART8 USART1 UART7 # UART4 is GPS PA0 UART4_TX UART4 @@ -184,9 +182,6 @@ define HAL_STORAGE_SIZE 16384 # enable RAMTROM parameter storage define HAL_WITH_RAMTRON 1 -# fallback to flash is no FRAM fitted -define STORAGE_FLASH_PAGE 22 - # enable FAT filesystem define HAL_OS_FATFS_IO 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/fmuv5/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/fmuv5/hwdef-bl.dat index bd5e7ee8c6..ed3006b34c 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/fmuv5/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/fmuv5/hwdef-bl.dat @@ -7,14 +7,6 @@ MCU STM32F7xx STM32F767xx # crystal frequency OSCILLATOR_HZ 16000000 -define STM32_LSECLK 32768U -define STM32_LSEDRV (3U << 3U) -define STM32_PLLSRC STM32_PLLSRC_HSE -define STM32_PLLM_VALUE 8 -define STM32_PLLN_VALUE 216 -define STM32_PLLP_VALUE 2 -define STM32_PLLQ_VALUE 9 - # board ID for firmware load APJ_BOARD_ID 50 @@ -30,11 +22,9 @@ PC6 LED_BOOTLOADER OUTPUT HIGH PC7 LED_ACTIVITY OUTPUT HIGH define HAL_LED_ON 0 -# board voltage -STM32_VDD 330U # order of UARTs (and USB) -UART_ORDER OTG1 USART2 UART7 +SERIAL_ORDER OTG1 USART2 UART7 # USART2 is telem1 PD6 USART2_RX USART2 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/fmuv5/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/fmuv5/hwdef.dat index d5cafdb40e..ddfc409798 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/fmuv5/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/fmuv5/hwdef.dat @@ -8,14 +8,6 @@ MCU STM32F7xx STM32F767xx # crystal frequency OSCILLATOR_HZ 16000000 -define STM32_LSECLK 32768U -define STM32_LSEDRV (3U << 3U) -define STM32_PLLSRC STM32_PLLSRC_HSE -define STM32_PLLM_VALUE 8 -define STM32_PLLN_VALUE 216 -define STM32_PLLP_VALUE 2 -define STM32_PLLQ_VALUE 9 - define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_CHIBIOS_FMUV5 define HAL_CHIBIOS_ARCH_FMUV5 1 @@ -24,8 +16,6 @@ APJ_BOARD_ID 50 FLASH_RESERVE_START_KB 32 -# board voltage -STM32_VDD 330U # flash size FLASH_SIZE_KB 2048 @@ -33,7 +23,7 @@ FLASH_SIZE_KB 2048 env OPTIMIZE -O2 # order of UARTs (and USB) -UART_ORDER OTG1 USART1 USART2 USART3 UART4 USART6 UART7 OTG2 +SERIAL_ORDER OTG1 USART2 USART3 USART1 UART4 USART6 UART7 OTG2 # default the 2nd interface to MAVLink2 until MissionPlanner updates drivers define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2 @@ -311,11 +301,6 @@ define HAL_COMPASS_AUTO_ROT_DEFAULT 2 DMA_PRIORITY SDMMC* UART8* ADC* SPI* TIM* -#define CH_DBG_ENABLE_ASSERTS TRUE -#define CH_DBG_ENABLE_CHECKS TRUE -#define CH_DBG_SYSTEM_STATE_CHECK TRUE -#define CH_DBG_ENABLE_STACK_CHECK TRUE - # define HAL_SPI_CHECK_CLOCK_FREQ 1 # enable FAT filesystem support (needs a microSD defined via SDMMC) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/iomcu/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/iomcu/hwdef.dat index 6f9f5204b1..fc1b70a2e1 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/iomcu/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/iomcu/hwdef.dat @@ -18,11 +18,9 @@ FLASH_SIZE_KB 64 # ChibiOS system timer -# board voltage -STM32_VDD 330U # order of UARTs -UART_ORDER EMPTY +SERIAL_ORDER EMPTY EMPTY EMPTY EMPTY define HAL_USE_UART TRUE # UART connected to FMU, uses DMA @@ -142,3 +140,4 @@ IOMCU_FW 1 MAIN_STACK 0x200 PROCESS_STACK 0x250 define HAL_DISABLE_LOOP_DELAY +define HAL_WITH_DSP FALSE diff --git a/libraries/AP_HAL_ChibiOS/hwdef/luminousbee4/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/luminousbee4/hwdef.dat index cd28562929..eeb134b5bc 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/luminousbee4/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/luminousbee4/hwdef.dat @@ -9,9 +9,6 @@ APJ_BOARD_ID 11 # crystal frequency OSCILLATOR_HZ 24000000 -# board voltage -STM32_VDD 330U - # ChibiOS system timer STM32_ST_USE_TIMER 5 @@ -32,7 +29,7 @@ define HAL_I2C_BUS_BASE 1 define HAL_I2C_INTERNAL_MASK 0 # order of UARTs (and USB) -UART_ORDER OTG1 UART4 USART2 USART3 UART8 USART1 UART7 +SERIAL_ORDER OTG1 USART2 USART3 UART4 UART8 USART1 UART7 # UART4 is GPS PA0 UART4_TX UART4 @@ -144,9 +141,6 @@ define HAL_STORAGE_SIZE 16384 # enable RAMTROM parameter storage define HAL_WITH_RAMTRON 1 -# fallback to flash is no FRAM fitted -define STORAGE_FLASH_PAGE 22 - # enable FAT filesystem define HAL_OS_FATFS_IO 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/mRoControlZeroF7/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/mRoControlZeroF7/hwdef-bl.dat index 26fdbb2d07..2c44887684 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/mRoControlZeroF7/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/mRoControlZeroF7/hwdef-bl.dat @@ -10,14 +10,6 @@ USB_STRING_MANUFACTURER "mRo" # crystal frequency OSCILLATOR_HZ 24000000 -define STM32_LSECLK 32768U -define STM32_LSEDRV (3U << 3U) -define STM32_PLLSRC STM32_PLLSRC_HSE -define STM32_PLLM_VALUE 24 -define STM32_PLLN_VALUE 432 -define STM32_PLLP_VALUE 2 -define STM32_PLLQ_VALUE 9 - # board ID for firmware load APJ_BOARD_ID 141 @@ -38,11 +30,9 @@ PB3 LED_ACTIVITY2 OUTPUT define HAL_LED_ON 0 -# board voltage -STM32_VDD 330U # order of UARTs (and USB) -UART_ORDER OTG1 UART7 +SERIAL_ORDER OTG1 UART7 # UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters). PE7 UART7_RX UART7 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/mRoControlZeroF7/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/mRoControlZeroF7/hwdef.dat index 4f601bed70..3440a6bcac 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/mRoControlZeroF7/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/mRoControlZeroF7/hwdef.dat @@ -9,17 +9,6 @@ APJ_BOARD_ID 141 # crystal frequency OSCILLATOR_HZ 24000000 -define STM32_LSECLK 32768U -define STM32_LSEDRV (3U << 3U) -define STM32_PLLSRC STM32_PLLSRC_HSE -define STM32_PLLM_VALUE 24 -define STM32_PLLN_VALUE 432 -define STM32_PLLP_VALUE 2 -define STM32_PLLQ_VALUE 9 - -# board voltage -STM32_VDD 330U - FLASH_SIZE_KB 2048 # with 2M flash we can afford to optimize for speed @@ -74,7 +63,7 @@ define HAL_I2C_INTERNAL_MASK 0 # USART6 FC # UART7 DEBUG -UART_ORDER OTG1 UART4 USART2 USART3 UART8 USART6 UART7 OTG2 +SERIAL_ORDER OTG1 USART2 USART3 UART4 UART8 USART6 UART7 OTG2 # default the 2nd interface to MAVLink2 until MissionPlanner updates drivers define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/mRoNexus/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/mRoNexus/hwdef-bl.dat new file mode 100644 index 0000000000..e6f479c22a --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/mRoNexus/hwdef-bl.dat @@ -0,0 +1,59 @@ +# hw definition file for processing by chibios_hwdef.py +# mRo Nexus CAN flight controller bootloader +# M10084 + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# USB setup +USB_STRING_MANUFACTURER "mRo" + +# crystal frequency +OSCILLATOR_HZ 25000000 + +# board ID for firmware load +APJ_BOARD_ID 1015 + +FLASH_SIZE_KB 2048 + +# bootloader is installed at zero offset +FLASH_RESERVE_START_KB 0 + +# the location where the bootloader will put the firmware +# the H743 has 128k sectors +FLASH_BOOTLOADER_LOAD_KB 128 + +PB0 LED_BOOTLOADER OUTPUT + +# define all 3 to make LED output White. +PA6 LED_ACTIVITY OUTPUT +PA7 LED_ACTIVITY2 OUTPUT +# PB11 LED_ACTIVITY3 OUTPUT + +define HAL_LED_ON 0 + + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 UART7 + +PE7 UART7_RX UART7 +PE8 UART7_TX UART7 + +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +define HAL_USE_EMPTY_STORAGE 1 +define HAL_STORAGE_SIZE 16384 + +# Add CS pins to ensure they are high in bootloader +PB12 CS_ADIS16470 CS +PA15 CS_ICM40609D CS +PE3 CS_DPS310 CS +PB11 CS_RM3100 CS +PE4 CS_FRAM CS + +# This is the reset line for the adis16470. This will force a reset upon reboot. +PB1 nRST_ADIS OUTPUT LOW diff --git a/libraries/AP_HAL_ChibiOS/hwdef/mRoNexus/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/mRoNexus/hwdef.dat new file mode 100644 index 0000000000..d3a62b4590 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/mRoNexus/hwdef.dat @@ -0,0 +1,193 @@ +# hw definition file for processing by chibios_hwdef.py +# mRo Nexus CAN flight controller +# A Dual CAN based flight controller / CAN IMU +# 36mm x 36mm, 31.5mm x 31.5mm grommeted mounting holes +# M10084 + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# board ID for firmware load +APJ_BOARD_ID 1015 + +# crystal frequency +OSCILLATOR_HZ 25000000 + + +FLASH_SIZE_KB 2048 + +# with 2M flash we can afford to optimize for speed +env OPTIMIZE -O2 + +# start on 2th sector (1st sector for bootloader) +FLASH_RESERVE_START_KB 128 + +# use FRAM for storage +define HAL_STORAGE_SIZE 16384 +define HAL_WITH_RAMTRON 1 + +# USB setup +USB_STRING_MANUFACTURER "mRo" + +# Order of I2C buses +I2C_ORDER I2C4 + +# order of UARTs (and USB) +# OTG1 SERIAL0 +# UART4 SERIAL3 +# UART7 SERIAL1 +# OTG2 SERIAL2 + +SERIAL_ORDER OTG1 UART7 OTG2 UART4 + +# UART4 SERIAL0 (GPS) +PD0 UART4_RX UART4 +PD1 UART4_TX UART4 + +# UART7 SERIAL1 (SPARE UART) +PE7 UART7_RX UART7 +PE8 UART7_TX UART7 + +# VDD sense pin for the External 5v Supply +PA4 BATT_VOLTAGE_SENS ADC1 SCALE(1.65) + +# VDD sense pin for the CAN supplied 5v Supply +PA3 VDD_5V_SENS ADC1 SCALE(1.65) + +#SPI2 SPIBus0 (1 device ADIS16470 6DOF) +PB13 SPI2_SCK SPI2 +PB14 SPI2_MISO SPI2 +PB15 SPI2_MOSI SPI2 + +#SPI3 SPIBus1 (2 devices ICM-40609 6DOF / RM3100 MAG +PB3 SPI3_SCK SPI3 +PB4 SPI3_MISO SPI3 +PD6 SPI3_MOSI SPI3 + +#SPI4 SPIBus2 (2 devices DPS310 BARO / FM25V02 FRAM) +PE2 SPI4_SCK SPI4 +PE5 SPI4_MISO SPI4 +PE6 SPI4_MOSI SPI4 + +# This input pin is used to detect that power is valid on USB. +PA9 VBUS_VALID INPUT + +# Now we define the pins that USB is connected on. +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# These are the pins for SWD debugging with a STlinkv2 or black-magic probe. +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# Now the first I2C bus. The pin speeds are automatically setup +# correctly, but can be overridden here if needed. +PD12 I2C4_SCL I2C4 +PD13 I2C4_SDA I2C4 + +# this board only has a single I2C bus so make it external +define HAL_I2C_INTERNAL_MASK 0 + +# Now setup the pins for the microSD card, if available. +PC8 SDMMC1_D0 SDMMC1 +PC9 SDMMC1_D1 SDMMC1 +PC10 SDMMC1_D2 SDMMC1 +PC11 SDMMC1_D3 SDMMC1 +PC12 SDMMC1_CK SDMMC1 +PD2 SDMMC1_CMD SDMMC1 + +# More CS pins for more sensors. The labels for all CS pins need to +# match the SPI device table later in this file. +PB12 CS_ADIS16470 CS +PA15 CS_ICM40609D CS +PE3 CS_DPS310 CS +PB11 CS_RM3100 CS + +# The CS pin for FRAM (ramtron). This one is marked as using +# SPEED_VERYLOW, which matches the HAL_PX4 setup. +PE4 CS_FRAM CS SPEED_VERYLOW + +# the first CAN bus +PB9 CAN1_TX CAN1 +PB8 CAN1_RX CAN1 + +PE0 GPIO_CAN1_SILENT OUTPUT PUSHPULL LOW GPIO(72) + +# This defines the pins for the 2nd CAN interface. +PB6 CAN2_TX CAN2 +PB5 CAN2_RX CAN2 + +PB7 GPIO_CAN2_SILENT OUTPUT PUSHPULL LOW GPIO(73) + +define BOARD_PWM_COUNT_DEFAULT 0 + +# This is the invensense data-ready pin. We don't use it in the +# default driver. +PD8 DRDY_ADIS16470 INPUT GPIO(93) +PE13 DRDY_ICM40609D INPUT +PC13 DRDY_RM3100 INPUT + +define HAL_DRDY_ADIS16470_PIN 93 + +# This is the reset line for the adis16470 +PB1 nRST_ADIS OUTPUT HIGH GPIO(74) + +# This is the pin to enable the sensors rail. It can be used to power +# cycle sensors to recover them in case there are problems with power on +# timing affecting sensor stability. We pull it high by default. + +#SPI3 Devices ICM40609 and RM3100 +PC6 SENSORS_SPI3_EN OUTPUT HIGH + +#SPI4 Devices DPS310 and FRAM +PC7 SENSORS_SPI4_EN OUTPUT HIGH + +SPIDEV adis16470 SPI2 DEVID1 CS_ADIS16470 MODE3 1*MHZ 2*MHZ +# SPIDEV icm40609d SPI3 DEVID2 CS_ICM40609D MODE3 2*MHZ 8*MHZ +#! ^^WHEN AVAILABLE +SPIDEV rm3100 SPI3 DEVID4 CS_RM3100 MODE3 2*MHZ 8*MHZ +SPIDEV dps310 SPI4 DEVID3 CS_DPS310 MODE3 5*MHZ 5*MHZ +SPIDEV ramtron SPI4 DEVID10 CS_FRAM MODE3 8*MHZ 8*MHZ + +# Now some defines for logging and terrain data files. +define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" +define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" + +# allow to have have a dedicated safety switch pin +define HAL_HAVE_SAFETY_SWITCH 0 + +# Enable FAT filesystem support (needs a microSD defined via SDMMC). +define HAL_OS_FATFS_IO 1 + +# Nexus has a TriColor LED like the Pixracer, Red, Green, Blue +define HAL_HAVE_PIXRACER_LED + +define HAL_GPIO_LED_ON 0 +define HAL_GPIO_LED_OFF 1 + +# LED setup for PixracerLED driver +PA6 LED_R OUTPUT HIGH GPIO(0) +PA7 LED_G OUTPUT HIGH GPIO(1) +PB0 LED_B OUTPUT HIGH GPIO(2) + +define HAL_GPIO_A_LED_PIN 0 +define HAL_GPIO_B_LED_PIN 1 +define HAL_GPIO_C_LED_PIN 2 + +# 2 IMUs (Analog Devices ADIS16470 and Invensense / TDK ICM40609D) +IMU ADIS1647x SPI:adis16470 ROTATION_ROLL_180 HAL_DRDY_ADIS16470_PIN +# IMU Invensense SPI:icm40609d ROTATION_NONE +#! ^^Need to confirm orientation + +define HAL_DEFAULT_INS_FAST_SAMPLE 1 +#! ^^Set to 3 when ICM40609D driver is available + +# 1 Absolute Pressure Sensor (Infineon DPS310) +BARO DPS280 SPI:dps310 + +# 1 compass (PNI RM3100) +COMPASS RM3100 SPI:rm3100 false ROTATION_YAW_180 + +define HAL_PROBE_EXTERNAL_I2C_COMPASSES + + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/mRoX21-777/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/mRoX21-777/hwdef-bl.dat index ea49861818..8b0611cbbe 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/mRoX21-777/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/mRoX21-777/hwdef-bl.dat @@ -12,19 +12,9 @@ MCU STM32F7xx STM32F777xx # crystal frequency OSCILLATOR_HZ 24000000 -define STM32_LSECLK 32768U -define STM32_LSEDRV (3U << 3U) -define STM32_PLLSRC STM32_PLLSRC_HSE -define STM32_PLLM_VALUE 24 -define STM32_PLLN_VALUE 432 -define STM32_PLLP_VALUE 2 -define STM32_PLLQ_VALUE 9 - # board ID for firmware load APJ_BOARD_ID 136 -# board voltage -STM32_VDD 330U # flash size FLASH_SIZE_KB 2048 @@ -35,7 +25,7 @@ USB_STRING_PRODUCT "X2.1-777" USB_STRING_SERIAL "%SERIAL%" # order of UARTs (and USB) -UART_ORDER OTG1 USART2 USART3 UART7 +SERIAL_ORDER OTG1 USART2 USART3 UART7 PD5 USART2_TX USART2 PD6 USART2_RX USART2 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/mRoX21-777/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/mRoX21-777/hwdef.dat index 1e937b5f9c..61fb054975 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/mRoX21-777/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/mRoX21-777/hwdef.dat @@ -27,14 +27,6 @@ define BOARD_TYPE_DEFAULT 20 # crystal frequency OSCILLATOR_HZ 24000000 -define STM32_LSECLK 32768U -define STM32_LSEDRV (3U << 3U) -define STM32_PLLSRC STM32_PLLSRC_HSE -define STM32_PLLM_VALUE 24 -define STM32_PLLN_VALUE 432 -define STM32_PLLP_VALUE 2 -define STM32_PLLQ_VALUE 9 - # board ID for firmware load APJ_BOARD_ID 136 @@ -47,8 +39,6 @@ APJ_BOARD_ID 136 # now define the voltage the MCU runs at. This is needed for ChibiOS # to set various internal driver limits. It is in 0.01 volt units -# board voltage -STM32_VDD 330U # this is the STM32 timer that ChibiOS will use for the low level # driver. This must be a 32 bit timer. We currently only support @@ -69,9 +59,9 @@ env OPTIMIZE -O2 # in drivers. # serial port for stdout. This is optional. If you leave it out then -# output from printf() lines will be thrown away (you can stil use +# output from printf() lines will be sent to # hal.console->printf() for the ArduPilot console, which is the first -# UART in the UART_ORDER list). The value for STDOUT_SERIAL is a +# UART in the SERIAL_ORDER list. The value for STDOUT_SERIAL is a # serial device name, and must be for a serial device for which pins # are defined in this file. For example, SD7 is for UART7 (SD7 == # "serial device 7" in ChibiOS). @@ -109,7 +99,7 @@ I2C_ORDER I2C1 # 6) SERIAL5: extra UART (usually RTOS debug console) # order of UARTs (and USB) -UART_ORDER OTG1 UART4 USART2 USART3 UART8 UART7 OTG2 +SERIAL_ORDER OTG1 USART2 USART3 UART4 UART8 UART7 OTG2 # default the 2nd interface to MAVLink2 until MissionPlanner updates drivers define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2 @@ -430,13 +420,6 @@ define HAL_BATT_CURR_SCALE 17.0 # this defines the default maximum clock on I2C devices. define HAL_I2C_MAX_CLOCK 100000 -# uncomment the lines below to enable strict API -# checking in ChibiOS -# define CH_DBG_ENABLE_ASSERTS TRUE -# define CH_DBG_ENABLE_CHECKS TRUE -# define CH_DBG_SYSTEM_STATE_CHECK TRUE -# define CH_DBG_ENABLE_STACK_CHECK TRUE - # we can't share IO UART (USART6) DMA_NOSHARE USART6_TX USART6_RX ADC1 DMA_PRIORITY USART6* diff --git a/libraries/AP_HAL_ChibiOS/hwdef/mindpx-v2/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/mindpx-v2/hwdef-bl.dat index a455867a4c..1f0a23d9f7 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/mindpx-v2/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/mindpx-v2/hwdef-bl.dat @@ -4,7 +4,6 @@ # MCU class and specific type MCU STM32F4xx STM32F427xx -define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_CHIBIOS_MINDPXV2 define HAL_CHIBIOS_ARCH_MINDPXV2 1 # board ID for firmware load @@ -12,12 +11,9 @@ APJ_BOARD_ID 88 # crystal frequency OSCILLATOR_HZ 8000000 -STM32_PLLM_VALUE 8 STM32_ST_USE_TIMER 5 -# board voltage -STM32_VDD 330U # flash size FLASH_SIZE_KB 2048 @@ -29,7 +25,7 @@ FLASH_BOOTLOADER_LOAD_KB 16 FLASH_RESERVE_START_KB 0 # order of UARTs (and USB) -UART_ORDER OTG1 USART2 +SERIAL_ORDER OTG1 USART2 PA9 VBUS INPUT diff --git a/libraries/AP_HAL_ChibiOS/hwdef/mindpx-v2/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/mindpx-v2/hwdef.dat index 9e2f770f59..21da3e8499 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/mindpx-v2/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/mindpx-v2/hwdef.dat @@ -5,19 +5,14 @@ # MCU class and specific type MCU STM32F4xx STM32F427xx -define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_CHIBIOS_MINDPXV2 - # board ID for firmware load APJ_BOARD_ID 88 # crystal frequency OSCILLATOR_HZ 8000000 -STM32_PLLM_VALUE 8 STM32_ST_USE_TIMER 5 -# board voltage -STM32_VDD 330U # flash size FLASH_SIZE_KB 2048 @@ -36,7 +31,7 @@ FLASH_RESERVE_END_KB 0 I2C_ORDER I2C1 I2C2 # order of UARTs (and USB) -UART_ORDER OTG1 UART4 USART2 USART3 UART8 USART1 UART7 +SERIAL_ORDER OTG1 USART2 USART3 UART4 UART8 USART1 UART7 USART6 # UART4 is GPS PA0 UART4_TX UART4 @@ -110,7 +105,12 @@ PC2 BAT_VOLT_SENS ADC1 PC3 FMU_ADC1 ADC1 PC4 FMU_ADC2 ADC1 PC5 FMU_ADC3 ADC1 -PC6 TIM8_CH1 TIM8 RCIN PULLDOWN LOW # also USART6_RX for serial RC + +# RC input default to timer +PC6 TIM8_CH1 TIM8 RCININT PULLDOWN + +# alternative RC input using USART6 +PC6 USART6_TX USART6 NODMA ALT(1) PC8 SDIO_D0 SDIO PC9 SDIO_D1 SDIO @@ -194,9 +194,6 @@ define HAL_STORAGE_SIZE 16384 # enable RAMTROM parameter storage define HAL_WITH_RAMTRON 1 -# fallback to flash storage -define STORAGE_FLASH_PAGE 22 - # allow to have have a dedicated safety switch pin define HAL_HAVE_SAFETY_SWITCH 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/mini-pix/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/mini-pix/hwdef-bl.dat index cb04bc9480..c424c1f2e1 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/mini-pix/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/mini-pix/hwdef-bl.dat @@ -27,11 +27,9 @@ define HAL_LED_ON 0 # the location where the bootloader will put the firmware FLASH_BOOTLOADER_LOAD_KB 16 -# board voltage -STM32_VDD 330U # order of UARTs (and USB) -UART_ORDER OTG1 +SERIAL_ORDER OTG1 # USB pins PA11 OTG_FS_DM OTG1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/mini-pix/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/mini-pix/hwdef.dat index 0d0827d7f8..45311cd62c 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/mini-pix/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/mini-pix/hwdef.dat @@ -4,8 +4,6 @@ # MCU class and specific type MCU STM32F4xx STM32F405xx -define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_CHIBIOS_MINIPIX - # board ID for firmware load APJ_BOARD_ID 3 @@ -17,8 +15,6 @@ STM32_ST_USE_TIMER 5 FLASH_SIZE_KB 1024 -# board voltage -STM32_VDD 330U # use USB for stdout, so no STDOUT_SERIAL # STDOUT_SERIAL SD2 @@ -28,7 +24,7 @@ STM32_VDD 330U I2C_ORDER I2C2 I2C1 # order of UARTs (and USB) -UART_ORDER OTG1 UART4 USART3 USART2 +SERIAL_ORDER OTG1 USART3 USART2 UART4 # UART4 serial GPS PA0 UART4_TX UART4 @@ -74,7 +70,10 @@ PC2 LPS22HB_CS CS PC3 LED_SAFETY OUTPUT PC4 SAFETY_IN INPUT -PC7 TIM8_CH2 TIM8 RCIN PULLUP LOW # also USART6_RX for serial RC +# default to RCIN using timer capture +PC7 TIM8_CH2 TIM8 RCININT PULLDOWN + + PC8 SDIO_D0 SDIO PC9 SDIO_D1 SDIO PC10 SDIO_D2 SDIO @@ -136,9 +135,6 @@ define HAL_STORAGE_SIZE 16384 # enable RAMTROM parameter storage define HAL_WITH_RAMTRON 1 -# fallback to flash is no FRAM fitted -define STORAGE_FLASH_PAGE 22 - # enable FAT filesystem define HAL_OS_FATFS_IO 1 @@ -155,4 +151,3 @@ define HAL_GPIO_C_LED_PIN 2 define HAL_GPIO_LED_ON 0 define HAL_GPIO_LED_OFF 1 - diff --git a/libraries/AP_HAL_ChibiOS/hwdef/omnibusf4pro/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/omnibusf4pro/hwdef-bl.dat index 299edb8ccf..19cb64f2c0 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/omnibusf4pro/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/omnibusf4pro/hwdef-bl.dat @@ -9,7 +9,6 @@ APJ_BOARD_ID 131 # crystal frequency OSCILLATOR_HZ 8000000 -STM32_PLLM_VALUE 8 FLASH_SIZE_KB 1024 @@ -26,11 +25,9 @@ define HAL_LED_ON 0 # the location where the bootloader will put the firmware FLASH_BOOTLOADER_LOAD_KB 64 -# board voltage -STM32_VDD 330U # order of UARTs -UART_ORDER OTG1 +SERIAL_ORDER OTG1 PA11 OTG_FS_DM OTG1 PA12 OTG_FS_DP OTG1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/omnibusf4pro/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/omnibusf4pro/hwdef.dat index 800fe87bea..3e56caad28 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/omnibusf4pro/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/omnibusf4pro/hwdef.dat @@ -11,10 +11,6 @@ APJ_BOARD_ID 131 # crystal frequency OSCILLATOR_HZ 8000000 -STM32_PLLM_VALUE 8 - -# board voltage -STM32_VDD 330U STM32_ST_USE_TIMER 5 @@ -26,12 +22,15 @@ FLASH_RESERVE_START_KB 64 I2C_ORDER I2C2 # order of UARTs -UART_ORDER OTG1 USART6 USART1 +SERIAL_ORDER OTG1 USART1 USART3 USART6 UART4 #adc PC1 BAT_CURR_SENS ADC1 SCALE(1) PC2 BAT_VOLT_SENS ADC1 SCALE(1) + +#analog rssi pin (also could be used as analog airspeed input) PA0 RSSI_IN ADC1 +define BOARD_RSSI_ANA_PIN 0 #pwm output. 1 - 4 on main header, 5 & 6 on separated header w/o 5V supply, 7 & 8 on CH5 and CH6 pads PB0 TIM1_CH2N TIM1 PWM(1) GPIO(50) @@ -52,6 +51,12 @@ PA7 SPI1_MOSI SPI1 PB10 I2C2_SCL I2C2 PULLUP PB11 I2C2_SDA I2C2 PULLUP +# use I2C pins as USART3 (SERIAL2) in BRD_ALT_CONFIG=1 & 4 +PB10 USART3_TX USART3 ALT(1) +PB11 USART3_RX USART3 ALT(1) +PB10 USART3_TX USART3 ALT(4) +PB11 USART3_RX USART3 ALT(4) + PB15 SPI2_MOSI SPI2 PB14 SPI2_MISO SPI2 PB13 SPI2_SCK SPI2 @@ -63,6 +68,15 @@ PA9 USART1_TX USART1 PC6 USART6_TX USART6 PC7 USART6_RX USART6 +# UART4 TX available as an alternative config on PA0 (RSSI pad) with BRD_ALT_CONFIG=2 +PA0 UART4_TX UART4 ALT(2) + +# full UART4 also available as alt config on PA0 (RSSI pad) and PA1 (PWM output chan 5) with BRD_ALT_CONFIG=3 & 4 +PA0 UART4_TX UART4 ALT(3) +PA1 UART4_RX UART4 ALT(3) +PA0 UART4_TX UART4 ALT(4) +PA1 UART4_RX UART4 ALT(4) + PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD @@ -72,7 +86,6 @@ PC12 SPI3_MOSI SPI3 PC11 SPI3_MISO SPI3 PC10 SPI3_SCK SPI3 - PB5 LED_BLUE OUTPUT LOW GPIO(1) define HAL_GPIO_A_LED_PIN 1 @@ -96,8 +109,6 @@ SPIDEV sdcard SPI2 DEVID2 SDCARD_CS MODE0 400*KHZ 25*MHZ SPIDEV bmp280 SPI3 DEVID3 BMP280_CS MODE3 1*MHZ 8*MHZ SPIDEV osd SPI3 DEVID4 OSD_CS MODE0 10*MHZ 10*MHZ -define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_CHIBIOS_OMNIBUSF4PRO - # one IMU IMU Invensense SPI:mpu6000 ROTATION_YAW_180 @@ -125,14 +136,7 @@ define HAL_BATT_CURR_PIN 11 define HAL_BATT_VOLT_SCALE 11 define HAL_BATT_CURR_SCALE 18.2 -#analog rssi pin (also could be used as analog airspeed input) -# PA0 - ADC123_CH0 -define BOARD_RSSI_ANA_PIN 0 - - - - -define OSD_ENABLED ENABLED +define OSD_ENABLED 1 define HAL_OSD_TYPE_DEFAULT 1 #To complementary channels work we define this @@ -140,10 +144,16 @@ define STM32_PWM_USE_ADVANCED TRUE define BOARD_PWM_COUNT_DEFAULT 8 -#define CH_DBG_ENABLE_ASSERTS TRUE -#define CH_DBG_ENABLE_CHECKS TRUE -#define CH_DBG_SYSTEM_STATE_CHECK TRUE -#define CH_DBG_ENABLE_STACK_CHECK TRUE - #font for the osd ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin + +# disable SMBUS and fuel battery monitors to save flash +define HAL_BATTMON_SMBUS_ENABLE 0 +define HAL_BATTMON_FUEL_ENABLE 0 + +# disable parachute and sprayer to save flash +define HAL_PARACHUTE_ENABLED 0 +define HAL_SPRAYER_ENABLED 0 + +# reduce max size of embedded params for apj_tool.py +define AP_PARAM_MAX_EMBEDDED_PARAM 1024 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/omnibusf4v6/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/omnibusf4v6/hwdef-bl.dat index c1279073f9..9a915219cb 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/omnibusf4v6/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/omnibusf4v6/hwdef-bl.dat @@ -9,7 +9,6 @@ APJ_BOARD_ID 137 # crystal frequency OSCILLATOR_HZ 8000000 -STM32_PLLM_VALUE 8 FLASH_SIZE_KB 1024 @@ -26,11 +25,9 @@ define HAL_LED_ON 0 # the location where the bootloader will put the firmware FLASH_BOOTLOADER_LOAD_KB 64 -# board voltage -STM32_VDD 330U # order of UARTs -UART_ORDER OTG1 +SERIAL_ORDER OTG1 PA11 OTG_FS_DM OTG1 PA12 OTG_FS_DP OTG1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/omnibusf4v6/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/omnibusf4v6/hwdef.dat index 4f68da1d4e..833de66bbd 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/omnibusf4v6/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/omnibusf4v6/hwdef.dat @@ -11,10 +11,6 @@ APJ_BOARD_ID 137 # crystal frequency OSCILLATOR_HZ 8000000 -STM32_PLLM_VALUE 8 - -# board voltage -STM32_VDD 330U # ChibiOS system timer STM32_ST_USE_TIMER 5 @@ -28,7 +24,7 @@ I2C_ORDER I2C1 # order of UARTs -UART_ORDER OTG1 USART6 USART1 UART4 USART3 +SERIAL_ORDER OTG1 USART1 UART4 USART6 USART3 USART2 #PINS @@ -45,6 +41,8 @@ PB11 USART3_RX USART3 # UART4 (only RX) #"TX" pin PA0 is used for RSSI_ADC_CHANNEL PA1 UART4_RX UART4 +# transmit only usart2, for telemetry output (eg. Hott telem) +PA2 USART2_TX USART2 #adc PC1 BAT_CURR_SENS ADC1 SCALE(1) @@ -151,6 +149,6 @@ define STM32_PWM_USE_ADVANCED TRUE define BOARD_PWM_COUNT_DEFAULT 6 -define OSD_ENABLED ENABLED +define OSD_ENABLED 1 #font for the osd ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin diff --git a/libraries/AP_HAL_ChibiOS/hwdef/revo-mini/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/revo-mini/hwdef-bl.dat index 5c98e70b85..078b88a03f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/revo-mini/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/revo-mini/hwdef-bl.dat @@ -9,7 +9,6 @@ APJ_BOARD_ID 124 # crystal frequency OSCILLATOR_HZ 8000000 -STM32_PLLM_VALUE 8 FLASH_SIZE_KB 1024 @@ -27,11 +26,9 @@ define HAL_LED_ON 0 # the location where the bootloader will put the firmware FLASH_BOOTLOADER_LOAD_KB 64 -# board voltage -STM32_VDD 330U # order of UARTs -UART_ORDER OTG1 +SERIAL_ORDER OTG1 PA11 OTG_FS_DM OTG1 PA12 OTG_FS_DP OTG1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/revo-mini/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/revo-mini/hwdef.dat index c7626b78fa..554316c732 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/revo-mini/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/revo-mini/hwdef.dat @@ -4,21 +4,16 @@ # MCU class and specific type MCU STM32F4xx STM32F405xx -define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_CHIBIOS_REVOMINI - # board ID for firmware load APJ_BOARD_ID 124 # crystal frequency OSCILLATOR_HZ 8000000 -STM32_PLLM_VALUE 8 define STM32_ST_USE_TIMER 5 FLASH_SIZE_KB 1024 -# board voltage -STM32_VDD 330U # use USB for stdout, so no STDOUT_SERIAL # STDOUT_SERIAL SD3 @@ -28,7 +23,7 @@ STM32_VDD 330U I2C_ORDER I2C1 # order of UARTs (and USB) -UART_ORDER OTG1 USART3 USART1 +SERIAL_ORDER OTG1 USART1 EMPTY USART3 # rcinput is PC6, which is the 3rd "PWM IN" pin (the yellow wire on a # revolution board) @@ -138,4 +133,5 @@ define HAL_LOGGING_DATAFLASH # 8 PWM available by default define BOARD_PWM_COUNT_DEFAULT 8 +define HAL_WITH_DSP FALSE diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F100xB.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F100xB.py index 7a5aa06111..61ffc280eb 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F100xB.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F100xB.py @@ -30,7 +30,9 @@ mcu = { # flags of 2 means faster memory for CPU intensive work 'RAM_MAP' : [ (0x20000000, 8, 1), # main memory, DMA safe - ] + ], + + 'EXPECTED_CLOCK' : 24000000 } ADC1_map = { diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F103xB.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F103xB.py index c3e8220f38..d7723cc730 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F103xB.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F103xB.py @@ -27,7 +27,9 @@ mcu = { 'RAM_MAP' : [ (0x20000000, 20, 1), # main memory, DMA safe - ] + ], + + 'EXPECTED_CLOCK' : 72000000 } ADC1_map = { diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F303xC.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F303xC.py new file mode 100644 index 0000000000..2cc82581df --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F303xC.py @@ -0,0 +1,464 @@ +#!/usr/bin/env python +''' +these tables are generated from the STM32 datasheets for the +STM32F303 +''' + +# additional build information for ChibiOS +build = { + "CHIBIOS_STARTUP_MK" : "os/common/startup/ARMCMx/compilers/GCC/mk/startup_stm32f3xx.mk", + "CHIBIOS_PLATFORM_MK" : "os/hal/ports/STM32/STM32F3xx/platform.mk" + } + +# MCU parameters +mcu = { + # location of MCU serial number + 'UDID_START' : 0x1FFFF7AC, + + # ram map, as list of (address, size-kb, flags) + # flags of 1 means DMA-capable + # flags of 2 means faster memory for CPU intensive work + 'RAM_MAP' : [ + (0x20000000, 40, 1), # main memory, DMA safe + (0x10000000, 8, 2), # CCM memory, faster, but not DMA safe + ], + + 'EXPECTED_CLOCK' : 72000000 +} + +AltFunction_map = { + # format is PIN:FUNCTION : AFNUM + # extracted from tabula-AF-STM32F303cc.csv + "PA0:COMP1_OUT" : 8, + "PA0:EVENTOUT" : 15, + "PA0:TIM2_CH1_ETR" : 1, + "PA0:TIM8_BKIN" : 9, + "PA0:TIM8_ETR" : 10, + "PA0:TSC_G1_IO1" : 3, + "PA0:USART2_CTS" : 7, + "PA1:EVENTOUT" : 15, + "PA1:RTC_REFIN" : 0, + "PA1:TIM15_CH1N" : 9, + "PA1:TIM2_CH2" : 1, + "PA1:TSC_G1_IO2" : 3, + "PA1:USART2_RTS_DE" : 7, + "PA2:COMP2_OUT" : 8, + "PA2:EVENTOUT" : 15, + "PA2:TIM15_CH1" : 9, + "PA2:TIM2_CH3" : 1, + "PA2:TSC_G1_IO3" : 3, + "PA2:USART2_TX" : 7, + "PA3:EVENTOUT" : 15, + "PA3:TIM15_CH2" : 9, + "PA3:TIM2_CH4" : 1, + "PA3:TSC_G1_IO4" : 3, + "PA3:USART2_RX" : 7, + "PA4:EVENTOUT" : 15, + "PA4:SPI1_NSS" : 5, + "PA4:SPI3_NSS,I2S3_WS" : 6, + "PA4:TIM3_CH2" : 2, + "PA4:TSC_G2_IO1" : 3, + "PA4:USART2_CK" : 7, + "PA5:EVENTOUT" : 15, + "PA5:SPI1_SCK" : 5, + "PA5:TIM2_CH1_ETR" : 1, + "PA5:TSC_G2_IO2" : 3, + "PA6:COMP1_OUT" : 8, + "PA6:EVENTOUT" : 15, + "PA6:SPI1_MISO" : 5, + "PA6:TIM16_CH1" : 1, + "PA6:TIM1_BKIN" : 6, + "PA6:TIM3_CH1" : 2, + "PA6:TIM8_BKIN" : 4, + "PA6:TSC_G2_IO3" : 3, + "PA7:COMP2_OUT" : 8, + "PA7:EVENTOUT" : 15, + "PA7:SPI1_MOSI" : 5, + "PA7:TIM17_CH1" : 1, + "PA7:TIM1_CH1N" : 6, + "PA7:TIM3_CH2" : 2, + "PA7:TIM8_CH1N" : 4, + "PA7:TSC_G2_IO4" : 3, + "PA8:COMP3_OUT" : 8, + "PA8:EVENTOUT" : 15, + "PA8:I2C2_SMBA" : 4, + "PA8:I2S2_MCK" : 5, + "PA8:MCO" : 0, + "PA8:TIM1_CH1" : 6, + "PA8:TIM4_ETR" : 10, + "PA8:USART1_CK" : 7, + "PA9:COMP5_OUT" : 8, + "PA9:EVENTOUT" : 15, + "PA9:I2C2_SCL" : 4, + "PA9:I2S3_MCK" : 5, + "PA9:TIM15_BKIN" : 9, + "PA9:TIM1_CH2" : 6, + "PA9:TIM2_CH3" : 10, + "PA9:TSC_G4_IO1" : 3, + "PA9:USART1_TX" : 7, + "PA10:COMP6_OUT" : 8, + "PA10:EVENTOUT" : 15, + "PA10:I2C2_SDA" : 4, + "PA10:TIM17_BKIN" : 1, + "PA10:TIM1_CH3" : 6, + "PA10:TIM2_CH4" : 10, + "PA10:TIM8_BKIN" : 11, + "PA10:TSC_G4_IO2" : 3, + "PA10:USART1_RX" : 7, + "PA11:CAN_RX" : 9, + "PA11:COMP1_OUT" : 8, + "PA11:EVENTOUT" : 15, + "PA11:TIM1_BKIN2" : 12, + "PA11:TIM1_CH1N" : 6, + "PA11:TIM1_CH4" : 11, + "PA11:TIM4_CH1" : 10, + "PA11:USART1_CTS" : 7, + "PA11:USB_DM" : 14, + "PA12:CAN_TX" : 9, + "PA12:COMP2_OUT" : 8, + "PA12:EVENTOUT" : 15, + "PA12:TIM16_CH1" : 1, + "PA12:TIM1_CH2N" : 6, + "PA12:TIM1_ETR" : 11, + "PA12:TIM4_CH2" : 10, + "PA12:USART1_RTS_DE" : 7, + "PA12:USB_DP" : 14, + "PA13:EVENTOUT" : 15, + "PA13:IR_OUT" : 5, + "PA13:SWDIO-JTMS" : 0, + "PA13:TIM16_CH1N" : 1, + "PA13:TIM4_CH3" : 10, + "PA13:TSC_G4_IO3" : 3, + "PA13:USART3_CTS" : 7, + "PA14:EVENTOUT" : 15, + "PA14:I2C1_SDA" : 4, + "PA14:SWCLK-JTCK" : 0, + "PA14:TIM1_BKIN" : 6, + "PA14:TIM8_CH2" : 5, + "PA14:TSC_G4_IO4" : 3, + "PA14:USART2_TX" : 7, + "PA15:EVENTOUT" : 15, + "PA15:I2C1_SCL" : 4, + "PA15:JTDI" : 0, + "PA15:SPI1_NSS" : 5, + "PA15:SPI3_NSS,I2S3_WS" : 6, + "PA15:TIM1_BKIN" : 9, + "PA15:TIM2_CH1_ETR" : 1, + "PA15:TIM8_CH1" : 2, + "PA15:USART2_RX" : 7, + "PB0:EVENTOUT" : 12, + "PB0:TIM1_CH2N" : 6, + "PB0:TIM3_CH3" : 2, + "PB0:TIM8_CH2N" : 4, + "PB0:TSC_G3_IO2" : 3, + "PB1:COMP4_OUT" : 8, + "PB1:EVENTOUT" : 12, + "PB1:TIM1_CH3N" : 6, + "PB1:TIM3_CH4" : 2, + "PB1:TIM8_CH3N" : 4, + "PB1:TSC_G3_IO3" : 3, + "PB2:EVENTOUT" : 12, + "PB2:TSC_G3_IO4" : 3, + "PB3:EVENTOUT" : 12, + "PB3:JTDO-TRACESWO" : 0, + "PB3:SPI1_SCK" : 5, + "PB3:SPI3_SCK,I2S3_CK" : 6, + "PB3:TIM2_CH2" : 1, + "PB3:TIM3_ETR" : 10, + "PB3:TIM4_ETR" : 2, + "PB3:TIM8_CH1N" : 4, + "PB3:TSC_G5_IO1" : 3, + "PB3:USART2_TX" : 7, + "PB4:EVENTOUT" : 12, + "PB4:NJTRST" : 0, + "PB4:SPI1_MISO" : 5, + "PB4:SPI3_MISO,I2S3EXT_SD" : 6, + "PB4:TIM16_CH1" : 1, + "PB4:TIM17_BKIN" : 10, + "PB4:TIM3_CH1" : 2, + "PB4:TIM8_CH2N" : 4, + "PB4:TSC_G5_IO2" : 3, + "PB4:USART2_RX" : 7, + "PB5:EVENTOUT" : 12, + "PB5:I2C1_SMBA" : 4, + "PB5:SPI1_MOSI" : 5, + "PB5:SPI3_MOSI,I2S3_SD" : 6, + "PB5:TIM16_BKIN" : 1, + "PB5:TIM17_CH1" : 10, + "PB5:TIM3_CH2" : 2, + "PB5:TIM8_CH3N" : 3, + "PB5:USART2_CK" : 7, + "PB6:EVENTOUT" : 12, + "PB6:I2C1_SCL" : 4, + "PB6:TIM16_CH1N" : 1, + "PB6:TIM4_CH1" : 2, + "PB6:TIM8_BKIN2" : 10, + "PB6:TIM8_CH1" : 5, + "PB6:TIM8_ETR" : 6, + "PB6:TSC_G5_IO3" : 3, + "PB6:USART1_TX" : 7, + "PB7:EVENTOUT" : 12, + "PB7:I2C1_SDA" : 4, + "PB7:TIM17_CH1N" : 1, + "PB7:TIM3_CH4" : 10, + "PB7:TIM4_CH2" : 2, + "PB7:TIM8_BKIN" : 5, + "PB7:TSC_G5_IO4" : 3, + "PB7:USART1_RX" : 7, + "PB8:CAN_RX" : 9, + "PB8:COMP1_OUT" : 8, + "PB8:EVENTOUT" : 12, + "PB8:I2C1_SCL" : 4, + "PB8:TIM16_CH1" : 1, + "PB8:TIM1_BKIN" : 11, + "PB8:TIM4_CH3" : 2, + "PB8:TIM8_CH2" : 10, + "PB8:TSC_SYNC" : 3, + "PB9:CAN_TX" : 9, + "PB9:COMP2_OUT" : 8, + "PB9:EVENTOUT" : 12, + "PB9:I2C1_SDA" : 4, + "PB9:IR_OUT" : 6, + "PB9:TIM17_CH1" : 1, + "PB9:TIM4_CH4" : 2, + "PB9:TIM8_CH3" : 10, + "PB10:EVENTOUT" : 12, + "PB10:TIM2_CH3" : 1, + "PB10:TSC_SYNC" : 3, + "PB10:USART3_TX" : 7, + "PB11:EVENTOUT" : 12, + "PB11:TIM2_CH4" : 1, + "PB11:TSC_G6_IO1" : 3, + "PB11:USART3_RX" : 7, + "PB12:EVENTOUT" : 12, + "PB12:I2C2_SMBA" : 4, + "PB12:SPI2_NSS,I2S2_WS" : 5, + "PB12:TIM1_BKIN" : 6, + "PB12:TSC_G6_IO2" : 3, + "PB12:USART3_CK" : 7, + "PB13:EVENTOUT" : 12, + "PB13:SPI2_SCK,I2S2_CK" : 5, + "PB13:TIM1_CH1N" : 6, + "PB13:TSC_G6_IO3" : 3, + "PB13:USART3_CTS" : 7, + "PB14:EVENTOUT" : 12, + "PB14:SPI2_MISO,I2S2EXT_SD" : 5, + "PB14:TIM15_CH1" : 1, + "PB14:TIM1_CH2N" : 6, + "PB14:TSC_G6_IO4" : 3, + "PB14:USART3_RTS_DE" : 7, + "PB15:EVENTOUT" : 12, + "PB15:RTC_REFIN" : 0, + "PB15:SPI2_MOSI,I2S2_SD" : 5, + "PB15:TIM15_CH1N" : 2, + "PB15:TIM15_CH2" : 1, + "PB15:TIM1_CH3N" : 4, + "PC0:EVENTOUT" : 0, + "PC1:EVENTOUT" : 0, + "PC2:COMP7_OUT" : 2, + "PC2:EVENTOUT" : 0, + "PC3:EVENTOUT" : 0, + "PC3:TIM1_BKIN2" : 5, + "PC4:EVENTOUT" : 0, + "PC4:USART1_TX" : 6, + "PC5:EVENTOUT" : 0, + "PC5:TSC_G3_IO1" : 2, + "PC5:USART1_RX" : 6, + "PC6:COMP6_OUT" : 6, + "PC6:EVENTOUT" : 0, + "PC6:I2S2_MCK" : 5, + "PC6:TIM3_CH1" : 1, + "PC6:TIM8_CH1" : 3, + "PC7:COMP5_OUT" : 6, + "PC7:EVENTOUT" : 0, + "PC7:I2S3_MCK" : 5, + "PC7:TIM3_CH2" : 1, + "PC7:TIM8_CH2" : 3, + "PC8:COMP3_OUT" : 6, + "PC8:EVENTOUT" : 0, + "PC8:TIM3_CH3" : 1, + "PC8:TIM8_CH3" : 3, + "PC9:EVENTOUT" : 0, + "PC9:I2S_CKIN" : 4, + "PC9:TIM3_CH4" : 1, + "PC9:TIM8_BKIN2" : 5, + "PC9:TIM8_CH4" : 3, + "PC10:EVENTOUT" : 0, + "PC10:SPI3_SCK,I2S3_CK" : 5, + "PC10:TIM8_CH1N" : 3, + "PC10:UART4_TX" : 4, + "PC10:USART3_TX" : 6, + "PC11:EVENTOUT" : 0, + "PC11:SPI3_MISO,I2S3EXT_SD" : 5, + "PC11:TIM8_CH2N" : 3, + "PC11:UART4_RX" : 4, + "PC11:USART3_RX" : 6, + "PC12:EVENTOUT" : 0, + "PC12:SPI3_MOSI,I2S3_SD" : 5, + "PC12:TIM8_CH3N" : 3, + "PC12:UART5_TX" : 4, + "PC12:USART3_CK" : 6, + "PC13:TIM1_CH1N" : 3, + "PD0:CAN_RX" : 6, + "PD0:EVENTOUT" : 0, + "PD1:CAN_TX" : 6, + "PD1:EVENTOUT" : 0, + "PD1:TIM8_BKIN2" : 5, + "PD1:TIM8_CH4" : 3, + "PD2:EVENTOUT" : 0, + "PD2:TIM3_ETR" : 1, + "PD2:TIM8_BKIN" : 3, + "PD2:UART5_RX" : 4, + "PD3:EVENTOUT" : 0, + "PD3:TIM2_CH1_ETR" : 1, + "PD3:USART2_CTS" : 6, + "PD4:EVENTOUT" : 0, + "PD4:TIM2_CH2" : 1, + "PD4:USART2_RTS_DE" : 6, + "PD5:EVENTOUT" : 0, + "PD5:USART2_TX" : 6, + "PD6:EVENTOUT" : 0, + "PD6:TIM2_CH4" : 1, + "PD6:USART2_RX" : 6, + "PD7:EVENTOUT" : 0, + "PD7:TIM2_CH3" : 1, + "PD7:USART2_CK" : 6, + "PD8:EVENTOUT" : 0, + "PD8:USART3_TX" : 6, + "PD9:EVENTOUT" : 0, + "PD9:USART3_RX" : 6, + "PD10:EVENTOUT" : 0, + "PD10:USART3_CK" : 6, + "PD11:EVENTOUT" : 0, + "PD11:USART3_CTS" : 6, + "PD12:EVENTOUT" : 0, + "PD12:TIM4_CH1" : 1, + "PD12:TSC_G8_IO1" : 2, + "PD12:USART3_RTS_DE" : 6, + "PD13:EVENTOUT" : 0, + "PD13:TIM4_CH2" : 1, + "PD13:TSC_G8_IO2" : 2, + "PD14:EVENTOUT" : 0, + "PD14:TIM4_CH3" : 1, + "PD14:TSC_G8_IO3" : 2, + "PD15:EVENTOUT" : 0, + "PD15:SPI2_NSS" : 5, + "PD15:TIM4_CH4" : 1, + "PD15:TSC_G8_IO4" : 2, + "PE0:EVENTOUT" : 1, + "PE0:TIM16_CH1" : 4, + "PE0:TIM4_ETR" : 2, + "PE0:USART1_TX" : 6, + "PE1:EVENTOUT" : 1, + "PE1:TIM17_CH1" : 4, + "PE1:USART1_RX" : 6, + "PE2:EVENTOUT" : 1, + "PE2:TIM3_CH1" : 2, + "PE2:TRACECK" : 0, + "PE2:TSC_G7_IO1" : 3, + "PE3:EVENTOUT" : 1, + "PE3:TIM3_CH2" : 2, + "PE3:TRACED0" : 0, + "PE3:TSC_G7_IO2" : 3, + "PE4:EVENTOUT" : 1, + "PE4:TIM3_CH3" : 2, + "PE4:TRACED1" : 0, + "PE4:TSC_G7_IO3" : 3, + "PE5:EVENTOUT" : 1, + "PE5:TIM3_CH4" : 2, + "PE5:TRACED2" : 0, + "PE5:TSC_G7_IO4" : 3, + "PE6:EVENTOUT" : 1, + "PE6:TRACED3" : 0, + "PE7:EVENTOUT" : 1, + "PE7:TIM1_ETR" : 2, + "PE8:EVENTOUT" : 1, + "PE8:TIM1_CH1N" : 2, + "PE9:EVENTOUT" : 1, + "PE9:TIM1_CH1" : 2, + "PE10:EVENTOUT" : 1, + "PE10:TIM1_CH2N" : 2, + "PE11:EVENTOUT" : 1, + "PE11:TIM1_CH2" : 2, + "PE12:EVENTOUT" : 1, + "PE12:TIM1_CH3N" : 2, + "PE13:EVENTOUT" : 1, + "PE13:TIM1_CH3" : 2, + "PE14:EVENTOUT" : 1, + "PE14:TIM1_BKIN2" : 5, + "PE14:TIM1_CH4" : 2, + "PE15:EVENTOUT" : 1, + "PE15:TIM1_BKIN" : 2, + "PE15:USART3_RX" : 6, + "PF0:I2C2_SDA" : 3, + "PF0:TIM1_CH3N" : 5, + "PF1:I2C2_SCL" : 3, + "PF2:EVENTOUT" : 0, + "PF4:COMP1_OUT" : 1, + "PF4:EVENTOUT" : 0, + "PF6:EVENTOUT" : 0, + "PF6:I2C2_SCL" : 3, + "PF6:TIM4_CH4" : 1, + "PF6:USART3_RTS_DE" : 6, + "PF9:EVENTOUT" : 0, + "PF9:SPI2_SCK" : 4, + "PF9:TIM15_CH1" : 2, + "PF10:EVENTOUT" : 0, + "PF10:SPI2_SCK" : 4, + "PF10:TIM15_CH2" : 2, +} + +ADC1_map = { + # format is PIN : ADC1_CHAN + # extracted from tabula-addfunc-F405.csv + "PA0" : 1, + "PA1" : 2, + "PA2" : 3, + "PA3" : 4, + "PF4" : 5, + "PC0" : 6, + "PC1" : 7, + "PC2" : 8, + "PC3" : 9, + "PF2" : 10, +} + +DMA_Map = { + # format is (DMA_TABLE, StreamNum, Channel) + # extracted from tabula-STM32F303-DMA.csv + "ADC1" : [(1,1,0)], + "SPI1_RX" : [(1,2,0)], + "SPI1_TX" : [(1,3,0)], + "SPI2_RX" : [(1,4,0)], + "SPI2_TX" : [(1,5,0)], + "USART3_TX" : [(1,2,0)], + "USART3_RX" : [(1,3,0)], + "USART1_TX" : [(1,4,0)], + "USART1_RX" : [(1,5,0)], + "USART2_RX" : [(1,6,0)], + "USART2_TX" : [(1,7,0)], + "I2C2_TX" : [(1,4,0)], + "I2C2_RX" : [(1,5,0)], + "I2C1_TX" : [(1,6,0)], + "I2C1_RX" : [(1,7,0)], + "TIM1_CH1" : [(1,2,0)], + "TIM1_CH2" : [(1,3,0)], + "TIM1_CH4" : [(1,4,0)], + "TIM1_UP" : [(1,5,0)], + "TIM1_CH3" : [(1,6,0)], + "TIM2_CH3" : [(1,1,0)], + "TIM2_UP" : [(1,2,0)], + "TIM2_CH1" : [(1,5,0)], + "TIM2_CH2" : [(1,7,0)], + "TIM2_CH4" : [(1,7,0)], + "TIM3_CH3" : [(1,2,0)], + "TIM3_CH4" : [(1,3,0)], + "TIM3_UP" : [(1,3,0)], + "TIM3_CH1" : [(1,6,0)], + "TIM15_CH1" : [(1,5,0)], + "TIM15_UP" : [(1,5,0)], + "TIM16_CH1" : [(1,3,0)], + "TIM16_UP" : [(1,3,0)], + "TIM17_CH1" : [(1,1,0)], + "TIM17_UP" : [(1,1,0)], +} diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F405xx.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F405xx.py index 9c98c31a11..8eee261686 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F405xx.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F405xx.py @@ -21,7 +21,9 @@ mcu = { 'RAM_MAP' : [ (0x20000000, 128, 1), # main memory, DMA safe (0x10000000, 64, 2), # CCM memory, faster, but not DMA safe - ] + ], + + 'EXPECTED_CLOCK' : 168000000 } AltFunction_map = { diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F412Rx.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F412Rx.py index 38772d3fe8..b36f2389e8 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F412Rx.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F412Rx.py @@ -44,7 +44,7 @@ DMA_Map = { "QUADSPI" : [(2,7,3)], "SDIO" : [(2,3,4),(2,6,4)], "SPI1_RX" : [(2,0,3),(2,2,3)], - "SPI1_TX" : [(2,2,2),(2,3,3),(2,5,3)], + "SPI1_TX" : [(2,3,3),(2,5,3)], "SPI2_RX" : [(1,3,0)], "SPI2_TX" : [(1,4,0)], "SPI3_RX" : [(1,0,0),(1,2,0)], diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F427xx.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F427xx.py index 3c2f1c9f1b..c33eab2445 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F427xx.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F427xx.py @@ -21,7 +21,9 @@ mcu = { 'RAM_MAP' : [ (0x20000000, 192, 1), # main memory, DMA safe (0x10000000, 64, 2), # CCM memory, faster, but not DMA safe - ] + ], + + 'EXPECTED_CLOCK' : 168000000 } DMA_Map = { diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F745xx.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F745xx.py index 1a5496147c..cfb26157c0 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F745xx.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F745xx.py @@ -21,7 +21,15 @@ mcu = { 'RAM_MAP' : [ (0x20010000, 256, 0), # main memory, not DMA safe (0x20000000, 64, 1), # DTCM memory, DMA safe - ] + ], + + 'EXPECTED_CLOCK' : 216000000, + + # this board has M7 instructions, but single precision only FPU + # we build as m4 as it makes for a smaller build, and given the 1M + # flash limit we care more about size + 'CORTEX' : 'cortex-m4', + 'CPU_FLAGS' : '-mcpu=cortex-m4 -mfpu=fpv4-sp-d16 -mfloat-abi=hard' } DMA_Map = { diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F767xx.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F767xx.py index 68e6ea4bda..e70a681571 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F767xx.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F767xx.py @@ -38,7 +38,13 @@ mcu = { # split DTCM in two to allow for fast checking of IS_DMA_SAFE in bouncebuffer code (0x20000000, 64, 1), # DTCM, DMA safe (0x20010000, 64, 2), # DTCM, 2nd half, used as fast memory. This lowers memory contention in the EKF code - ] + ], + + 'EXPECTED_CLOCK' : 216000000, + + # this MCU has M7 instructions and hardware double precision + 'CORTEX' : 'cortex-m7', + 'CPU_FLAGS' : '-mcpu=cortex-m7 -mfpu=fpv5-d16 -mfloat-abi=hard', } DMA_Map = { diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F777xx.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F777xx.py index 8a760476c5..86e1bfa0c6 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F777xx.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F777xx.py @@ -35,7 +35,13 @@ mcu = { 'RAM_MAP' : [ (0x20020000, 384, 0), # SRAM1/SRAM2 (0x20000000, 128, 1), # DTCM, DMA - ] + ], + + 'EXPECTED_CLOCK' : 216000000, + + # this MCU has M7 instructions and hardware double precision + 'CORTEX' : 'cortex-m7', + 'CPU_FLAGS' : '-mcpu=cortex-m7 -mfpu=fpv5-d16 -mfloat-abi=hard', } DMA_Map = { diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32H743xx.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32H743xx.py index 23a329aff7..b703dc3f32 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32H743xx.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32H743xx.py @@ -24,7 +24,13 @@ mcu = { (0x38000000, 64, 1), # SRAM4. This supports both DMA and BDMA ops (0x24000000, 512, 4), # AXI SRAM. Use this for SDMMC IDMA ops (0x00000400, 63, 2), # ITCM (first 1k removed, to keep address 0 unused) - ] + ], + + 'EXPECTED_CLOCK' : 400000000, + + # this MCU has M7 instructions and hardware double precision + 'CORTEX' : 'cortex-m7', + 'CPU_FLAGS' : '-mcpu=cortex-m7 -mfpu=fpv5-d16 -mfloat-abi=hard', } pincount = { diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/af_parse.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/af_parse.py index 2b0ace05ed..b65f7141b7 100755 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/af_parse.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/af_parse.py @@ -47,7 +47,7 @@ def pin_compare(p1, p2): return 1 def parse_af_table(fname, table): - csvt = csv.reader(open(fname,'rb')) + csvt = csv.reader(open(fname,'r')) i = 0 aflist = [] for row in csvt: @@ -63,6 +63,8 @@ def parse_af_table(fname, table): row = row[1:] pin = row[0] for i in range(len(aflist)): + if len(row) <= i+1: + break af = aflist[i] s = row[i+1] s = s.replace('_\r', '_') diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py index 449384ef44..d8953129df 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py @@ -3,7 +3,14 @@ setup board.h for chibios ''' -import argparse, sys, fnmatch, os, dma_resolver, shlex, pickle, re +import argparse +import sys +import fnmatch +import os +import dma_resolver +import shlex +import pickle +import re import shutil parser = argparse.ArgumentParser("chibios_pins.py") @@ -49,15 +56,24 @@ portmap = {} # dictionary of all config lines, indexed by first word config = {} +# alternate pin mappings +altmap = {} + # list of all pins in config file order allpins = [] # list of configs by type bytype = {} +# list of alt configs by type +alttype = {} + # list of configs by label bylabel = {} +# list of alt configs by label +altlabel = {} + # list of SPI devices spidev = [] @@ -81,6 +97,8 @@ imu_list = [] compass_list = [] baro_list = [] +all_lines = [] + mcu_type = None dual_USB_enabled = False @@ -107,9 +125,10 @@ def get_mcu_lib(mcu): except ImportError: error("Unable to find module for MCU %s" % mcu) + def setup_mcu_type_defaults(): '''setup defaults for given mcu type''' - global pincount, ports, portmap, vtypes + global pincount, ports, portmap, vtypes, mcu_type lib = get_mcu_lib(mcu_type) if hasattr(lib, 'pincount'): pincount = lib.pincount @@ -124,6 +143,7 @@ def setup_mcu_type_defaults(): for pin in range(pincount[port]): portmap[port].append(generic_pin(port, pin, None, 'INPUT', [])) + def get_alt_function(mcu, pin, function): '''return alternative function number for a pin''' lib = get_mcu_lib(mcu) @@ -131,7 +151,7 @@ def get_alt_function(mcu, pin, function): if function.endswith('_TXINV') or function.endswith('_RXINV'): # RXINV and TXINV are special labels for inversion pins, not alt-functions return None - + if hasattr(lib, "AltFunction_map"): alt_map = lib.AltFunction_map else: @@ -149,7 +169,7 @@ def get_alt_function(mcu, pin, function): for l in af_labels: if function.startswith(l): s = pin + ":" + function - if not s in alt_map: + if s not in alt_map: error("Unknown pin function %s for MCU %s" % (s, mcu)) return alt_map[s] return None @@ -157,11 +177,12 @@ def get_alt_function(mcu, pin, function): def have_type_prefix(ptype): '''return True if we have a peripheral starting with the given peripheral type''' - for t in bytype.keys(): + for t in list(bytype.keys()) + list(alttype.keys()): if t.startswith(ptype): return True return False + def get_ADC1_chan(mcu, pin): '''return ADC1 channel for an analog pin''' import importlib @@ -171,7 +192,7 @@ def get_ADC1_chan(mcu, pin): except ImportError: error("Unable to find ADC1_Map for MCU %s" % mcu) - if not pin in ADC1_map: + if pin not in ADC1_map: error("Unable to find ADC1 channel for pin %s" % pin) return ADC1_map[pin] @@ -206,16 +227,16 @@ class generic_pin(object): error("Peripheral prefix mismatch for %s %s %s" % (self.portpin, label, type)) def f1_pin_setup(self): - for l in af_labels: - if self.label.startswith(l): + for label in af_labels: + if self.label.startswith(label): if self.label.endswith(tuple(f1_input_sigs)): self.sig_dir = 'INPUT' self.extra.append('FLOATING') elif self.label.endswith(tuple(f1_output_sigs)): self.sig_dir = 'OUTPUT' - elif l == 'I2C': + elif label == 'I2C': self.sig_dir = 'OUTPUT' - elif l == 'OTG': + elif label == 'OTG': self.sig_dir = 'OUTPUT' else: error("Unknown signal type %s:%s for %s!" % (self.portpin, self.label, mcu_type)) @@ -257,7 +278,7 @@ class generic_pin(object): '''return true if this is a CS pin''' return self.has_extra("CS") or self.type == "CS" - def get_MODER(self): + def get_MODER_value(self): '''return one of ALTERNATE, OUTPUT, ANALOG, INPUT''' if self.af is not None: v = "ALTERNATE" @@ -271,9 +292,13 @@ class generic_pin(object): v = "OUTPUT" else: v = "INPUT" - return "PIN_MODE_%s(%uU)" % (v, self.pin) + return v - def get_OTYPER(self): + def get_MODER(self): + '''return one of ALTERNATE, OUTPUT, ANALOG, INPUT''' + return "PIN_MODE_%s(%uU)" % (self.get_MODER_value(), self.pin) + + def get_OTYPER_value(self): '''return one of PUSHPULL, OPENDRAIN''' v = 'PUSHPULL' if self.type.startswith('I2C'): @@ -283,9 +308,13 @@ class generic_pin(object): for e in self.extra: if e in values: v = e - return "PIN_OTYPE_%s(%uU)" % (v, self.pin) + return v - def get_OSPEEDR(self): + def get_OTYPER(self): + '''return one of PUSHPULL, OPENDRAIN''' + return "PIN_OTYPE_%s(%uU)" % (self.get_OTYPER_value(), self.pin) + + def get_OSPEEDR_value(self): '''return one of SPEED_VERYLOW, SPEED_LOW, SPEED_MEDIUM, SPEED_HIGH''' # on STM32F4 these speeds correspond to 2MHz, 25MHz, 50MHz and 100MHz values = ['SPEED_VERYLOW', 'SPEED_LOW', 'SPEED_MEDIUM', 'SPEED_HIGH'] @@ -293,9 +322,21 @@ class generic_pin(object): for e in self.extra: if e in values: v = e - return "PIN_O%s(%uU)" % (v, self.pin) + return v - def get_PUPDR(self): + def get_OSPEEDR_int(self): + '''return value from 0 to 3 for speed''' + values = ['SPEED_VERYLOW', 'SPEED_LOW', 'SPEED_MEDIUM', 'SPEED_HIGH'] + v = self.get_OSPEEDR_value() + if v not in values: + error("Bad OSPEED %s" % v) + return values.index(v) + + def get_OSPEEDR(self): + '''return one of SPEED_VERYLOW, SPEED_LOW, SPEED_MEDIUM, SPEED_HIGH''' + return "PIN_O%s(%uU)" % (self.get_OSPEEDR_value(), self.pin) + + def get_PUPDR_value(self): '''return one of FLOATING, PULLUP, PULLDOWN''' values = ['FLOATING', 'PULLUP', 'PULLDOWN'] v = 'FLOATING' @@ -308,7 +349,7 @@ class generic_pin(object): self.label.endswith('_RX') or self.label.endswith('_CTS') or self.label.endswith('_RTS'))): - v = "PULLUP" + v = "PULLUP" # generate pullups for SDIO and SDMMC if (self.type.startswith('SDIO') or self.type.startswith('SDMMC')) and ( @@ -317,13 +358,17 @@ class generic_pin(object): self.label.endswith('_D2') or self.label.endswith('_D3') or self.label.endswith('_CMD'))): - v = "PULLUP" + v = "PULLUP" for e in self.extra: if e in values: v = e - return "PIN_PUPDR_%s(%uU)" % (v, self.pin) + return v - def get_ODR_F1(self): + def get_PUPDR(self): + '''return one of FLOATING, PULLUP, PULLDOWN wrapped in PIN_PUPDR_ macro''' + return "PIN_PUPDR_%s(%uU)" % (self.get_PUPDR_value(), self.pin) + + def get_ODR_F1_value(self): '''return one of LOW, HIGH''' values = ['LOW', 'HIGH'] v = 'HIGH' @@ -334,30 +379,38 @@ class generic_pin(object): for e in self.extra: if e in values: v = e - #for some controllers input pull up down is selected by ODR + # for some controllers input pull up down is selected by ODR if self.type == "INPUT": v = 'LOW' if 'PULLUP' in self.extra: v = "HIGH" - return "PIN_ODR_%s(%uU)" % (v, self.pin) + return v - def get_ODR(self): + def get_ODR_value(self): '''return one of LOW, HIGH''' if mcu_series.startswith("STM32F1"): - return self.get_ODR_F1() + return self.get_ODR_F1_value() values = ['LOW', 'HIGH'] v = 'HIGH' for e in self.extra: if e in values: v = e - return "PIN_ODR_%s(%uU)" % (v, self.pin) + return v - def get_AFIO(self): + def get_ODR(self): + '''return one of LOW, HIGH wrapped in PIN_ODR macro''' + return "PIN_ODR_%s(%uU)" % (self.get_ODR_value(), self.pin) + + def get_AFIO_value(self): '''return AFIO''' af = self.af if af is None: af = 0 - return "PIN_AFIO_AF(%uU, %uU)" % (self.pin, af) + return af + + def get_AFIO(self): + '''return AFIO wrapped in PIN_AFIO_AF macro''' + return "PIN_AFIO_AF(%uU, %uU)" % (self.pin, self.get_AFIO_value()) def get_AFRL(self): '''return AFIO low 8''' @@ -373,7 +426,7 @@ class generic_pin(object): def get_CR_F1(self): '''return CR FLAGS for STM32F1xx''' - #Check Speed + # Check Speed if self.sig_dir != "INPUT" or self.af is not None: speed_values = ['SPEED_LOW', 'SPEED_MEDIUM', 'SPEED_HIGH'] v = 'SPEED_MEDIUM' @@ -425,7 +478,7 @@ class generic_pin(object): speed_str = "PIN_%s(%uU) |" % (v, self.pin) else: speed_str = "" - #Check Alternate function + # Check Alternate function if self.type.startswith('I2C'): v = "AF_OD" elif self.sig_dir == 'OUTPUT': @@ -456,6 +509,19 @@ class generic_pin(object): return None return self.get_CR() + def pal_modeline(self): + '''return a mode line suitable for palSetModeLine()''' + # MODER, OTYPER, OSPEEDR, PUPDR, ODR, AFRL, AFRH + ret = 'PAL_STM32_MODE_' + self.get_MODER_value() + ret += '|PAL_STM32_OTYPE_' + self.get_OTYPER_value() + ret += '|PAL_STM32_SPEED(%u)' % self.get_OSPEEDR_int() + ret += '|PAL_STM32_PUPDR_' + self.get_PUPDR_value() + af = self.get_AFIO_value() + if af != 0: + ret += '|PAL_STM32_ALTERNATE(%u)' % af + + return ret + def __str__(self): str = '' if self.af is not None: @@ -468,12 +534,14 @@ class generic_pin(object): str) -def get_config(name, column=0, required=True, default=None, type=None, spaces=False): +def get_config(name, column=0, required=True, default=None, type=None, spaces=False, aslist=False): '''get a value from config dictionary''' - if not name in config: + if name not in config: if required and default is None: error("missing required value %s in hwdef.dat" % name) return default + if aslist: + return config[name] if len(config[name]) < column + 1: if not required: return None @@ -483,11 +551,11 @@ def get_config(name, column=0, required=True, default=None, type=None, spaces=Fa ret = ' '.join(config[name][column:]) else: ret = config[name][column] - + if type is not None: if type == int and ret.startswith('0x'): try: - ret = int(ret,16) + ret = int(ret, 16) except Exception: error("Badly formed config value %s (got %s)" % (name, ret)) else: @@ -497,22 +565,35 @@ def get_config(name, column=0, required=True, default=None, type=None, spaces=Fa error("Badly formed config value %s (got %s)" % (name, ret)) return ret + def get_mcu_config(name, required=False): '''get a value from the mcu dictionary''' lib = get_mcu_lib(mcu_type) if not hasattr(lib, 'mcu'): error("Missing mcu config for %s" % mcu_type) - if not name in lib.mcu: + if name not in lib.mcu: if required: error("Missing required mcu config %s for %s" % (name, mcu_type)) return None return lib.mcu[name] + +def make_line(label): + '''return a line for a label''' + if label in bylabel: + p = bylabel[label] + line = 'PAL_LINE(GPIO%s,%uU)' % (p.port, p.pin) + else: + line = "0" + return line + + def enable_can(f): '''setup for a CAN enabled board''' f.write('#define HAL_WITH_UAVCAN 1\n') env_vars['HAL_WITH_UAVCAN'] = '1' + def has_sdcard_spi(): '''check for sdcard connected to spi bus''' for dev in spidev: @@ -520,6 +601,7 @@ def has_sdcard_spi(): return True return False + def write_mcu_config(f): '''write MCU config defines''' f.write('// MCU type (ChibiOS define)\n') @@ -547,12 +629,12 @@ def write_mcu_config(f): f.write('#define STM32_SDC_USE_SDMMC1 TRUE\n') build_flags.append('USE_FATFS=yes') elif has_sdcard_spi(): - f.write('// MMC via SPI available, enable POSIX filesystem support\n') - f.write('#define USE_POSIX\n\n') - f.write('#define HAL_USE_MMC_SPI TRUE\n') - f.write('#define HAL_USE_SDC FALSE\n') - f.write('#define HAL_SDCARD_SPI_HOOK TRUE\n') - build_flags.append('USE_FATFS=yes') + f.write('// MMC via SPI available, enable POSIX filesystem support\n') + f.write('#define USE_POSIX\n\n') + f.write('#define HAL_USE_MMC_SPI TRUE\n') + f.write('#define HAL_USE_SDC FALSE\n') + f.write('#define HAL_SDCARD_SPI_HOOK TRUE\n') + build_flags.append('USE_FATFS=yes') else: f.write('#define HAL_USE_SDC FALSE\n') build_flags.append('USE_FATFS=no') @@ -563,7 +645,7 @@ def write_mcu_config(f): f.write('#define HAL_USE_SERIAL_USB TRUE\n') if 'OTG2' in bytype: f.write('#define STM32_USB_USE_OTG2 TRUE\n') - if have_type_prefix('CAN') and not 'AP_PERIPH' in env_vars: + if have_type_prefix('CAN') and 'AP_PERIPH' not in env_vars: enable_can(f) if get_config('PROCESS_STACK', required=False): @@ -603,6 +685,7 @@ def write_mcu_config(f): f.write('#define FLASH_LOAD_ADDRESS 0x%08x\n' % (0x08000000 + flash_reserve_start*1024)) if args.bootloader: f.write('#define FLASH_BOOTLOADER_LOAD_KB %u\n' % get_config('FLASH_BOOTLOADER_LOAD_KB', type=int)) + f.write('#define FLASH_RESERVE_END_KB %u\n' % get_config('FLASH_RESERVE_END_KB', default=0, type=int)) f.write('\n') ram_map = get_mcu_config('RAM_MAP', True) @@ -629,17 +712,36 @@ def write_mcu_config(f): lib = get_mcu_lib(mcu_type) build_info = lib.build - if mcu_series.startswith("STM32F1"): - cortex = "cortex-m3" + if get_mcu_config('CPU_FLAGS') and get_mcu_config('CORTEX'): + # CPU flags specified in mcu file + cortex = get_mcu_config('CORTEX') + env_vars['CPU_FLAGS'] = get_mcu_config('CPU_FLAGS').split() + build_info['MCU'] = cortex + print("MCU Flags: %s %s" % (cortex, env_vars['CPU_FLAGS'])) + elif mcu_series.startswith("STM32F1"): + cortex = "cortex-m3" env_vars['CPU_FLAGS'] = ["-mcpu=%s" % cortex] build_info['MCU'] = cortex else: cortex = "cortex-m4" - env_vars['CPU_FLAGS'] = [ "-mcpu=%s" % cortex, "-mfpu=fpv4-sp-d16", "-mfloat-abi=hard"] + env_vars['CPU_FLAGS'] = ["-mcpu=%s" % cortex, "-mfpu=fpv4-sp-d16", "-mfloat-abi=hard"] build_info['MCU'] = cortex - if not args.bootloader: - env_vars['CPU_FLAGS'].append('-u_printf_float') - build_info['ENV_UDEFS'] = "-DCHPRINTF_USE_FLOAT=1" + + if get_mcu_config('EXPECTED_CLOCK'): + f.write('#define HAL_EXPECTED_SYSCLOCK %u\n' % get_mcu_config('EXPECTED_CLOCK')) + + env_vars['CORTEX'] = cortex + + if not args.bootloader: + if cortex == 'cortex-m4': + env_vars['CPU_FLAGS'].append('-DARM_MATH_CM4') + elif cortex == 'cortex-m7': + env_vars['CPU_FLAGS'].append('-DARM_MATH_CM7') + + if not mcu_series.startswith("STM32F1") and not args.bootloader: + env_vars['CPU_FLAGS'].append('-u_printf_float') + build_info['ENV_UDEFS'] = "-DCHPRINTF_USE_FLOAT=1" + # setup build variables for v in build_info.keys(): build_flags.append('%s=%s' % (v, build_info[v])) @@ -647,7 +749,7 @@ def write_mcu_config(f): # setup for bootloader build if args.bootloader: f.write(''' -#define HAL_BOOTLOADER_BUILD TRUE +#define HAL_BOOTLOADER_BUILD TRUE #define HAL_USE_ADC FALSE #define HAL_USE_EXT FALSE #define HAL_NO_UARTDRIVER @@ -662,7 +764,7 @@ def write_mcu_config(f): #define CH_CFG_USE_OBJ_FIFOS FALSE #define CH_DBG_FILL_THREADS FALSE #define CH_CFG_USE_SEMAPHORES FALSE -#define CH_CFG_USE_HEAP FALSE +#define CH_CFG_USE_HEAP FALSE #define CH_CFG_USE_MUTEXES FALSE #define CH_CFG_USE_CONDVARS FALSE #define CH_CFG_USE_CONDVARS_TIMEOUT FALSE @@ -674,10 +776,17 @@ def write_mcu_config(f): #define CH_CFG_USE_MEMCORE FALSE #define HAL_USE_I2C FALSE #define HAL_USE_PWM FALSE +#define CH_DBG_ENABLE_STACK_CHECK FALSE ''') if env_vars.get('ROMFS_UNCOMPRESSED', False): f.write('#define HAL_ROMFS_UNCOMPRESSED\n') + if 'AP_PERIPH' in env_vars: + f.write(''' +#define CH_DBG_ENABLE_STACK_CHECK FALSE +''') + + def write_ldscript(fname): '''write ldscript.ld for this board''' flash_size = get_config('FLASH_USE_MAX_KB', type=int, default=0) @@ -723,6 +832,7 @@ MEMORY INCLUDE common.ld ''' % (flash_base, flash_length, ram0_start, ram0_len)) + def copy_common_linkerscript(outdir, hwdef): dirpath = os.path.dirname(hwdef) shutil.copy(os.path.join(dirpath, "../common/common.ld"), @@ -741,7 +851,6 @@ def get_USB_IDs(): default_pid = 0x5741 return (get_config('USB_VENDOR', type=int, default=default_vid), get_config('USB_PRODUCT', type=int, default=default_pid)) - def write_USB_config(f): '''write USB config defines''' if not have_type_prefix('OTG'): @@ -750,12 +859,12 @@ def write_USB_config(f): (USB_VID, USB_PID) = get_USB_IDs() f.write('#define HAL_USB_VENDOR_ID 0x%04x\n' % int(USB_VID)) f.write('#define HAL_USB_PRODUCT_ID 0x%04x\n' % int(USB_PID)) - f.write('#define HAL_USB_STRING_MANUFACTURER "%s"\n' % get_config("USB_STRING_MANUFACTURER", default="ArduPilot")) + f.write('#define HAL_USB_STRING_MANUFACTURER %s\n' % get_config("USB_STRING_MANUFACTURER", default="\"ArduPilot\"")) default_product = "%BOARD%" if args.bootloader: default_product += "-BL" - f.write('#define HAL_USB_STRING_PRODUCT "%s"\n' % get_config("USB_STRING_PRODUCT", default=default_product)) - f.write('#define HAL_USB_STRING_SERIAL "%s"\n' % get_config("USB_STRING_SERIAL", default="%SERIAL%")) + f.write('#define HAL_USB_STRING_PRODUCT %s\n' % get_config("USB_STRING_PRODUCT", default="\"%s\""%default_product)) + f.write('#define HAL_USB_STRING_SERIAL %s\n' % get_config("USB_STRING_SERIAL", default="\"%SERIAL%\"")) f.write('\n\n') @@ -774,13 +883,13 @@ def write_SPI_table(f): mode = dev[4] lowspeed = dev[5] highspeed = dev[6] - if not bus.startswith('SPI') or not bus in spi_list: + if not bus.startswith('SPI') or bus not in spi_list: error("Bad SPI bus in SPIDEV line %s" % dev) if not devid.startswith('DEVID') or not is_int(devid[5:]): error("Bad DEVID in SPIDEV line %s" % dev) - if not cs in bylabel or not bylabel[cs].is_CS(): + if cs not in bylabel or not bylabel[cs].is_CS(): error("Bad CS pin in SPIDEV line %s" % dev) - if not mode in ['MODE0', 'MODE1', 'MODE2', 'MODE3']: + if mode not in ['MODE0', 'MODE1', 'MODE2', 'MODE3']: error("Bad MODE in SPIDEV line %s" % dev) if not lowspeed.endswith('*MHZ') and not lowspeed.endswith('*KHZ'): error("Bad lowspeed value %s in SPIDEV line %s" % (lowspeed, dev)) @@ -801,7 +910,7 @@ def write_SPI_table(f): def write_SPI_config(f): '''write SPI config defines''' global spi_list - for t in bytype.keys(): + for t in list(bytype.keys()) + list(alttype.keys()): if t.startswith('SPI'): spi_list.append(t) spi_list = sorted(spi_list) @@ -818,6 +927,7 @@ def write_SPI_config(f): f.write('#define HAL_SPI_BUS_LIST %s\n\n' % ','.join(devlist)) write_SPI_table(f) + def parse_spi_device(dev): '''parse a SPI:xxx device item''' a = dev.split(':') @@ -825,12 +935,13 @@ def parse_spi_device(dev): error("Bad SPI device: %s" % dev) return 'hal.spi->get_device("%s")' % a[1] + def parse_i2c_device(dev): '''parse a I2C:xxx:xxx device item''' a = dev.split(':') if len(a) != 3: error("Bad I2C device: %s" % dev) - busaddr = int(a[2],base=0) + busaddr = int(a[2], base=0) if a[1] == 'ALL_EXTERNAL': return ('FOREACH_I2C_EXTERNAL(b)', 'GET_I2C_DEVICE(b,0x%02x)' % (busaddr)) elif a[1] == 'ALL_INTERNAL': @@ -840,10 +951,12 @@ def parse_i2c_device(dev): busnum = int(a[1]) return ('', 'GET_I2C_DEVICE(%u,0x%02x)' % (busnum, busaddr)) + def seen_str(dev): '''return string representation of device for checking for duplicates''' return str(dev[:2]) + def write_IMU_config(f): '''write IMU config defines''' global imu_list @@ -855,7 +968,7 @@ def write_IMU_config(f): error("Duplicate IMU: %s" % seen_str(dev)) seen.add(seen_str(dev)) driver = dev[0] - for i in range(1,len(dev)): + for i in range(1, len(dev)): if dev[i].startswith("SPI:"): dev[i] = parse_spi_device(dev[i]) elif dev[i].startswith("I2C:"): @@ -868,6 +981,7 @@ def write_IMU_config(f): if len(devlist) > 0: f.write('#define HAL_INS_PROBE_LIST %s\n\n' % ';'.join(devlist)) + def write_MAG_config(f): '''write MAG config defines''' global compass_list @@ -884,7 +998,7 @@ def write_MAG_config(f): driver = a[0] if len(a) > 1 and a[1].startswith('probe'): probe = a[1] - for i in range(1,len(dev)): + for i in range(1, len(dev)): if dev[i].startswith("SPI:"): dev[i] = parse_spi_device(dev[i]) elif dev[i].startswith("I2C:"): @@ -897,6 +1011,7 @@ def write_MAG_config(f): if len(devlist) > 0: f.write('#define HAL_MAG_PROBE_LIST %s\n\n' % ';'.join(devlist)) + def write_BARO_config(f): '''write barometer config defines''' global baro_list @@ -913,7 +1028,7 @@ def write_BARO_config(f): driver = a[0] if len(a) > 1 and a[1].startswith('probe'): probe = a[1] - for i in range(1,len(dev)): + for i in range(1, len(dev)): if dev[i].startswith("SPI:"): dev[i] = parse_spi_device(dev[i]) elif dev[i].startswith("I2C:"): @@ -922,12 +1037,36 @@ def write_BARO_config(f): dev[i] = 'std::move(%s)' % dev[i] n = len(devlist)+1 devlist.append('HAL_BARO_PROBE%u' % n) + args = ['*this'] + dev[1:] f.write( - '#define HAL_BARO_PROBE%u %s ADD_BACKEND(AP_Baro_%s::%s(*this,%s))\n' - % (n, wrapper, driver, probe, ','.join(dev[1:]))) + '#define HAL_BARO_PROBE%u %s ADD_BACKEND(AP_Baro_%s::%s(%s))\n' + % (n, wrapper, driver, probe, ','.join(args))) if len(devlist) > 0: f.write('#define HAL_BARO_PROBE_LIST %s\n\n' % ';'.join(devlist)) - + +def write_board_validate_macro(f): + '''write board validation macro''' + global config + validate_string = '' + validate_dict = {} + if 'BOARD_VALIDATE' in config: + for check in config['BOARD_VALIDATE']: + check_name = check + check_string = check + while True: + def substitute_alias(m): + return '(' + get_config(m.group(1), spaces=True) + ')' + output = re.sub(r'\$(\w+|\{([^}]*)\})', substitute_alias, check_string) + if (output == check_string): + break + check_string = output + validate_dict[check_name] = check_string + # Finally create check conditional + for check_name in validate_dict: + validate_string += "!" + validate_dict[check_name] + "?" + "\"" + check_name + "\"" + ":" + validate_string += "nullptr" + f.write('#define HAL_VALIDATE_BOARD (%s)\n\n' % validate_string) + def get_gpio_bylabel(label): '''get GPIO(n) setting on a pin label, or -1''' p = bylabel.get(label) @@ -935,6 +1074,7 @@ def get_gpio_bylabel(label): return -1 return p.extra_value('GPIO', type=int, default=-1) + def get_extra_bylabel(label, name, default=None): '''get extra setting for a label by name''' p = bylabel.get(label) @@ -942,12 +1082,30 @@ def get_extra_bylabel(label, name, default=None): return default return p.extra_value(name, type=str, default=default) +def get_UART_ORDER(): + '''get UART_ORDER from SERIAL_ORDER option''' + if get_config('UART_ORDER', required=False, aslist=True) is not None: + error('Please convert UART_ORDER to SERIAL_ORDER') + serial_order = get_config('SERIAL_ORDER', required=False, aslist=True) + if serial_order is None: + return None + if args.bootloader: + # in bootloader SERIAL_ORDER is treated the same as UART_ORDER + return serial_order + map = [ 0, 3, 1, 2, 4, 5, 6, 7, 8, 9, 10, 11, 12 ] + while len(serial_order) < 4: + serial_order += ['EMPTY'] + uart_order = [] + for i in range(len(serial_order)): + uart_order.append(serial_order[map[i]]) + return uart_order + def write_UART_config(f): '''write UART config defines''' global dual_USB_enabled - if get_config('UART_ORDER', required=False) is None: + uart_list = get_UART_ORDER() + if uart_list is None: return - uart_list = config['UART_ORDER'] f.write('\n// UART configuration\n') # write out driver declarations for HAL_ChibOS_Class.cpp @@ -958,7 +1116,7 @@ def write_UART_config(f): for dev in uart_list: if dev == 'EMPTY': f.write('#define HAL_UART%s_DRIVER Empty::UARTDriver uart%sDriver\n' % - (devnames[idx], devnames[idx])) + (devnames[idx], devnames[idx])) num_empty_uarts += 1 else: f.write( @@ -1001,12 +1159,11 @@ def write_UART_config(f): else: error("Invalid element %s in UART_ORDER" % dev) devlist.append('HAL_%s_CONFIG' % dev) - if dev + "_RTS" in bylabel: - p = bylabel[dev + '_RTS'] - rts_line = 'PAL_LINE(GPIO%s,%uU)' % (p.port, p.pin) + tx_line = make_line(dev + '_TX') + rx_line = make_line(dev + '_RX') + rts_line = make_line(dev + '_RTS') + if rts_line != "0": have_rts_cts = True - else: - rts_line = "0" if dev.startswith('OTG2'): f.write( '#define HAL_%s_CONFIG {(BaseSequentialStream*) &SDU2, true, false, 0, 0, false, 0, 0}\n' @@ -1023,10 +1180,10 @@ def write_UART_config(f): "#define HAL_%s_CONFIG { (BaseSequentialStream*) &SD%u, false, " % (dev, n)) if mcu_series.startswith("STM32F1"): - f.write("%s, " % rts_line) + f.write("%s, %s, %s, " % (tx_line, rx_line, rts_line)) else: - f.write("STM32_%s_RX_DMA_CONFIG, STM32_%s_TX_DMA_CONFIG, %s, " % - (dev, dev, rts_line)) + f.write("STM32_%s_RX_DMA_CONFIG, STM32_%s_TX_DMA_CONFIG, %s, %s, %s, " % + (dev, dev, tx_line, rx_line, rts_line)) # add inversion pins, if any f.write("%d, " % get_gpio_bylabel(dev + "_RXINV")) @@ -1058,13 +1215,16 @@ def write_UART_config(f): num_uarts = len(devlist) if 'IOMCU_UART' in config: num_uarts -= 1 + if num_uarts > 8: + error("Exceeded max num UARTs of 8 (%u)" % num_uarts) f.write('#define HAL_UART_NUM_SERIAL_PORTS %u\n' % (num_uarts+num_empty_uarts)) + def write_UART_config_bootloader(f): '''write UART config defines''' - if get_config('UART_ORDER', required=False) is None: + uart_list = get_UART_ORDER() + if uart_list is None: return - uart_list = config['UART_ORDER'] f.write('\n// UART configuration\n') devlist = [] have_uart = False @@ -1089,6 +1249,7 @@ def write_UART_config_bootloader(f): #endif ''') + def write_I2C_config(f): '''write I2C config defines''' if not have_type_prefix('I2C'): @@ -1099,7 +1260,7 @@ def write_I2C_config(f): #endif ''') return - if not 'I2C_ORDER' in config: + if 'I2C_ORDER' not in config: print("Missing I2C_ORDER config") return i2c_list = config['I2C_ORDER'] @@ -1114,16 +1275,19 @@ def write_I2C_config(f): error("Bad I2C_ORDER element %s" % dev) n = int(dev[3:]) devlist.append('HAL_I2C%u_CONFIG' % n) + sda_line = make_line('I2C%u_SDA' % n) + scl_line = make_line('I2C%u_SCL' % n) f.write(''' #if defined(STM32_I2C_I2C%u_RX_DMA_STREAM) && defined(STM32_I2C_I2C%u_TX_DMA_STREAM) -#define HAL_I2C%u_CONFIG { &I2CD%u, STM32_I2C_I2C%u_RX_DMA_STREAM, STM32_I2C_I2C%u_TX_DMA_STREAM, HAL_GPIO_PIN_I2C%u_SCL, HAL_GPIO_PIN_I2C%u_SDA } +#define HAL_I2C%u_CONFIG { &I2CD%u, STM32_I2C_I2C%u_RX_DMA_STREAM, STM32_I2C_I2C%u_TX_DMA_STREAM, %s, %s } #else -#define HAL_I2C%u_CONFIG { &I2CD%u, SHARED_DMA_NONE, SHARED_DMA_NONE, HAL_GPIO_PIN_I2C%u_SCL, HAL_GPIO_PIN_I2C%u_SDA } +#define HAL_I2C%u_CONFIG { &I2CD%u, SHARED_DMA_NONE, SHARED_DMA_NONE, %s, %s } #endif ''' - % (n, n, n, n, n, n, n, n, n, n, n, n)) + % (n, n, n, n, n, n, scl_line, sda_line, n, n, scl_line, sda_line)) f.write('\n#define HAL_I2C_DEVICE_LIST %s\n\n' % ','.join(devlist)) + def parse_timer(str): '''parse timer channel string, i.e TIM8_CH2N''' result = re.match(r'TIM([0-9]*)_CH([1234])(N?)', str) @@ -1136,7 +1300,8 @@ def parse_timer(str): return (tim, chan, compl) else: error("Bad timer definition %s" % str) - + + def write_PWM_config(f): '''write PWM config defines''' rc_in = None @@ -1166,7 +1331,7 @@ def write_PWM_config(f): #define HAL_USE_PWM FALSE #endif ''') - + if rc_in is not None: (n, chan, compl) = parse_timer(rc_in.label) if compl: @@ -1183,11 +1348,11 @@ def write_PWM_config(f): f.write('#define STM32_RCIN_DMA_STREAM STM32_TIM_TIM%u_CH%u_DMA_STREAM\n' % (n, chan)) f.write('#define STM32_RCIN_DMA_CHANNEL STM32_TIM_TIM%u_CH%u_DMA_CHAN\n' % (n, chan)) f.write('\n') - + if rc_in_int is not None: (n, chan, compl) = parse_timer(rc_in_int.label) if compl: - error('Complementary channel is not supported for RCININT %s' % rc_in_int.label) + error('Complementary channel is not supported for RCININT %s' % rc_in_int.label) f.write('// RC input config\n') f.write('#define HAL_USE_EICU TRUE\n') f.write('#define STM32_EICU_USE_TIM%u TRUE\n' % n) @@ -1198,7 +1363,7 @@ def write_PWM_config(f): if alarm is not None: (n, chan, compl) = parse_timer(alarm.label) if compl: - error("Complementary channel is not supported for ALARM %s" % alarm.label) + error("Complementary channel is not supported for ALARM %s" % alarm.label) f.write('\n') f.write('// Alarm PWM output config\n') f.write('#define STM32_PWM_USE_TIM%u TRUE\n' % n) @@ -1230,8 +1395,8 @@ def write_PWM_config(f): }, \\ &PWMD%u /* PWMDriver* */ \\ }\n''' % - (chan-1, pwm_clock, period, chan_mode[0], - chan_mode[1], chan_mode[2], chan_mode[3], n)) + (chan-1, pwm_clock, period, chan_mode[0], + chan_mode[1], chan_mode[2], chan_mode[3], n)) else: f.write('\n') f.write('// No Alarm output pin defined\n') @@ -1255,8 +1420,8 @@ def write_PWM_config(f): 'PWM_OUTPUT_DISABLED', 'PWM_OUTPUT_DISABLED', 'PWM_OUTPUT_DISABLED', 'PWM_OUTPUT_DISABLED' ] - alt_functions = [ 0, 0, 0, 0 ] - pal_lines = [ '0', '0', '0', '0' ] + alt_functions = [0, 0, 0, 0] + pal_lines = ['0', '0', '0', '0'] for p in pwm_out: if p.type != t: continue @@ -1330,7 +1495,7 @@ def write_ADC_config(f): f.write('#define HAL_HAVE_SERVO_VOLTAGE 1\n') adc_chans.append((chan, scale, p.label, p.portpin)) adc_chans = sorted(adc_chans) - vdd = get_config('STM32_VDD') + vdd = get_config('STM32_VDD', default='330U') if vdd[-1] == 'U': vdd = vdd[:-1] vdd = float(vdd) * 0.01 @@ -1384,6 +1549,7 @@ def write_GPIO_config(f): (label, p.port, p.pin)) f.write('\n') + def bootloader_path(): # always embed a bootloader if it is available this_dir = os.path.realpath(__file__) @@ -1399,12 +1565,14 @@ def bootloader_path(): return None + def add_bootloader(): '''added bootloader to ROMFS''' bp = bootloader_path() if bp is not None: romfs["bootloader.bin"] = bp + def write_ROMFS(outdir): '''create ROMFS embedded header''' romfs_list = [] @@ -1412,6 +1580,7 @@ def write_ROMFS(outdir): romfs_list.append((k, romfs[k])) env_vars['ROMFS_FILES'] = romfs_list + def setup_apj_IDs(): '''setup the APJ board IDs''' env_vars['APJ_BOARD_ID'] = get_config('APJ_BOARD_ID') @@ -1419,10 +1588,11 @@ def setup_apj_IDs(): (USB_VID, USB_PID) = get_USB_IDs() env_vars['USBID'] = '0x%04x/0x%04x' % (USB_VID, USB_PID) + def write_peripheral_enable(f): '''write peripheral enable lines''' f.write('// peripherals enabled\n') - for type in sorted(bytype.keys()): + for type in sorted(list(bytype.keys()) + list(alttype.keys())): if type.startswith('USART') or type.startswith('UART'): dstr = 'STM32_SERIAL_USE_%-6s' % type f.write('#ifndef %s\n' % dstr) @@ -1435,17 +1605,47 @@ def write_peripheral_enable(f): if type.startswith('I2C'): f.write('#define STM32_I2C_USE_%s TRUE\n' % type) + def get_dma_exclude(periph_list): '''return list of DMA devices to exclude from DMA''' dma_exclude = [] for periph in periph_list: - if periph not in bylabel: - continue - p = bylabel[periph] - if p.has_extra('NODMA'): - dma_exclude.append(periph) + if periph in bylabel: + p = bylabel[periph] + if p.has_extra('NODMA'): + dma_exclude.append(periph) + if periph in altlabel: + p = altlabel[periph] + if p.has_extra('NODMA'): + dma_exclude.append(periph) return dma_exclude + +def write_alt_config(f): + '''write out alternate config settings''' + if len(altmap.keys()) == 0: + # no alt configs + return + f.write(''' +/* alternative configurations */ +#define PAL_STM32_SPEED(n) ((n&3U)<<3U) +#define PAL_STM32_HIGH 0x8000U + +#define HAL_PIN_ALT_CONFIG { \\ +''') + for alt in altmap.keys(): + for pp in altmap[alt].keys(): + p = altmap[alt][pp] + f.write(" { %u, %s, PAL_LINE(GPIO%s,%uU)}, /* %s */ \\\n" % (alt, p.pal_modeline(), p.port, p.pin, str(p))) + f.write('}\n\n') + +def write_all_lines(hwdat): + f = open(hwdat, 'w') + f.write('\n'.join(all_lines)) + f.close() + if not 'AP_PERIPH' in env_vars: + romfs["hwdef.dat"] = hwdat + def write_hwdef_header(outfilename): '''write hwdef header file''' print("Writing hwdef setup in %s" % outfilename) @@ -1474,13 +1674,14 @@ def write_hwdef_header(outfilename): write_IMU_config(f) write_MAG_config(f) write_BARO_config(f) + write_board_validate_macro(f) write_peripheral_enable(f) - dma_resolver.write_dma_header(f, periph_list, mcu_type, - dma_exclude=get_dma_exclude(periph_list), - dma_priority=get_config('DMA_PRIORITY',default='TIM* SPI*', spaces=True), - dma_noshare=get_config('DMA_NOSHARE',default='', spaces=True)) + dma_unassigned = dma_resolver.write_dma_header(f, periph_list, mcu_type, + dma_exclude=get_dma_exclude(periph_list), + dma_priority=get_config('DMA_PRIORITY', default='TIM* SPI*', spaces=True), + dma_noshare=get_config('DMA_NOSHARE', default='', spaces=True)) if not args.bootloader: write_PWM_config(f) @@ -1579,6 +1780,16 @@ def write_hwdef_header(outfilename): # there were no pin definitions, use 0 f.write("0") f.write(")\n\n") + write_alt_config(f) + + if not mcu_series.startswith("STM32F1"): + dma_required = ['SPI*', 'ADC*'] + if 'IOMCU_UART' in config: + dma_required.append(config['IOMCU_UART'][0] + '*') + for d in dma_unassigned: + for r in dma_required: + if fnmatch.fnmatch(d, r): + error("Missing required DMA for %s" % d) def build_peripheral_list(): @@ -1586,7 +1797,11 @@ def build_peripheral_list(): peripherals = [] done = set() prefixes = ['SPI', 'USART', 'UART', 'I2C'] - for p in allpins: + periph_pins = allpins[:] + for alt in altmap.keys(): + for p in altmap[alt].keys(): + periph_pins.append(altmap[alt][p]) + for p in periph_pins: type = p.type if type in done: continue @@ -1594,13 +1809,17 @@ def build_peripheral_list(): if type.startswith(prefix): ptx = type + "_TX" prx = type + "_RX" - peripherals.append(ptx) - peripherals.append(prx) - if not ptx in bylabel: - bylabel[ptx] = p - if not prx in bylabel: - bylabel[prx] = p - + if prefix in ['SPI', 'I2C']: + # in DMA map I2C and SPI has RX and TX suffix + if ptx not in bylabel: + bylabel[ptx] = p + if prx not in bylabel: + bylabel[prx] = p + if prx in bylabel or prx in altlabel: + peripherals.append(prx) + if ptx in bylabel or ptx in altlabel: + peripherals.append(ptx) + if type.startswith('ADC'): peripherals.append(type) if type.startswith('SDIO') or type.startswith('SDMMC'): @@ -1615,7 +1834,7 @@ def build_peripheral_list(): elif not p.has_extra('ALARM') and not p.has_extra('RCININT'): # get the TIMn_UP DMA channels for DShot label = type + '_UP' - if not label in peripherals and not p.has_extra('NODMA'): + if label not in peripherals and not p.has_extra('NODMA'): peripherals.append(label) done.add(type) return peripherals @@ -1642,10 +1861,12 @@ def write_env_py(filename): env_vars['CHIBIOS_BUILD_FLAGS'] = ' '.join(build_flags) pickle.dump(env_vars, open(filename, "wb")) + def romfs_add(romfs_filename, filename): '''add a file to ROMFS''' romfs[romfs_filename] = filename + def romfs_wildcard(pattern): '''add a set of files to ROMFS by wildcard''' base_path = os.path.join(os.path.dirname(__file__), '..', '..', '..', '..') @@ -1653,23 +1874,31 @@ def romfs_wildcard(pattern): for f in os.listdir(os.path.join(base_path, pattern_dir)): if fnmatch.fnmatch(f, pattern): romfs[f] = os.path.join(pattern_dir, f) - + +def romfs_add_dir(subdirs): + '''add a filesystem directory to ROMFS''' + for dirname in subdirs: + romfs_dir = os.path.join(os.path.dirname(args.hwdef), dirname) + if not args.bootloader and os.path.exists(romfs_dir): + for root, d, files in os.walk(romfs_dir): + for f in files: + if fnmatch.fnmatch(f, '*~'): + # skip editor backup files + continue + fullpath = os.path.join(root, f) + relpath = os.path.normpath(os.path.join(dirname, os.path.relpath(root, romfs_dir), f)) + romfs[relpath] = fullpath + def process_line(line): '''process one line of pin definition file''' global allpins, imu_list, compass_list, baro_list - a = shlex.split(line) + global mcu_type, mcu_series + all_lines.append(line) + a = shlex.split(line, posix=False) # keep all config lines for later use alllines.append(line) - if a[0].startswith('P') and a[0][1] in ports and a[0] in config: - error("Pin %s redefined" % a[0]) - - config[a[0]] = a[1:] - if a[0] == 'MCU': - global mcu_type, mcu_series - mcu_type = a[2] - mcu_series = a[1] - setup_mcu_type_defaults() + p = None if a[0].startswith('P') and a[0][1] in ports: # it is a port/pin definition try: @@ -1683,33 +1912,63 @@ def process_line(line): return p = generic_pin(port, pin, label, type, extra) - portmap[port][pin] = p - allpins.append(p) - if not type in bytype: - bytype[type] = [] - bytype[type].append(p) - bylabel[label] = p af = get_alt_function(mcu_type, a[0], label) if af is not None: p.af = af - if a[0] == 'SPIDEV': + + alt = p.extra_value("ALT", type=int, default=0) + if alt != 0: + if mcu_series.startswith("STM32F1"): + error("Alt config not allowed for F1 MCU") + if alt not in altmap: + altmap[alt] = {} + if p.portpin in altmap[alt]: + error("Pin %s ALT(%u) redefined" % (p.portpin, alt)) + altmap[alt][p.portpin] = p + # we need to add alt pins into bytype[] so they are enabled in chibios config + if type not in alttype: + alttype[type] = [] + alttype[type].append(p) + altlabel[label] = p + return + + if a[0] in config: + error("Pin %s redefined" % a[0]) + + if p is None and line.find('ALT(') != -1: + error("ALT() invalid for %s" % a[0]) + + config[a[0]] = a[1:] + if p is not None: + # add to set of pins for primary config + portmap[port][pin] = p + allpins.append(p) + if type not in bytype: + bytype[type] = [] + bytype[type].append(p) + bylabel[label] = p + elif a[0] == 'MCU': + mcu_type = a[2] + mcu_series = a[1] + setup_mcu_type_defaults() + elif a[0] == 'SPIDEV': spidev.append(a[1:]) - if a[0] == 'IMU': + elif a[0] == 'IMU': imu_list.append(a[1:]) - if a[0] == 'COMPASS': + elif a[0] == 'COMPASS': compass_list.append(a[1:]) - if a[0] == 'BARO': + elif a[0] == 'BARO': baro_list.append(a[1:]) - if a[0] == 'ROMFS': - romfs_add(a[1],a[2]) - if a[0] == 'ROMFS_WILDCARD': + elif a[0] == 'ROMFS': + romfs_add(a[1], a[2]) + elif a[0] == 'ROMFS_WILDCARD': romfs_wildcard(a[1]) - if a[0] == 'undef': + elif a[0] == 'undef': print("Removing %s" % a[1]) config.pop(a[1], '') - bytype.pop(a[1],'') - bylabel.pop(a[1],'') - #also remove all occurences of defines in previous lines if any + bytype.pop(a[1], '') + bylabel.pop(a[1], '') + # also remove all occurences of defines in previous lines if any for line in alllines[:]: if line.startswith('define') and a[1] == line.split()[1]: alllines.remove(line) @@ -1729,7 +1988,7 @@ def process_line(line): compass_list = [] if a[1] == 'BARO': baro_list = [] - if a[0] == 'env': + elif a[0] == 'env': print("Adding environment %s" % ' '.join(a[1:])) if len(a[1:]) < 2: error("Bad env line for %s" % a[0]) @@ -1766,7 +2025,7 @@ outdir = args.outdir if outdir is None: outdir = '/tmp' -if not "MCU" in config: +if "MCU" not in config: error("Missing MCU type in config") mcu_type = get_config('MCU', 1) @@ -1775,12 +2034,17 @@ print("Setup for MCU %s" % mcu_type) # build a list for peripherals for DMA resolver periph_list = build_peripheral_list() +# write out hw.dat for ROMFS +write_all_lines(os.path.join(outdir, "hw.dat")) + # write out hwdef.h write_hwdef_header(os.path.join(outdir, "hwdef.h")) # write out ldscript.ld write_ldscript(os.path.join(outdir, "ldscript.ld")) +romfs_add_dir(['scripts']) + write_ROMFS(outdir) # copy the shared linker script into the build directory; it must diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/convert_uart_order.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/convert_uart_order.py new file mode 100755 index 0000000000..d502d91f61 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/convert_uart_order.py @@ -0,0 +1,37 @@ +#!/usr/bin/env python +''' +convert UART_ORDER in a hwdef.dat into a SERIAL_ORDER +''' + +import sys, shlex + +def convert_file(fname): + lines = open(fname, 'r').readlines() + for i in range(len(lines)): + if lines[i].startswith('SERIAL_ORDER'): + print("Already has SERIAL_ORDER: %s" % fname) + return + + for i in range(len(lines)): + line = lines[i] + if not line.startswith('UART_ORDER'): + continue + a = shlex.split(line, posix=False) + if a[0] != 'UART_ORDER': + continue + uart_order = a[1:] + if not fname.endswith('-bl.dat'): + while len(uart_order) < 4: + uart_order += ['EMPTY'] + a += ['EMPTY'] + map = [ 0, 2, 3, 1, 4, 5, 6, 7, 8, 9, 10, 11, 12 ] + for j in range(len(uart_order)): + a[j+1] = uart_order[map[j]] + a[0] = 'SERIAL_ORDER' + print("%s new order " % fname, a) + lines[i] = ' '.join(a) + '\n' + open(fname, 'w').write(''.join(lines)) + +files=sys.argv[1:] +for fname in files: + convert_file(fname) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/dma_resolver.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/dma_resolver.py index e87c2a8df3..733e940542 100755 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/dma_resolver.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/dma_resolver.py @@ -204,7 +204,11 @@ def generate_DMAMUX_map(peripheral_list, noshare_list, dma_exclude): else: dmamux1_peripherals.append(p) map1 = generate_DMAMUX_map_mask(dmamux1_peripherals, 0xFFFF, noshare_list, dma_exclude) - map2 = generate_DMAMUX_map_mask(dmamux2_peripherals, 0xFF, noshare_list, dma_exclude) + # there are 8 BDMA channels, but an issue has been found where if I2C4 and SPI6 + # use neighboring channels then we sometimes lose a BDMA completion interrupt. To + # avoid this we set the BDMA available mask to 0x33, which forces the channels not to be + # adjacent. This issue was found on a CUAV-X7, with H743 RevV. + map2 = generate_DMAMUX_map_mask(dmamux2_peripherals, 0x33, noshare_list, dma_exclude) # translate entries from map2 to "DMA controller 3", which is used for BDMA for p in map2.keys(): streams = [] @@ -236,7 +240,7 @@ def write_dma_header(f, peripheral_list, mcu_type, dma_exclude=[], if hasattr(lib, "DMA_Map"): dma_map = lib.DMA_Map else: - return + return [] except ImportError: print("Unable to find module for MCU %s" % mcu_type) sys.exit(1) @@ -386,6 +390,7 @@ def write_dma_header(f, peripheral_list, mcu_type, dma_exclude=[], continue f.write('#define STM32_SPI_%s_DMA_STREAMS STM32_SPI_%s_TX_%s_STREAM, STM32_SPI_%s_RX_%s_STREAM\n' % ( key, key, dma_name(key), key, dma_name(key))) + return unassigned if __name__ == '__main__': diff --git a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-f412-rev1/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-f412-rev1/hwdef.dat index d711d426d5..578c1aee4f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-f412-rev1/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-f412-rev1/hwdef.dat @@ -9,6 +9,7 @@ APJ_BOARD_ID 9 # crystal frequency OSCILLATOR_HZ 24000000 +define HAL_CUSTOM_CLOCK_TREE STM32_HSE_ENABLED FALSE STM32_PLLM_VALUE 16 STM32_PLLN_VALUE 384 @@ -20,8 +21,6 @@ STM32_PREE2 STM32_PREE2_DIV1 STM32_PWM_USE_TIM3 TRUE -# board voltage -STM32_VDD 330U # flash size FLASH_SIZE_KB 1024 @@ -34,7 +33,7 @@ STDOUT_BAUDRATE 115200 I2C_ORDER I2C2 I2C1 # order of UARTs -UART_ORDER USART2 USART6 USART3 +SERIAL_ORDER USART2 USART3 EMPTY USART6 PC0 MGND ADC1 PC1 PWM4_SENSE ADC1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-journey/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-journey/hwdef.dat index c1e96048f1..9e6452b1d8 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-journey/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-journey/hwdef.dat @@ -9,6 +9,7 @@ APJ_BOARD_ID 9 # crystal frequency OSCILLATOR_HZ 24000000 +define HAL_CUSTOM_CLOCK_TREE STM32_HSE_ENABLED FALSE STM32_PLLM_VALUE 16 STM32_PLLN_VALUE 384 @@ -20,8 +21,6 @@ STM32_PREE2 STM32_PREE2_DIV1 STM32_PWM_USE_TIM3 TRUE -# board voltage -STM32_VDD 330U # flash size FLASH_SIZE_KB 1024 @@ -40,7 +39,7 @@ define HAL_I2C_MAX_CLOCK 400000 define APM_I2C_PRIORITY 181 # order of UARTs -UART_ORDER USART1 USART6 USART2 +SERIAL_ORDER USART1 USART2 EMPTY USART6 PC0 MGND ADC1 PC1 PWM4_SENSE ADC1 @@ -130,7 +129,10 @@ define HAL_BARO_20789_I2C_ADDR_ICM 0x68 # unstick 20789 on I2C on boot define HAL_I2C_CLEAR_BUS -env DEFINES CONFIG_HAL_BOARD_SUBTYPE='HAL_BOARD_SUBTYPE_CHIBIOS_SKYVIPER_F412' +define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_CHIBIOS_SKYVIPER_F412 # the web UI uses an abin file for firmware uploads env BUILD_ABIN True + +# need more space for default parameters +define AP_PARAM_MAX_EMBEDDED_PARAM 8192 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/hwdef.dat index 4fd09727f2..d6ae555f30 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/hwdef.dat @@ -27,7 +27,7 @@ undef SDIO undef HAL_BOARD_LOG_DIRECTORY undef HAL_BOARD_TERRAIN_DIRECTORY -UART_ORDER OTG1 UART4 USART2 +SERIAL_ORDER OTG1 USART2 EMPTY UART4 # enable AP_Radio support define HAL_RCINPUT_WITH_AP_RADIO 1 @@ -52,11 +52,14 @@ SPIDEV pixartflow SPI4 DEVID13 MPU_EXT_CS MODE3 2*MHZ 2*MHZ # SPI2 for the cypress needs exclusive access or we will end up with # lost packets -DMA_PRIORITY SPI2_* +DMA_PRIORITY SPI2_* SPI* ADC* DMA_NOSHARE SPI2_* undef PA1 PA1 UART4_RX UART4 NODMA +# use flash storage +define STORAGE_FLASH_PAGE 22 + env DEFAULT_PARAMETERS 'Tools/Frame_params/SkyViper-2450GPS/defaults.parm' # the web UI uses an abin file for firmware uploads diff --git a/libraries/AP_HAL_ChibiOS/hwdef/sparky2/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/sparky2/hwdef-bl.dat index 1b624d2091..d6dad2cdea 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/sparky2/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/sparky2/hwdef-bl.dat @@ -9,7 +9,6 @@ APJ_BOARD_ID 130 # crystal frequency OSCILLATOR_HZ 8000000 -STM32_PLLM_VALUE 8 FLASH_SIZE_KB 1024 @@ -27,11 +26,9 @@ define HAL_LED_ON 0 # the location where the bootloader will put the firmware FLASH_BOOTLOADER_LOAD_KB 64 -# board voltage -STM32_VDD 330U # order of UARTs -UART_ORDER OTG1 +SERIAL_ORDER OTG1 PA11 OTG_FS_DM OTG1 PA12 OTG_FS_DP OTG1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/sparky2/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/sparky2/hwdef.dat index f934a9de78..f2a803fcf6 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/sparky2/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/sparky2/hwdef.dat @@ -9,14 +9,11 @@ APJ_BOARD_ID 130 # crystal frequency OSCILLATOR_HZ 8000000 -STM32_PLLM_VALUE 8 define STM32_ST_USE_TIMER 5 FLASH_SIZE_KB 1024 -# board voltage -STM32_VDD 330U # use USB for stdout, so no STDOUT_SERIAL # STDOUT_SERIAL SD1 @@ -48,7 +45,7 @@ PA8 VBUS INPUT OPENDRAIN # ---------UARTS----------- # order of UARTs (and USB) -UART_ORDER OTG1 USART1 USART3 +SERIAL_ORDER OTG1 USART3 EMPTY USART1 # Main PORT PA9 USART1_TX USART1 @@ -137,8 +134,6 @@ SPIDEV dataflash SPI3 DEVID1 FLASH_CS MODE3 32*MHZ 32*MHZ # enable logging to dataflash define HAL_LOGGING_DATAFLASH -define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_CHIBIOS_SPARKY2 - define STM32_PWM_USE_ADVANCED TRUE define BOARD_PWM_COUNT_DEFAULT 7 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4/hwdef-bl.dat index d73fbeaf74..59ecaf6ec0 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4/hwdef-bl.dat @@ -9,7 +9,6 @@ APJ_BOARD_ID 134 # crystal frequency OSCILLATOR_HZ 8000000 -STM32_PLLM_VALUE 8 FLASH_SIZE_KB 1024 @@ -26,11 +25,9 @@ define HAL_LED_ON 0 # the location where the bootloader will put the firmware FLASH_BOOTLOADER_LOAD_KB 64 -# board voltage -STM32_VDD 330U # order of UARTs -UART_ORDER OTG1 +SERIAL_ORDER OTG1 PA11 OTG_FS_DM OTG1 PA12 OTG_FS_DP OTG1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4/hwdef.dat index 9107cbfed1..c2e0e64ab9 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4/hwdef.dat @@ -10,21 +10,18 @@ APJ_BOARD_ID 134 # crystal frequency OSCILLATOR_HZ 8000000 -STM32_PLLM_VALUE 8 define STM32_ST_USE_TIMER 5 #define CH_CFG_ST_RESOLUTION 16 FLASH_SIZE_KB 1024 -# board voltage -STM32_VDD 330U # only one I2C bus I2C_ORDER I2C1 # order of UARTs (and USB) -UART_ORDER OTG1 USART3 USART1 UART4 UART5 +SERIAL_ORDER OTG1 USART1 UART4 USART3 UART5 # LEDs PB9 LED_BLUE OUTPUT LOW GPIO(0) @@ -149,14 +146,7 @@ define HAL_LOGGING_DATAFLASH # 8 PWM available by default define BOARD_PWM_COUNT_DEFAULT 8 -# uncomment the lines below to enable strict API -# checking in ChibiOS -#define CH_DBG_ENABLE_ASSERTS TRUE -#define CH_DBG_ENABLE_CHECKS TRUE -#define CH_DBG_SYSTEM_STATE_CHECK TRUE -#define CH_DBG_ENABLE_STACK_CHECK TRUE - # setup for OSD -define OSD_ENABLED ENABLED +define OSD_ENABLED 1 define HAL_OSD_TYPE_DEFAULT 1 ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin diff --git a/libraries/AP_HAL_ChibiOS/stdio.cpp b/libraries/AP_HAL_ChibiOS/stdio.cpp index 959004a77d..0f9fc8aa8b 100644 --- a/libraries/AP_HAL_ChibiOS/stdio.cpp +++ b/libraries/AP_HAL_ChibiOS/stdio.cpp @@ -29,6 +29,10 @@ #include #include "hwdef/common/stdio.h" #include +#if HAL_USE_SERIAL_USB == TRUE +#include +#include "UARTDriver.h" +#endif extern const AP_HAL::HAL& hal; @@ -80,7 +84,10 @@ int __wrap_asprintf(char **strp, const char *fmt, ...) int __wrap_vprintf(const char *fmt, va_list arg) { #ifdef HAL_STDOUT_SERIAL - return chvprintf ((BaseSequentialStream*)&HAL_STDOUT_SERIAL, fmt, arg); + return chvprintf((BaseSequentialStream*)&HAL_STDOUT_SERIAL, fmt, arg); +#elif HAL_USE_SERIAL_USB == TRUE + usb_initialise(); + return chvprintf((BaseSequentialStream*)&SDU1, fmt, arg); #else (void)arg; return strlen(fmt); diff --git a/libraries/AP_HAL_ChibiOS/system.cpp b/libraries/AP_HAL_ChibiOS/system.cpp index 51fa98d9f5..159b9916af 100644 --- a/libraries/AP_HAL_ChibiOS/system.cpp +++ b/libraries/AP_HAL_ChibiOS/system.cpp @@ -20,6 +20,7 @@ #include #include #include "hwdef/common/watchdog.h" +#include "hwdef/common/stm32_util.h" #include #include "hal.h" @@ -31,6 +32,16 @@ static_assert(sizeof(systime_t) == 2, "expected 16 bit systime_t"); static_assert(sizeof(systime_t) == 4, "expected 32 bit systime_t"); #endif +#if defined(HAL_EXPECTED_SYSCLOCK) +#ifdef STM32_SYS_CK +static_assert(HAL_EXPECTED_SYSCLOCK == STM32_SYS_CK, "unexpected STM32_SYS_CK value"); +#elif defined(STM32_HCLK) +static_assert(HAL_EXPECTED_SYSCLOCK == STM32_HCLK, "unexpected STM32_HCLK value"); +#else +#error "unknown system clock" +#endif +#endif + extern const AP_HAL::HAL& hal; extern "C" { @@ -55,17 +66,28 @@ void NMI_Handler(void) { while (1); } /* save watchdog data for a hard fault */ -static void save_fault_watchdog(uint16_t line, FaultType fault_type, uint32_t fault_addr) +static void save_fault_watchdog(uint16_t line, FaultType fault_type, uint32_t fault_addr, uint32_t lr) { #ifndef HAL_BOOTLOADER_BUILD bool using_watchdog = AP_BoardConfig::watchdog_enabled(); if (using_watchdog) { AP_HAL::Util::PersistentData &pd = hal.util->persistent_data; pd.fault_line = line; - pd.fault_type = fault_type; + if (pd.fault_type == 0) { + // don't overwrite earlier fault + pd.fault_type = fault_type; + } pd.fault_addr = fault_addr; - pd.fault_thd_prio = chThdGetPriorityX(); + thread_t *tp = chThdGetSelfX(); + if (tp) { + pd.fault_thd_prio = tp->prio; + // get first 4 bytes of the name, but only of first fault + if (tp->name && pd.thread_name4[0] == 0) { + strncpy(pd.thread_name4, tp->name, 4); + } + } pd.fault_icsr = SCB->ICSR; + pd.fault_lr = lr; stm32_watchdog_save((uint32_t *)&hal.util->persistent_data, (sizeof(hal.util->persistent_data)+3)/4); } #endif @@ -97,8 +119,27 @@ void HardFault_Handler(void) { (void)isFaultOnStacking; (void)isFaultAddressValid; - save_fault_watchdog(__LINE__, faultType, faultAddress); + save_fault_watchdog(__LINE__, faultType, faultAddress, (uint32_t)ctx.lr_thd); +#ifdef HAL_GPIO_PIN_FAULT + while (true) { + fault_printf("HARDFAULT\n"); + fault_printf("CUR=0x%08x\n", ch.rlist.current); + if (ch.rlist.current) { + fault_printf("NAME=%s\n", ch.rlist.current->name); + } + fault_printf("FA=0x%08x\n", faultAddress); + fault_printf("PC=0x%08x\n", ctx.pc); + fault_printf("LR=0x%08x\n", ctx.lr_thd); + fault_printf("R0=0x%08x\n", ctx.r0); + fault_printf("R1=0x%08x\n", ctx.r1); + fault_printf("R2=0x%08x\n", ctx.r2); + fault_printf("R3=0x%08x\n", ctx.r3); + fault_printf("R12=0x%08x\n", ctx.r12); + fault_printf("XPSR=0x%08x\n", ctx.xpsr); + fault_printf("\n\n"); + } +#endif //Cause debugger to stop. Ignored if no debugger is attached while(1) {} } @@ -131,7 +172,7 @@ void UsageFault_Handler(void) { (void)isUnalignedAccessFault; (void)isDivideByZeroFault; - save_fault_watchdog(__LINE__, faultType, faultAddress); + save_fault_watchdog(__LINE__, faultType, faultAddress, (uint32_t)ctx.lr_thd); //Cause debugger to stop. Ignored if no debugger is attached while(1) {} @@ -163,7 +204,7 @@ void MemManage_Handler(void) { (void)isExceptionStackingFault; (void)isFaultAddressValid; - save_fault_watchdog(__LINE__, faultType, faultAddress); + save_fault_watchdog(__LINE__, faultType, faultAddress, (uint32_t)ctx.lr_thd); while(1) {} } @@ -183,7 +224,10 @@ void panic(const char *errormsg, ...) va_end(ap); hal.scheduler->delay_microseconds(10000); - while(1) {} + while (1) { + vprintf(errormsg, ap); + hal.scheduler->delay(500); + } } uint32_t micros()