mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Rangefinder: make get_temp const
This commit is contained in:
parent
14c32f556c
commit
88b5ff8c6f
@ -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) {
|
||||
|
@ -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…
Reference in New Issue
Block a user