AP_InertialSensor: make calibrated() const

This commit is contained in:
Andrew Tridgell 2015-02-01 13:31:37 +11:00
parent 68f64fa11c
commit 6e62e1ca7b
2 changed files with 2 additions and 2 deletions

View File

@ -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;
} }

View File

@ -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.
/// ///