From d6e98a054f356d2df10af7be45096b33ec20812d Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 15 Jun 2022 12:24:26 +0900 Subject: [PATCH] Copter: get_rangefinder_height_interpolated_cm made const --- ArduCopter/Copter.h | 6 ++---- ArduCopter/sensors.cpp | 2 +- 2 files changed, 3 insertions(+), 5 deletions(-) diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index c39e378951..362b1a4558 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -256,10 +256,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;