diff --git a/libraries/AP_RangeFinder/AP_RangeFinder.cpp b/libraries/AP_RangeFinder/AP_RangeFinder.cpp index 7adc758f05..c487eb2eba 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder.cpp @@ -745,7 +745,7 @@ MAV_DISTANCE_SENSOR RangeFinder::get_mav_distance_sensor_type_orient(enum Rotati } // Write an RFND (rangefinder) packet -void RangeFinder::Log_RFND() +void RangeFinder::Log_RFND() const { if (_log_rfnd_bit == uint32_t(-1)) { return; diff --git a/libraries/AP_RangeFinder/AP_RangeFinder.h b/libraries/AP_RangeFinder/AP_RangeFinder.h index 4f8854f869..8f805e7786 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder.h @@ -212,7 +212,7 @@ private: bool _add_backend(AP_RangeFinder_Backend *driver, uint8_t instance); uint32_t _log_rfnd_bit = -1; - void Log_RFND(); + void Log_RFND() const; }; namespace AP { diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.cpp index 6d3b6e690f..ea3e28593b 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.cpp @@ -55,7 +55,7 @@ bool AP_RangeFinder_BLPing::get_reading(uint16_t &reading_cm) struct { float sum_cm = 0; uint16_t count = 0; - float mean() { return sum_cm / count; }; + float mean() const { return sum_cm / count; }; } averageStruct; // read any available lines from the lidar diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_VL53L1X.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_VL53L1X.cpp index 3ad272dcd8..17f43c0554 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_VL53L1X.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_VL53L1X.cpp @@ -402,7 +402,7 @@ uint32_t AP_RangeFinder_VL53L1X::timeoutMicrosecondsToMclks(uint32_t timeout_us, // Calculate macro period in microseconds (12.12 format) with given VCSEL period // assumes fast_osc_frequency has been read and stored // based on VL53L1_calc_macro_period_us() -uint32_t AP_RangeFinder_VL53L1X::calcMacroPeriod(uint8_t vcsel_period) +uint32_t AP_RangeFinder_VL53L1X::calcMacroPeriod(uint8_t vcsel_period) const { // from VL53L1_calc_pll_period_us() // fast osc frequency in 4.12 format; PLL period in 0.24 format diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_VL53L1X.h b/libraries/AP_RangeFinder/AP_RangeFinder_VL53L1X.h index 742d0b053f..5cd6efe58e 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_VL53L1X.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_VL53L1X.h @@ -1290,6 +1290,6 @@ private: uint16_t encodeTimeout(uint32_t timeout_mclks); uint32_t timeoutMclksToMicroseconds(uint32_t timeout_mclks, uint32_t macro_period_us); uint32_t timeoutMicrosecondsToMclks(uint32_t timeout_us, uint32_t macro_period_us); - uint32_t calcMacroPeriod(uint8_t vcsel_period); + uint32_t calcMacroPeriod(uint8_t vcsel_period) const; bool setupManualCalibration(void); };