Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduCopter/avoidance_adsb.h
9642 views
1
#pragma once
2
3
#include <AP_Avoidance/AP_Avoidance_config.h>
4
5
#if AP_ADSB_AVOIDANCE_ENABLED
6
7
#include <AP_Avoidance/AP_Avoidance.h>
8
9
// Provide Copter-specific implementation of avoidance. While most of
10
// the logic for doing the actual avoidance is present in
11
// AP_Avoidance, this class allows Copter to override base
12
// functionality - for example, not doing anything while landed.
13
class AP_Avoidance_Copter : public AP_Avoidance {
14
public:
15
16
using AP_Avoidance::AP_Avoidance;
17
18
/* Do not allow copies */
19
CLASS_NO_COPY(AP_Avoidance_Copter);
20
21
private:
22
// helper function to set modes and always succeed
23
void set_mode_else_try_RTL_else_LAND(Mode::Number mode);
24
25
// get minimum limit altitude allowed on descend
26
float get_altitude_minimum_m() const;
27
28
protected:
29
// override avoidance handler
30
MAV_COLLISION_ACTION handle_avoidance(const AP_Avoidance::Obstacle *obstacle, MAV_COLLISION_ACTION requested_action) override;
31
32
// override recovery handler
33
void handle_recovery(RecoveryAction recovery_action) override;
34
35
// check flight mode is avoid_adsb
36
bool check_flightmode(bool allow_mode_change);
37
38
// vertical avoidance handler
39
bool handle_avoidance_vertical(const AP_Avoidance::Obstacle *obstacle, bool allow_mode_change);
40
41
// horizontal avoidance handler
42
bool handle_avoidance_horizontal(const AP_Avoidance::Obstacle *obstacle, bool allow_mode_change);
43
44
// perpendicular (3 dimensional) avoidance handler
45
bool handle_avoidance_perpendicular(const AP_Avoidance::Obstacle *obstacle, bool allow_mode_change);
46
47
// control mode before avoidance began
48
Mode::Number prev_control_mode = Mode::Number::RTL;
49
};
50
51
#endif // AP_ADSB_AVOIDANCE_ENABLED
52
53