Copter: avoidance no longer takes ahrs in constructor

This commit is contained in:
Peter Barker 2019-07-09 16:05:42 +10:00 committed by Andrew Tridgell
parent d7fd88bbca
commit 9412075b9c
3 changed files with 4 additions and 6 deletions

View File

@ -545,7 +545,7 @@ private:
AP_ADSB adsb;
// avoidance of adsb enabled vehicles (normally manned vehicles)
AP_Avoidance_Copter avoidance_adsb{ahrs, adsb};
AP_Avoidance_Copter avoidance_adsb{adsb};
#endif
// last valid RC input time

View File

@ -169,7 +169,7 @@ bool AP_Avoidance_Copter::handle_avoidance_vertical(const AP_Avoidance::Obstacle
// decide on whether we should climb or descend
bool should_climb = false;
Location my_loc;
if (_ahrs.get_position(my_loc)) {
if (AP::ahrs().get_position(my_loc)) {
should_climb = my_loc.alt > obstacle->_location.alt;
}

View File

@ -8,10 +8,8 @@
// functionality - for example, not doing anything while landed.
class AP_Avoidance_Copter : public AP_Avoidance {
public:
AP_Avoidance_Copter(AP_AHRS &ahrs, class AP_ADSB &adsb)
: AP_Avoidance(ahrs, adsb)
{
}
using AP_Avoidance::AP_Avoidance;
/* Do not allow copies */
AP_Avoidance_Copter(const AP_Avoidance_Copter &other) = delete;