diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 62ba1c503d..6b8a3f786a 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -255,10 +255,8 @@ private: uint32_t glitch_cleared_ms; // system time glitch cleared } rangefinder_state, rangefinder_up_state; - /* - return rangefinder height interpolated using inertial altitude - */ - bool get_rangefinder_height_interpolated_cm(int32_t& ret); + // return rangefinder height interpolated using inertial altitude + bool get_rangefinder_height_interpolated_cm(int32_t& ret) const; class SurfaceTracking { public: diff --git a/ArduCopter/sensors.cpp b/ArduCopter/sensors.cpp index 54968f092f..afa8c7e333 100644 --- a/ArduCopter/sensors.cpp +++ b/ArduCopter/sensors.cpp @@ -135,7 +135,7 @@ bool Copter::rangefinder_up_ok() const difference between the inertial height at that time and the current inertial height to give us interpolation of height from rangefinder */ -bool Copter::get_rangefinder_height_interpolated_cm(int32_t& ret) +bool Copter::get_rangefinder_height_interpolated_cm(int32_t& ret) const { if (!rangefinder_alt_ok()) { return false;