AP_Rangefinder: make get_temp const

This commit is contained in:
Pierre Kancir 2021-06-04 18:32:44 +02:00 committed by Randy Mackay
parent 14c32f556c
commit 88b5ff8c6f
2 changed files with 2 additions and 2 deletions

View File

@ -745,7 +745,7 @@ MAV_DISTANCE_SENSOR RangeFinder::get_mav_distance_sensor_type_orient(enum Rotati
} }
// get temperature reading in C. returns true on success and populates temp argument // get temperature reading in C. returns true on success and populates temp argument
bool RangeFinder::get_temp(enum Rotation orientation, float &temp) bool RangeFinder::get_temp(enum Rotation orientation, float &temp) const
{ {
AP_RangeFinder_Backend *backend = find_instance(orientation); AP_RangeFinder_Backend *backend = find_instance(orientation);
if (backend == nullptr) { if (backend == nullptr) {

View File

@ -182,7 +182,7 @@ public:
uint32_t last_reading_ms(enum Rotation orientation) const; uint32_t last_reading_ms(enum Rotation orientation) const;
// get temperature reading in C. returns true on success and populates temp argument // get temperature reading in C. returns true on success and populates temp argument
bool get_temp(enum Rotation orientation, float &temp); bool get_temp(enum Rotation orientation, float &temp) const;
/* /*
set an externally estimated terrain height. Used to enable power set an externally estimated terrain height. Used to enable power