AP_RangeFinder: fix offset param for PWM driver

This commit is contained in:
Randy Mackay 2020-02-03 10:48:47 +09:00 committed by Andrew Tridgell
parent f5aa9d5e58
commit fa76276040

View File

@ -166,14 +166,14 @@ void AP_RangeFinder_PWM::update(void)
}
if (!get_reading(state.distance_cm)) {
// add offset
state.distance_cm += params.offset;
// failure; consider changing our state
if (AP_HAL::millis() - state.last_reading_ms > 200) {
set_status(RangeFinder::RangeFinder_NoData);
}
return;
}
// add offset
state.distance_cm += params.offset;
// update range_valid state based on distance measured
state.last_reading_ms = AP_HAL::millis();