mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 00:13:59 -04:00
AP_Rangefinder : make get_temp const
This makes backend get_temp methods const Co-Authored-By: Josh Henderson <69225461+hendjoshsr71@users.noreply.github.com>
This commit is contained in:
parent
5cca39e50a
commit
9729377bb3
@ -61,7 +61,7 @@ public:
|
||||
uint32_t last_reading_ms() const { return state.last_reading_ms; }
|
||||
|
||||
// get temperature reading in C. returns true on success and populates temp argument
|
||||
virtual bool get_temp(float &temp) { return false; }
|
||||
virtual bool get_temp(float &temp) const { return false; }
|
||||
|
||||
protected:
|
||||
|
||||
|
@ -50,7 +50,7 @@ bool AP_RangeFinder_NMEA::get_reading(uint16_t &reading_cm)
|
||||
}
|
||||
|
||||
// get temperature reading
|
||||
bool AP_RangeFinder_NMEA::get_temp(float &temp)
|
||||
bool AP_RangeFinder_NMEA::get_temp(float &temp) const
|
||||
{
|
||||
uint32_t now_ms = AP_HAL::millis();
|
||||
if ((_temp_readtime_ms == 0) || ((now_ms - _temp_readtime_ms) > read_timeout_ms())) {
|
||||
|
@ -45,7 +45,7 @@ private:
|
||||
bool get_reading(uint16_t &reading_cm) override;
|
||||
|
||||
// get temperature reading in C. returns true on success and populates temp argument
|
||||
bool get_temp(float &temp) override;
|
||||
bool get_temp(float &temp) const override;
|
||||
|
||||
uint16_t read_timeout_ms() const override { return 3000; }
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user