From 92ef809e3b357c626d8e7fde8990d0279f1b3c71 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Thu, 16 Nov 2023 17:44:55 +0000 Subject: [PATCH] AP_IOMCU: allow bdshot iomcu on non-bdshot fmu --- libraries/AP_IOMCU/AP_IOMCU.cpp | 9 ++++++--- libraries/AP_IOMCU/AP_IOMCU.h | 3 ++- 2 files changed, 8 insertions(+), 4 deletions(-) diff --git a/libraries/AP_IOMCU/AP_IOMCU.cpp b/libraries/AP_IOMCU/AP_IOMCU.cpp index b996aefbe4..6be77ef637 100644 --- a/libraries/AP_IOMCU/AP_IOMCU.cpp +++ b/libraries/AP_IOMCU/AP_IOMCU.cpp @@ -117,12 +117,13 @@ void AP_IOMCU::thread_main(void) uart.begin(1500*1000, 128, 128); uart.set_unbuffered_writes(true); +#if HAL_WITH_IO_MCU_BIDIR_DSHOT AP_BLHeli* blh = AP_BLHeli::get_singleton(); uint16_t erpm_period_ms = 10; // default 100Hz if (blh && blh->get_telemetry_rate() > 0) { erpm_period_ms = constrain_int16(1000 / blh->get_telemetry_rate(), 1, 1000); } - +#endif trigger_event(IOEVENT_INIT); while (!do_shutdown) { @@ -317,7 +318,7 @@ void AP_IOMCU::thread_main(void) read_servo(); last_servo_read_ms = AP_HAL::millis(); } - +#if HAL_WITH_IO_MCU_BIDIR_DSHOT if (AP_BoardConfig::io_dshot() && now - last_erpm_read_ms > erpm_period_ms) { // read erpm at configured rate. A more efficient scheme might be to // send erpm info back with the response from a PWM send, but that would @@ -333,7 +334,7 @@ void AP_IOMCU::thread_main(void) read_telem(); last_telem_read_ms = AP_HAL::millis(); } - +#endif if (now - last_safety_option_check_ms > 1000) { update_safety_options(); last_safety_option_check_ms = now; @@ -397,6 +398,7 @@ void AP_IOMCU::read_rc_input() } } +#if HAL_WITH_IO_MCU_BIDIR_DSHOT /* read dshot erpm */ @@ -452,6 +454,7 @@ void AP_IOMCU::read_telem() } esc_group = (esc_group + 1) % (IOMCU_MAX_TELEM_CHANNELS / 4); } +#endif /* read status registers diff --git a/libraries/AP_IOMCU/AP_IOMCU.h b/libraries/AP_IOMCU/AP_IOMCU.h index 1c976d2d73..24d19c32c3 100644 --- a/libraries/AP_IOMCU/AP_IOMCU.h +++ b/libraries/AP_IOMCU/AP_IOMCU.h @@ -271,11 +271,12 @@ private: uint16_t rate; } dshot_rate; +#if HAL_WITH_IO_MCU_BIDIR_DSHOT // bi-directional dshot erpm values struct page_dshot_erpm dshot_erpm; struct page_dshot_telem dshot_telem[IOMCU_MAX_TELEM_CHANNELS/4]; uint8_t esc_group; - +#endif // queue of dshot commands that need sending ObjectBuffer dshot_command_queue{8};