AP_RangeFinder: PWM driver adds offset param value

This commit is contained in:
Randy Mackay 2020-01-16 12:35:25 +09:00 committed by Andrew Tridgell
parent dfd1e4c839
commit db3f1cb3b3

View File

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