mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 07:28:29 -04:00
AP_RangeFinder: trigger a new reading automatically
this fixes Maxbotix I2C
This commit is contained in:
parent
6416a4d0e6
commit
baa0217bec
@ -104,6 +104,9 @@ bool AP_RangeFinder_MaxsonarI2CXL::get_reading(uint16_t &reading_cm)
|
||||
// combine results into distance
|
||||
reading_cm = ((uint16_t)buff[0]) << 8 | buff[1];
|
||||
|
||||
// trigger a new reading
|
||||
start_reading();
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user