mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_IOMCU: fixed check for BLHeli support
This commit is contained in:
parent
fdf2599329
commit
5fb71e945c
@ -19,6 +19,7 @@
|
|||||||
#include <AP_InternalError/AP_InternalError.h>
|
#include <AP_InternalError/AP_InternalError.h>
|
||||||
#include <AP_Logger/AP_Logger.h>
|
#include <AP_Logger/AP_Logger.h>
|
||||||
#include <AP_Arming/AP_Arming.h>
|
#include <AP_Arming/AP_Arming.h>
|
||||||
|
#include <AP_BLHeli/AP_BLHeli.h>
|
||||||
#include <ch.h>
|
#include <ch.h>
|
||||||
|
|
||||||
extern const AP_HAL::HAL &hal;
|
extern const AP_HAL::HAL &hal;
|
||||||
@ -117,7 +118,7 @@ void AP_IOMCU::thread_main(void)
|
|||||||
uart.begin(1500*1000, 128, 128);
|
uart.begin(1500*1000, 128, 128);
|
||||||
uart.set_unbuffered_writes(true);
|
uart.set_unbuffered_writes(true);
|
||||||
|
|
||||||
#if HAL_WITH_IO_MCU_BIDIR_DSHOT
|
#if HAVE_AP_BLHELI_SUPPORT && HAL_WITH_IO_MCU_BIDIR_DSHOT
|
||||||
AP_BLHeli* blh = AP_BLHeli::get_singleton();
|
AP_BLHeli* blh = AP_BLHeli::get_singleton();
|
||||||
uint16_t erpm_period_ms = 10; // default 100Hz
|
uint16_t erpm_period_ms = 10; // default 100Hz
|
||||||
if (blh && blh->get_telemetry_rate() > 0) {
|
if (blh && blh->get_telemetry_rate() > 0) {
|
||||||
@ -318,7 +319,7 @@ void AP_IOMCU::thread_main(void)
|
|||||||
read_servo();
|
read_servo();
|
||||||
last_servo_read_ms = AP_HAL::millis();
|
last_servo_read_ms = AP_HAL::millis();
|
||||||
}
|
}
|
||||||
#if HAL_WITH_IO_MCU_BIDIR_DSHOT
|
#if HAVE_AP_BLHELI_SUPPORT && HAL_WITH_IO_MCU_BIDIR_DSHOT
|
||||||
if (AP_BoardConfig::io_dshot() && now - last_erpm_read_ms > erpm_period_ms) {
|
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
|
// 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
|
// send erpm info back with the response from a PWM send, but that would
|
||||||
@ -398,7 +399,7 @@ void AP_IOMCU::read_rc_input()
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#if HAL_WITH_IO_MCU_BIDIR_DSHOT
|
#if HAVE_AP_BLHELI_SUPPORT && HAL_WITH_IO_MCU_BIDIR_DSHOT
|
||||||
/*
|
/*
|
||||||
read dshot erpm
|
read dshot erpm
|
||||||
*/
|
*/
|
||||||
|
Loading…
Reference in New Issue
Block a user