AP_InertialSensor: add accel_cal_requires_reboot

This commit is contained in:
Jonathan Challinger 2015-12-28 20:32:06 -08:00
parent f6a41a8936
commit 137ace473d
2 changed files with 8 additions and 1 deletions

View File

@ -332,7 +332,8 @@ AP_InertialSensor::AP_InertialSensor() :
_calibrating(false),
_log_raw_data(false),
_backends_detected(false),
_dataflash(NULL)
_dataflash(NULL),
_accel_cal_requires_reboot(false)
{
if (_s_instance) {
AP_HAL::panic("Too many inertial sensors");
@ -1318,6 +1319,8 @@ void AP_InertialSensor::_acal_save_calibrations()
hal.console->print("ERR: Trim over maximum of 10 degrees!!");
_new_trim = false; //we have either got faulty level during acal or highly misaligned accelerometers
}
_accel_cal_requires_reboot = true;
}
void AP_InertialSensor::_acal_event_failure()

View File

@ -241,6 +241,8 @@ public:
// update accel calibrator
void acal_update();
bool accel_cal_requires_reboot() const { return _accel_cal_requires_reboot; }
private:
// load backend drivers
@ -405,6 +407,8 @@ private:
float _trim_pitch;
float _trim_roll;
bool _new_trim;
bool _accel_cal_requires_reboot;
};
#include "AP_InertialSensor_Backend.h"