mirror of https://github.com/ArduPilot/ardupilot
Copter: avoidance no longer takes ahrs in constructor
This commit is contained in:
parent
d7fd88bbca
commit
9412075b9c
|
@ -545,7 +545,7 @@ private:
|
||||||
AP_ADSB adsb;
|
AP_ADSB adsb;
|
||||||
|
|
||||||
// avoidance of adsb enabled vehicles (normally manned vehicles)
|
// avoidance of adsb enabled vehicles (normally manned vehicles)
|
||||||
AP_Avoidance_Copter avoidance_adsb{ahrs, adsb};
|
AP_Avoidance_Copter avoidance_adsb{adsb};
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// last valid RC input time
|
// last valid RC input time
|
||||||
|
|
|
@ -169,7 +169,7 @@ bool AP_Avoidance_Copter::handle_avoidance_vertical(const AP_Avoidance::Obstacle
|
||||||
// decide on whether we should climb or descend
|
// decide on whether we should climb or descend
|
||||||
bool should_climb = false;
|
bool should_climb = false;
|
||||||
Location my_loc;
|
Location my_loc;
|
||||||
if (_ahrs.get_position(my_loc)) {
|
if (AP::ahrs().get_position(my_loc)) {
|
||||||
should_climb = my_loc.alt > obstacle->_location.alt;
|
should_climb = my_loc.alt > obstacle->_location.alt;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -8,10 +8,8 @@
|
||||||
// functionality - for example, not doing anything while landed.
|
// functionality - for example, not doing anything while landed.
|
||||||
class AP_Avoidance_Copter : public AP_Avoidance {
|
class AP_Avoidance_Copter : public AP_Avoidance {
|
||||||
public:
|
public:
|
||||||
AP_Avoidance_Copter(AP_AHRS &ahrs, class AP_ADSB &adsb)
|
|
||||||
: AP_Avoidance(ahrs, adsb)
|
using AP_Avoidance::AP_Avoidance;
|
||||||
{
|
|
||||||
}
|
|
||||||
|
|
||||||
/* Do not allow copies */
|
/* Do not allow copies */
|
||||||
AP_Avoidance_Copter(const AP_Avoidance_Copter &other) = delete;
|
AP_Avoidance_Copter(const AP_Avoidance_Copter &other) = delete;
|
||||||
|
|
Loading…
Reference in New Issue