AP_BLHeli: fix compilation when HAL_WITH_ESC_TELEM == 0

This commit is contained in:
Dr.-Ing. Amilcar do Carmo Lucas 2021-04-16 20:11:17 +02:00 committed by Peter Barker
parent 13a97eecd4
commit 120081f7ab
2 changed files with 2 additions and 3 deletions

View File

@ -1409,6 +1409,7 @@ void AP_BLHeli::init(void)
*/
void AP_BLHeli::read_telemetry_packet(void)
{
#if HAL_WITH_ESC_TELEM
uint8_t buf[telem_packet_size];
if (telem_uart->read(buf, telem_packet_size) < telem_packet_size) {
// short read, we should have 10 bytes ready when this function is called
@ -1462,6 +1463,7 @@ void AP_BLHeli::read_telemetry_packet(void)
t.consumption_mah,
trpm, hal.rcout->get_erpm_error_rate(motor_idx), (unsigned)AP_HAL::millis());
}
#endif // HAL_WITH_ESC_TELEM
}
/*

View File

@ -27,9 +27,6 @@
#if HAL_SUPPORT_RCOUT_SERIAL
#define HAVE_AP_BLHELI_SUPPORT
#ifndef HAL_WITH_ESC_TELEM
#define HAL_WITH_ESC_TELEM TRUE
#endif
#include <AP_ESC_Telem/AP_ESC_Telem_Backend.h>