diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 9915885060a68..40fb3a320157e 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -256,7 +256,7 @@ class Copter : public AP_Vehicle { AP_SurfaceDistance rangefinder_up_state {ROTATION_PITCH_90, inertial_nav, 1U}; // helper function to get inertially interpolated rangefinder height. - bool get_rangefinder_height_interpolated_cm(int32_t& ret) const; + bool get_rangefinder_height_interpolated_cm(int32_t& ret); #if AP_RANGEFINDER_ENABLED class SurfaceTracking { diff --git a/ArduCopter/sensors.cpp b/ArduCopter/sensors.cpp index f83a1c25e3076..c9b2be574173f 100644 --- a/ArduCopter/sensors.cpp +++ b/ArduCopter/sensors.cpp @@ -68,7 +68,7 @@ void Copter::update_rangefinder_terrain_offset() } // helper function to get inertially interpolated rangefinder height. -bool Copter::get_rangefinder_height_interpolated_cm(int32_t& ret) const +bool Copter::get_rangefinder_height_interpolated_cm(int32_t& ret) { #if AP_RANGEFINDER_ENABLED return rangefinder_state.get_rangefinder_height_interpolated_cm(ret);