AP_RangeFinder: Add missing const in member functions

Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
Patrick José Pereira 2021-02-01 13:26:33 -03:00 committed by Andrew Tridgell
parent 2ae7edc8b2
commit efffed0510
5 changed files with 5 additions and 5 deletions

View File

@ -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;

View File

@ -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 {

View File

@ -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

View File

@ -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

View File

@ -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);
};