mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
INS: add calibrated check
Checks is the scaling vector has been updated. Required for pre-arm checks for ArduCopter
This commit is contained in:
parent
07b6efafd8
commit
42bca90676
@ -403,6 +403,13 @@ bool AP_InertialSensor::calibrate_accel(void (*flash_leds_cb)(bool on),
|
|||||||
return false;
|
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
|
// _calibrate_model - perform low level accel calibration
|
||||||
// accel_sample are accelerometer samples collected in 6 different positions
|
// accel_sample are accelerometer samples collected in 6 different positions
|
||||||
// accel_offsets are output from the calibration routine
|
// accel_offsets are output from the calibration routine
|
||||||
|
@ -68,6 +68,12 @@ public:
|
|||||||
float& trim_pitch);
|
float& trim_pitch);
|
||||||
#endif
|
#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.
|
/// Perform cold-start initialisation for just the gyros.
|
||||||
///
|
///
|
||||||
/// @note This should not be called unless ::init has previously
|
/// @note This should not be called unless ::init has previously
|
||||||
|
Loading…
Reference in New Issue
Block a user