3 #include <AP_Avoidance/AP_Avoidance.h>
5 // Provide Copter-specific implementation of avoidance. While most of
6 // the logic for doing the actual avoidance is present in
7 // AP_Avoidance, this class allows Copter to override base
8 // functionality - for example, not doing anything while landed.
9 class AP_Avoidance_Copter
: public AP_Avoidance
{
12 using AP_Avoidance::AP_Avoidance
;
14 /* Do not allow copies */
15 CLASS_NO_COPY(AP_Avoidance_Copter
);
18 // helper function to set modes and always succeed
19 void set_mode_else_try_RTL_else_LAND(Mode::Number mode
);
21 // get minimum limit altitude allowed on descend
22 int32_t get_altitude_minimum() const;
25 // override avoidance handler
26 MAV_COLLISION_ACTION
handle_avoidance(const AP_Avoidance::Obstacle
*obstacle
, MAV_COLLISION_ACTION requested_action
) override
;
28 // override recovery handler
29 void handle_recovery(RecoveryAction recovery_action
) override
;
31 // check flight mode is avoid_adsb
32 bool check_flightmode(bool allow_mode_change
);
34 // vertical avoidance handler
35 bool handle_avoidance_vertical(const AP_Avoidance::Obstacle
*obstacle
, bool allow_mode_change
);
37 // horizontal avoidance handler
38 bool handle_avoidance_horizontal(const AP_Avoidance::Obstacle
*obstacle
, bool allow_mode_change
);
40 // perpendicular (3 dimensional) avoidance handler
41 bool handle_avoidance_perpendicular(const AP_Avoidance::Obstacle
*obstacle
, bool allow_mode_change
);
43 // control mode before avoidance began
44 Mode::Number prev_control_mode
= Mode::Number::RTL
;