mirror of https://github.com/ArduPilot/ardupilot
AP_InertialSensor: make calibrated() const
This commit is contained in:
parent
68f64fa11c
commit
6e62e1ca7b
|
@ -536,7 +536,7 @@ void AP_InertialSensor::check_3D_calibration()
|
||||||
/*
|
/*
|
||||||
return true if we have 3D calibration values
|
return true if we have 3D calibration values
|
||||||
*/
|
*/
|
||||||
bool AP_InertialSensor::calibrated()
|
bool AP_InertialSensor::calibrated() const
|
||||||
{
|
{
|
||||||
return _have_3D_calibration;
|
return _have_3D_calibration;
|
||||||
}
|
}
|
||||||
|
|
|
@ -95,7 +95,7 @@ public:
|
||||||
///
|
///
|
||||||
/// @note this should not be called while flying because it reads from the eeprom which can be slow
|
/// @note this should not be called while flying because it reads from the eeprom which can be slow
|
||||||
///
|
///
|
||||||
bool calibrated();
|
bool calibrated() const;
|
||||||
|
|
||||||
/// Perform cold-start initialisation for just the gyros.
|
/// Perform cold-start initialisation for just the gyros.
|
||||||
///
|
///
|
||||||
|
|
Loading…
Reference in New Issue