mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_RangeFinder: Allow new Maxsonar I2C reading even if reading fails
This commit is contained in:
parent
de61ac3055
commit
5db60eb9ac
@ -116,10 +116,10 @@ bool AP_RangeFinder_MaxsonarI2CXL::get_reading(uint16_t &reading_cm)
|
||||
if (ret) {
|
||||
// combine results into distance
|
||||
reading_cm = be16toh(val);
|
||||
}
|
||||
|
||||
// trigger a new reading
|
||||
start_reading();
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user