mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
PulsedLightRFinder: read method returns int16_t
This commit is contained in:
parent
bf3fa8b99b
commit
32820b4260
@ -80,7 +80,7 @@ bool AP_RangeFinder_PulsedLightLRF::take_reading()
|
||||
}
|
||||
|
||||
// read - return last value measured by sensor
|
||||
int AP_RangeFinder_PulsedLightLRF::read()
|
||||
int16_t AP_RangeFinder_PulsedLightLRF::read()
|
||||
{
|
||||
uint8_t buff[2];
|
||||
int16_t ret_value = 0;
|
||||
|
@ -90,7 +90,7 @@ public:
|
||||
bool take_reading();
|
||||
|
||||
// read value from sensor and return distance in cm
|
||||
int read();
|
||||
int16_t read();
|
||||
|
||||
// heath
|
||||
bool healthy;
|
||||
|
Loading…
Reference in New Issue
Block a user