AP_RangeFinder: PWM driver adds offset param value
This commit is contained in:
parent
58a0990a5b
commit
a2fdc5b428
@ -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);
|
||||||
|
Loading…
Reference in New Issue
Block a user