From 88b5ff8c6fb72ee43d59ce7da6f35c261aaad99b Mon Sep 17 00:00:00 2001 From: Pierre Kancir Date: Fri, 4 Jun 2021 18:32:44 +0200 Subject: [PATCH] AP_Rangefinder: make get_temp const --- libraries/AP_RangeFinder/AP_RangeFinder.cpp | 2 +- libraries/AP_RangeFinder/AP_RangeFinder.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder.cpp b/libraries/AP_RangeFinder/AP_RangeFinder.cpp index 9a7ba82633..6953e6c918 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 } // 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); if (backend == nullptr) { diff --git a/libraries/AP_RangeFinder/AP_RangeFinder.h b/libraries/AP_RangeFinder/AP_RangeFinder.h index 518a3cca9b..6e264e4c6b 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder.h @@ -182,7 +182,7 @@ public: uint32_t last_reading_ms(enum Rotation orientation) const; // 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