AP_RangeFinder: trigger a new reading automatically

this fixes Maxbotix I2C
This commit is contained in:
Andrew Tridgell 2014-07-08 16:28:18 +10:00
parent 6416a4d0e6
commit baa0217bec
1 changed files with 3 additions and 0 deletions

View File

@ -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;
}