From d7fd88bbca3aae5444b56ad695bacd75fc26382c Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 9 Jul 2019 16:04:59 +1000 Subject: [PATCH] AP_Avoidance: stop taking reference to ahrs in constructor --- libraries/AP_Avoidance/AP_Avoidance.cpp | 10 ++++++---- libraries/AP_Avoidance/AP_Avoidance.h | 10 ++++------ 2 files changed, 10 insertions(+), 10 deletions(-) diff --git a/libraries/AP_Avoidance/AP_Avoidance.cpp b/libraries/AP_Avoidance/AP_Avoidance.cpp index 5561fd3989..b91ebd293b 100644 --- a/libraries/AP_Avoidance/AP_Avoidance.cpp +++ b/libraries/AP_Avoidance/AP_Avoidance.cpp @@ -3,6 +3,7 @@ extern const AP_HAL::HAL& hal; #include +#include #include #define AVOIDANCE_DEBUGGING 0 @@ -125,8 +126,7 @@ const AP_Param::GroupInfo AP_Avoidance::var_info[] = { AP_GROUPEND }; -AP_Avoidance::AP_Avoidance(AP_AHRS &ahrs, AP_ADSB &adsb) : - _ahrs(ahrs), +AP_Avoidance::AP_Avoidance(AP_ADSB &adsb) : _adsb(adsb) { AP_Param::setup_object_defaults(this, var_info); @@ -436,6 +436,8 @@ bool AP_Avoidance::obstacle_is_more_serious_threat(const AP_Avoidance::Obstacle void AP_Avoidance::check_for_threats() { + const AP_AHRS &_ahrs = AP::ahrs(); + Location my_loc; if (!_ahrs.get_position(my_loc)) { // if we don't know our own location we can't determine any threat level @@ -522,7 +524,7 @@ void AP_Avoidance::handle_avoidance_local(AP_Avoidance::Obstacle *threat) action = (MAV_COLLISION_ACTION)_fail_action.get(); Location my_loc; if (action != MAV_COLLISION_ACTION_NONE && _fail_altitude_minimum > 0 && - _ahrs.get_position(my_loc) && ((my_loc.alt*0.01f) < _fail_altitude_minimum)) { + AP::ahrs().get_position(my_loc) && ((my_loc.alt*0.01f) < _fail_altitude_minimum)) { // disable avoidance when close to ground, report only action = MAV_COLLISION_ACTION_REPORT; } @@ -597,7 +599,7 @@ bool AP_Avoidance::get_vector_perpendicular(const AP_Avoidance::Obstacle *obstac } Location my_abs_pos; - if (!_ahrs.get_position(my_abs_pos)) { + if (!AP::ahrs().get_position(my_abs_pos)) { // we should not get to here! If we don't know our position // we can't know if there are any threats, for starters! return false; diff --git a/libraries/AP_Avoidance/AP_Avoidance.h b/libraries/AP_Avoidance/AP_Avoidance.h index e3fe9ce198..39d17758f4 100644 --- a/libraries/AP_Avoidance/AP_Avoidance.h +++ b/libraries/AP_Avoidance/AP_Avoidance.h @@ -25,7 +25,6 @@ based on AP_ADSB, Tom Pittenger, November 2015 */ -#include #include // F_RCVRY possible parameter values @@ -40,6 +39,10 @@ class AP_Avoidance { public: + + // constructor + AP_Avoidance(class AP_ADSB &adsb); + // obstacle class to hold latest information for a known obstacles class Obstacle { public: @@ -92,8 +95,6 @@ public: static const struct AP_Param::GroupInfo var_info[]; protected: - // constructor - AP_Avoidance(AP_AHRS &ahrs, class AP_ADSB &adsb); // top level avoidance handler. This calls the vehicle specific handle_avoidance with requested action void handle_avoidance_local(AP_Avoidance::Obstacle *threat); @@ -133,9 +134,6 @@ protected: static Vector3f perpendicular_xyz(const Location &p1, const Vector3f &v1, const Location &p2); static Vector2f perpendicular_xy(const Location &p1, const Vector3f &v1, const Location &p2); - // reference to AHRS, so we can ask for our position, heading and speed - const AP_AHRS &_ahrs; - private: // constants