mirror of https://github.com/ArduPilot/ardupilot
AP_InertialSensor: skip gyro cal on watchdog reset
This commit is contained in:
parent
ad2ff5a207
commit
3f0af2ce29
|
@ -1986,6 +1986,17 @@ MAV_RESULT AP_InertialSensor::simple_accel_cal()
|
|||
return result;
|
||||
}
|
||||
|
||||
/*
|
||||
see if gyro calibration should be performed
|
||||
*/
|
||||
AP_InertialSensor::Gyro_Calibration_Timing AP_InertialSensor::gyro_calibration_timing()
|
||||
{
|
||||
if (hal.util->was_watchdog_reset()) {
|
||||
return GYRO_CAL_NEVER;
|
||||
}
|
||||
return (Gyro_Calibration_Timing)_gyro_cal_timing.get();
|
||||
}
|
||||
|
||||
|
||||
namespace AP {
|
||||
|
||||
|
|
|
@ -135,7 +135,7 @@ public:
|
|||
bool gyro_calibrated_ok(uint8_t instance) const { return _gyro_cal_ok[instance]; }
|
||||
bool gyro_calibrated_ok_all() const;
|
||||
bool use_gyro(uint8_t instance) const;
|
||||
Gyro_Calibration_Timing gyro_calibration_timing() { return (Gyro_Calibration_Timing)_gyro_cal_timing.get(); }
|
||||
Gyro_Calibration_Timing gyro_calibration_timing();
|
||||
|
||||
bool get_accel_health(uint8_t instance) const { return (instance<_accel_count) ? _accel_healthy[instance] : false; }
|
||||
bool get_accel_health(void) const { return get_accel_health(_primary_accel); }
|
||||
|
|
Loading…
Reference in New Issue