From 06f9c6a210d7935dc3a6cd76f790bac73ea98d0a Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 3 Feb 2020 10:48:47 +0900 Subject: [PATCH] AP_RangeFinder: fix offset param for PWM driver --- libraries/AP_RangeFinder/AP_RangeFinder_PWM.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_PWM.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_PWM.cpp index 3fd253be15..d6c7269955 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_PWM.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_PWM.cpp @@ -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();