mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
AP_Vehicle: correct compilation when AHRS not available
CubeOrange-periph-heavy was broken
This commit is contained in:
parent
04b46678a4
commit
84913569cd
@ -957,11 +957,14 @@ void AP_Vehicle::accel_cal_update()
|
||||
return;
|
||||
}
|
||||
ins.acal_update();
|
||||
|
||||
#if AP_AHRS_ENABLED
|
||||
// check if new trim values, and set them
|
||||
Vector3f trim_rad;
|
||||
if (ins.get_new_trim(trim_rad)) {
|
||||
ahrs.set_trim(trim_rad);
|
||||
}
|
||||
#endif
|
||||
|
||||
#if HAL_CAL_ALWAYS_REBOOT
|
||||
if (ins.accel_cal_requires_reboot() &&
|
||||
|
Loading…
Reference in New Issue
Block a user