From b31cd1adb51b9832a7fc46fe3d1b0d44b330d1a8 Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Mon, 15 Apr 2019 17:29:36 -0700 Subject: [PATCH] AP_RangeFinder: Remove pre arm distance check --- libraries/AP_RangeFinder/RangeFinder.cpp | 21 ---------------- libraries/AP_RangeFinder/RangeFinder.h | 10 -------- .../AP_RangeFinder/RangeFinder_Backend.cpp | 25 ------------------- .../AP_RangeFinder/RangeFinder_Backend.h | 2 -- 4 files changed, 58 deletions(-) diff --git a/libraries/AP_RangeFinder/RangeFinder.cpp b/libraries/AP_RangeFinder/RangeFinder.cpp index e27df7c000..696dae1eec 100644 --- a/libraries/AP_RangeFinder/RangeFinder.cpp +++ b/libraries/AP_RangeFinder/RangeFinder.cpp @@ -311,10 +311,6 @@ void RangeFinder::init(enum Rotation orientation_default) // present (although it may not be healthy) num_instances = i+1; } - // initialise pre-arm check variables - state[i].pre_arm_check = false; - state[i].pre_arm_distance_min = 9999; // initialise to an arbitrary large value - state[i].pre_arm_distance_max = 0; // initialise status state[i].status = RangeFinder_NotConnected; @@ -337,7 +333,6 @@ void RangeFinder::update(void) continue; } drivers[i]->update(); - drivers[i]->update_pre_arm_check(); } } @@ -631,22 +626,6 @@ uint8_t RangeFinder::range_valid_count_orient(enum Rotation orientation) const return backend->range_valid_count(); } -/* - returns true if pre-arm checks have passed for all range finders - these checks involve the user lifting or rotating the vehicle so that sensor readings between - the min and 2m can be captured - */ -bool RangeFinder::pre_arm_check() const -{ - for (uint8_t i=0; i min distance sensed - max distance < 200cm - min distance sensed is within 10cm of ground clearance or sensor's minimum distance - */ -void AP_RangeFinder_Backend::update_pre_arm_check() -{ - // return immediately if already passed or no sensor data - if (state.pre_arm_check || state.status == RangeFinder::RangeFinder_NotConnected || state.status == RangeFinder::RangeFinder_NoData) { - return; - } - - // update min, max captured distances - state.pre_arm_distance_min = MIN(state.distance_cm, state.pre_arm_distance_min); - state.pre_arm_distance_max = MAX(state.distance_cm, state.pre_arm_distance_max); - - // Check that the range finder has been exercised through a realistic range of movement - if (((state.pre_arm_distance_max - state.pre_arm_distance_min) >= RANGEFINDER_PREARM_REQUIRED_CHANGE_CM) && - (state.pre_arm_distance_max < RANGEFINDER_PREARM_ALT_MAX_CM) && - ((int16_t)state.pre_arm_distance_min < (MAX(params.ground_clearance_cm,params.min_distance_cm) + 10)) && - ((int16_t)state.pre_arm_distance_min > (MIN(params.ground_clearance_cm,params.min_distance_cm) - 10))) { - state.pre_arm_check = true; - } -} diff --git a/libraries/AP_RangeFinder/RangeFinder_Backend.h b/libraries/AP_RangeFinder/RangeFinder_Backend.h index 8e1f557ea1..01fdaa452f 100644 --- a/libraries/AP_RangeFinder/RangeFinder_Backend.h +++ b/libraries/AP_RangeFinder/RangeFinder_Backend.h @@ -33,8 +33,6 @@ public: virtual void handle_msg(mavlink_message_t *msg) { return; } - void update_pre_arm_check(); - enum Rotation orientation() const { return (Rotation)params.orientation.get(); } uint16_t distance_cm() const { return state.distance_cm; } uint16_t voltage_mv() const { return state.voltage_mv; }