5
0
mirror of https://github.com/ArduPilot/ardupilot synced 2025-01-05 23:48:31 -04:00

AP_Vehicle: correct compilation with HAL_INS_ACCELCAL_ENABLED false

This commit is contained in:
Peter Barker 2022-03-18 18:02:30 +11:00 committed by Andrew Tridgell
parent 38a1c4412a
commit fe863b9567
2 changed files with 7 additions and 2 deletions
libraries/AP_Vehicle

View File

@ -302,7 +302,9 @@ const AP_Scheduler::Task AP_Vehicle::scheduler_tasks[] = {
#if OSD_ENABLED
SCHED_TASK(publish_osd_info, 1, 10, 240),
#endif
#if HAL_INS_ACCELCAL_ENABLED
SCHED_TASK(accel_cal_update, 10, 100, 245),
#endif
#if HAL_EFI_ENABLED
SCHED_TASK_CLASS(AP_EFI, &vehicle.efi, update, 10, 200, 250),
#endif
@ -482,6 +484,8 @@ void AP_Vehicle::get_osd_roll_pitch_rad(float &roll, float &pitch) const
#endif
#if HAL_INS_ACCELCAL_ENABLED
#ifndef HAL_CAL_ALWAYS_REBOOT
// allow for forced reboot after accelcal
#define HAL_CAL_ALWAYS_REBOOT 0
@ -492,7 +496,6 @@ void AP_Vehicle::get_osd_roll_pitch_rad(float &roll, float &pitch) const
*/
void AP_Vehicle::accel_cal_update()
{
#if HAL_INS_ENABLED
if (hal.util->get_soft_armed()) {
return;
}
@ -510,8 +513,8 @@ void AP_Vehicle::accel_cal_update()
hal.scheduler->reboot(false);
}
#endif
#endif // HAL_INS_ENABLED
}
#endif // HAL_INS_ACCELCAL_ENABLED
AP_Vehicle *AP_Vehicle::_singleton = nullptr;

View File

@ -386,8 +386,10 @@ protected:
void publish_osd_info();
#endif
#if HAL_INS_ACCELCAL_ENABLED
// update accel calibration
void accel_cal_update();
#endif
ModeReason control_mode_reason = ModeReason::UNKNOWN;