mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
AP_InertialSensor: fixed build error
This commit is contained in:
parent
2e9f61fe49
commit
7cb7ad3636
@ -1303,7 +1303,7 @@ AP_InertialSensor::_init_gyro()
|
|||||||
float best_diff[INS_MAX_INSTANCES];
|
float best_diff[INS_MAX_INSTANCES];
|
||||||
bool converged[INS_MAX_INSTANCES];
|
bool converged[INS_MAX_INSTANCES];
|
||||||
#if HAL_INS_TEMPERATURE_CAL_ENABLE
|
#if HAL_INS_TEMPERATURE_CAL_ENABLE
|
||||||
float start_temperature[INS_MAX_INSTANCES];
|
float start_temperature[INS_MAX_INSTANCES] {};
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// exit immediately if calibration is already in progress
|
// exit immediately if calibration is already in progress
|
||||||
|
Loading…
Reference in New Issue
Block a user