Browse Source

AP_Rangefinder: make get_temp const

zr-v5.1
Pierre Kancir 4 years ago committed by Randy Mackay
parent
commit
88b5ff8c6f
  1. 2
      libraries/AP_RangeFinder/AP_RangeFinder.cpp
  2. 2
      libraries/AP_RangeFinder/AP_RangeFinder.h

2
libraries/AP_RangeFinder/AP_RangeFinder.cpp

@ -745,7 +745,7 @@ MAV_DISTANCE_SENSOR RangeFinder::get_mav_distance_sensor_type_orient(enum Rotati @@ -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) {

2
libraries/AP_RangeFinder/AP_RangeFinder.h

@ -182,7 +182,7 @@ public: @@ -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

Loading…
Cancel
Save