INS: add calibrated check

Checks is the scaling vector has been updated.  Required for pre-arm
checks for ArduCopter
This commit is contained in:
Randy Mackay 2013-04-22 23:55:53 +09:00
parent 07b6efafd8
commit 42bca90676
2 changed files with 13 additions and 0 deletions

View File

@ -403,6 +403,13 @@ bool AP_InertialSensor::calibrate_accel(void (*flash_leds_cb)(bool on),
return false;
}
/// calibrated - returns true if the accelerometers have been calibrated
/// @note this should not be called while flying because it reads from the eeprom which can be slow
bool AP_InertialSensor::calibrated()
{
return _accel_offset.load();
}
// _calibrate_model - perform low level accel calibration
// accel_sample are accelerometer samples collected in 6 different positions
// accel_offsets are output from the calibration routine

View File

@ -68,6 +68,12 @@ public:
float& trim_pitch);
#endif
/// calibrated - returns true if the accelerometers have been calibrated
///
/// @note this should not be called while flying because it reads from the eeprom which can be slow
///
bool calibrated();
/// Perform cold-start initialisation for just the gyros.
///
/// @note This should not be called unless ::init has previously