AP_RangeFinder: fix offset param for PWM driver
This commit is contained in:
parent
529f067914
commit
7d8952a48a
@ -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::Status::NoData);
|
||||
}
|
||||
return;
|
||||
}
|
||||
// add offset
|
||||
state.distance_cm += params.offset;
|
||||
|
||||
// update range_valid state based on distance measured
|
||||
state.last_reading_ms = AP_HAL::millis();
|
||||
|
Loading…
Reference in New Issue
Block a user