From 2bdb2f67abb84e2141eeca1512525eecd5b6e587 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 16 Jan 2020 12:35:25 +0900 Subject: [PATCH] AP_RangeFinder: PWM driver adds offset param value --- libraries/AP_RangeFinder/AP_RangeFinder_PWM.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_PWM.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_PWM.cpp index 68358a6784..a950af2192 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_PWM.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_PWM.cpp @@ -166,6 +166,8 @@ 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);