AP_RangeFinder: Allow new Maxsonar I2C reading even if reading fails

This commit is contained in:
rishabsingh3003 2023-10-22 15:31:51 -04:00 committed by Peter Barker
parent de61ac3055
commit 5db60eb9ac
1 changed files with 3 additions and 3 deletions

View File

@ -116,11 +116,11 @@ 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();
}
// trigger a new reading
start_reading();
return ret;
}