From 2f78872785a04c25ce25cc92e7e2b5f9bef7246c Mon Sep 17 00:00:00 2001 From: MattKear Date: Wed, 16 Oct 2024 18:30:32 +0100 Subject: [PATCH] Copter: minor change to ger_rangefinder_height_interpolated --- ArduCopter/Copter.h | 2 +- ArduCopter/sensors.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 9915885060..40fb3a3201 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -256,7 +256,7 @@ private: 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 f83a1c25e3..c9b2be5741 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);