AP_ToshibaCAN: fix compilation when HAL_WITH_ESC_TELEM == 0

This commit is contained in:
Dr.-Ing. Amilcar do Carmo Lucas 2021-04-16 20:11:22 +02:00 committed by Peter Barker
parent d15042d7c0
commit 9d2790049f
1 changed files with 2 additions and 0 deletions

View File

@ -300,6 +300,7 @@ void AP_ToshibaCAN::loop()
if (send_stage == 8) {
AP_HAL::CANFrame recv_frame;
while (read_frame(recv_frame, timeout)) {
#if HAL_WITH_ESC_TELEM
// decode rpm and voltage data
if ((recv_frame.id >= MOTOR_DATA1) && (recv_frame.id <= MOTOR_DATA1 + TOSHIBACAN_MAX_NUM_ESCS)) {
// copy contents to our structure
@ -379,6 +380,7 @@ void AP_ToshibaCAN::loop()
update_telem_data(esc_id, t, AP_ESC_Telem_Backend::TelemetryType::USAGE);
}
}
#endif // HAL_WITH_ESC_TELEM
}
// update bitmask of escs that replied