APM:Copter
avoidance_adsb.h
Go to the documentation of this file.
1 #pragma once
2 
4 
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.
10 public:
11  AP_Avoidance_Copter(AP_AHRS &ahrs, class AP_ADSB &adsb)
12  : AP_Avoidance(ahrs, adsb)
13  {
14  }
15 
16  /* Do not allow copies */
17  AP_Avoidance_Copter(const AP_Avoidance_Copter &other) = delete;
19 
20 private:
21  // helper function to set modes and always succeed
23 
24 protected:
25  // override avoidance handler
26  MAV_COLLISION_ACTION handle_avoidance(const AP_Avoidance::Obstacle *obstacle, MAV_COLLISION_ACTION requested_action) override;
27 
28  // override recovery handler
29  void handle_recovery(uint8_t recovery_action) override;
30 
31  // check flight mode is avoid_adsb
32  bool check_flightmode(bool allow_mode_change);
33 
34  // vertical avoidance handler
35  bool handle_avoidance_vertical(const AP_Avoidance::Obstacle *obstacle, bool allow_mode_change);
36 
37  // horizontal avoidance handler
38  bool handle_avoidance_horizontal(const AP_Avoidance::Obstacle *obstacle, bool allow_mode_change);
39 
40  // perpendicular (3 dimensional) avoidance handler
41  bool handle_avoidance_perpendicular(const AP_Avoidance::Obstacle *obstacle, bool allow_mode_change);
42 
43  // control mode before avoidance began
45 };
AP_Avoidance_Copter(AP_AHRS &ahrs, class AP_ADSB &adsb)
control_mode_t
Definition: defines.h:91
void set_mode_else_try_RTL_else_LAND(control_mode_t mode)
bool check_flightmode(bool allow_mode_change)
bool handle_avoidance_perpendicular(const AP_Avoidance::Obstacle *obstacle, bool allow_mode_change)
control_mode_t prev_control_mode
bool handle_avoidance_vertical(const AP_Avoidance::Obstacle *obstacle, bool allow_mode_change)
AP_Avoidance_Copter & operator=(const AP_Avoidance_Copter &)=delete
bool handle_avoidance_horizontal(const AP_Avoidance::Obstacle *obstacle, bool allow_mode_change)
void handle_recovery(uint8_t recovery_action) override
MAV_COLLISION_ACTION handle_avoidance(const AP_Avoidance::Obstacle *obstacle, MAV_COLLISION_ACTION requested_action) override
Definition: defines.h:98