APM:Libraries
AP_Avoidance.h
Go to the documentation of this file.
1 #pragma once
2 
3 /*
4  This program is free software: you can redistribute it and/or modify
5  it under the terms of the GNU General Public License as published by
6  the Free Software Foundation, either version 3 of the License, or
7  (at your option) any later version.
8 
9  This program is distributed in the hope that it will be useful,
10  but WITHOUT ANY WARRANTY; without even the implied warranty of
11  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12  GNU General Public License for more details.
13 
14  You should have received a copy of the GNU General Public License
15  along with this program. If not, see <http://www.gnu.org/licenses/>.
16  */
17 /*
18  Situational awareness for ArduPilot
19 
20  - record a series of moving points in space which should be avoided
21  - produce messages for GCS if a collision risk is detected
22 
23  Peter Barker, May 2016
24 
25  based on AP_ADSB, Tom Pittenger, November 2015
26 */
27 
28 #include <AP_AHRS/AP_AHRS.h>
29 #include <AP_ADSB/AP_ADSB.h>
30 
31 // F_RCVRY possible parameter values
32 #define AP_AVOIDANCE_RECOVERY_REMAIN_IN_AVOID_ADSB 0
33 #define AP_AVOIDANCE_RECOVERY_RESUME_PREVIOUS_FLIGHTMODE 1
34 #define AP_AVOIDANCE_RECOVERY_RTL 2
35 #define AP_AVOIDANCE_RECOVERY_RESUME_IF_AUTO_ELSE_LOITER 3
36 
37 #define AP_AVOIDANCE_STATE_RECOVERY_TIME_MS 2000 // we will not downgrade state any faster than this (2 seconds)
38 
39 #define AP_AVOIDANCE_ESCAPE_TIME_SEC 2 // vehicle runs from thread for 2 seconds
40 
41 class AP_Avoidance {
42 public:
43  // obstacle class to hold latest information for a known obstacles
44  class Obstacle {
45  public:
46  MAV_COLLISION_SRC src;
47  uint32_t src_id;
48  uint32_t timestamp_ms;
49 
52 
53  // fields relating to this being a threat. These would be the reason to have a separate list of threats:
54  MAV_COLLISION_THREAT_LEVEL threat_level;
55  float closest_approach_xy; // metres
56  float closest_approach_z; // metres
57  float time_to_closest_approach; // seconds, 3D approach
58  float distance_to_closest_approach; // metres, 3D
59  uint32_t last_gcs_report_time; // millis
60  };
61 
62 
63  // add obstacle to the list of known obstacles
64  void add_obstacle(uint32_t obstacle_timestamp_ms,
65  const MAV_COLLISION_SRC src,
66  uint32_t src_id,
67  const Location &loc,
68  const Vector3f &vel_ned);
69 
70  void add_obstacle(uint32_t obstacle_timestamp_ms,
71  const MAV_COLLISION_SRC src,
72  uint32_t src_id,
73  const Location &loc,
74  float cog,
75  float hspeed,
76  float vspeed);
77 
78  // update should be called at 10hz or higher
79  void update();
80 
81  // enable or disable avoidance
82  void enable() { _enabled = true; };
83  void disable() { _enabled = false; };
84 
85  // current overall threat level
86  MAV_COLLISION_THREAT_LEVEL current_threat_level() const;
87 
88  // add obstacles into the Avoidance system from MAVLink messages
89  void handle_msg(const mavlink_message_t &msg);
90 
91  // for holding parameters
92  static const struct AP_Param::GroupInfo var_info[];
93 
94 protected:
95  // constructor
96  AP_Avoidance(AP_AHRS &ahrs, class AP_ADSB &adsb);
97 
98  // top level avoidance handler. This calls the vehicle specific handle_avoidance with requested action
100 
101  // avoid the most significant threat. child classes must override this method
102  // function returns the action that it is actually taking
103  virtual MAV_COLLISION_ACTION handle_avoidance(const AP_Avoidance::Obstacle *obstacle, MAV_COLLISION_ACTION requested_action) = 0;
104 
105  // recover after all threats have cleared. child classes must override this method
106  // recovery_action is from F_RCVRY parameter
107  virtual void handle_recovery(uint8_t recovery_action) = 0;
108 
109  uint32_t _last_state_change_ms = 0;
110  MAV_COLLISION_THREAT_LEVEL _threat_level = MAV_COLLISION_THREAT_LEVEL_NONE;
111 
112  // gcs notification
113  // specifies how long we should continue sending messages about a threat after it has cleared
114  static const uint8_t _gcs_cleared_messages_duration = 5; // seconds
116 
118 
120 
121  // returns an entry from the MAV_COLLISION_ACTION representative
122  // of what the current avoidance handler is up to.
123  MAV_COLLISION_ACTION mav_avoidance_action() { return _latest_action; }
124 
125  // get target destination that best gets vehicle away from the nearest obstacle
126  bool get_destination_perpendicular(const AP_Avoidance::Obstacle *obstacle, Vector3f &newdest_neu, const float wp_speed_xy, const float wp_speed_z, const uint8_t _minimum_avoid_height);
127 
128  // get unit vector away from the nearest obstacle
129  bool get_vector_perpendicular(const AP_Avoidance::Obstacle *obstacle, Vector3f &vec_neu);
130 
131  // helper functions to calculate destination to get us away from obstacle
132  // Note: v1 is NED
133  static Vector3f perpendicular_xyz(const Location &p1, const Vector3f &v1, const Location &p2);
134  static Vector2f perpendicular_xy(const Location &p1, const Vector3f &v1, const Location &p2);
135 
136  // reference to AHRS, so we can ask for our position, heading and speed
137  const AP_AHRS &_ahrs;
138 
139 private:
140 
141  // constants
142  const uint32_t MAX_OBSTACLE_AGE_MS = 5000; // obstacles that have not been heard from for 5 seconds are removed from the list
143  const static uint8_t _gcs_notify_interval = 1; // seconds
144 
145  // speed below which we will fly directly away from a threat
146  // rather than perpendicular to its velocity:
147  const uint8_t _low_velocity_threshold = 1; // meters/second
148 
149  // check to see if we are initialised (and possibly do initialisation)
150  bool check_startup();
151 
152  // initialize _obstacle_list
153  void init();
154 
155  // free _obstacle_list
156  void deinit();
157 
158  // get unique id for adsb
160 
161  void check_for_threats();
162  void update_threat_level(const Location &my_loc,
163  const Vector3f &my_vel,
164  AP_Avoidance::Obstacle &obstacle);
165 
166  // calls into the AP_ADSB library to retrieve vehicle data
167  void get_adsb_samples();
168 
169  // returns true if the obstacle should be considered more of a
170  // threat than the current most serious threat
171  bool obstacle_is_more_serious_threat(const AP_Avoidance::Obstacle &obstacle) const;
172 
173  // internal variables
178  MAV_COLLISION_ACTION _latest_action = MAV_COLLISION_ACTION_NONE;
179 
180  // external references
181  class AP_ADSB &_adsb;
182 
183  // parameters
184  AP_Int8 _enabled;
185  AP_Int8 _obstacles_max;
186 
187  AP_Int8 _fail_action;
188  AP_Int8 _fail_recovery;
193 
194  AP_Int8 _warn_action;
198 };
199 
201  const Vector2f &p);
202 float closest_approach_xy(const Location &my_loc,
203  const Vector3f &my_vel,
204  const Location &obstacle_loc,
205  const Vector3f &obstacle_vel,
206  uint8_t time_horizon);
207 
208 float closest_approach_z(const Location &my_loc,
209  const Vector3f &my_vel,
210  const Location &obstacle_loc,
211  const Vector3f &obstacle_vel,
212  uint8_t time_horizon);
AP_Avoidance::Obstacle * most_serious_threat()
virtual MAV_COLLISION_ACTION handle_avoidance(const AP_Avoidance::Obstacle *obstacle, MAV_COLLISION_ACTION requested_action)=0
const AP_AHRS & _ahrs
Definition: AP_Avoidance.h:137
bool check_startup()
AP_Int8 _obstacles_max
Definition: AP_Avoidance.h:185
uint32_t _last_state_change_ms
Definition: AP_Avoidance.h:109
AP_Int8 _fail_recovery
Definition: AP_Avoidance.h:188
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
class AP_ADSB & _adsb
Definition: AP_Avoidance.h:181
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_Avoidance.h:92
AP_Int8 _warn_time_horizon
Definition: AP_Avoidance.h:195
AP_Int8 _enabled
Definition: AP_Avoidance.h:184
const uint32_t MAX_OBSTACLE_AGE_MS
Definition: AP_Avoidance.h:142
const uint8_t _low_velocity_threshold
Definition: AP_Avoidance.h:147
MAV_COLLISION_ACTION _latest_action
Definition: AP_Avoidance.h:178
float distance_to_closest_approach
Definition: AP_Avoidance.h:58
void check_for_threats()
uint32_t last_gcs_report_time
Definition: AP_Avoidance.h:59
uint32_t _gcs_cleared_messages_first_sent
Definition: AP_Avoidance.h:115
MAV_COLLISION_THREAT_LEVEL current_threat_level() const
AP_Int8 _fail_time_horizon
Definition: AP_Avoidance.h:189
float closest_distance_between_radial_and_point(const Vector2f &w, const Vector2f &p)
void handle_threat_gcs_notify(AP_Avoidance::Obstacle *threat)
void handle_avoidance_local(AP_Avoidance::Obstacle *threat)
uint8_t _obstacles_allocated
Definition: AP_Avoidance.h:175
AP_Int8 _warn_action
Definition: AP_Avoidance.h:194
AP_Int16 _fail_altitude_minimum
Definition: AP_Avoidance.h:192
static DummyVehicle vehicle
Definition: AHRS_Test.cpp:35
bool get_destination_perpendicular(const AP_Avoidance::Obstacle *obstacle, Vector3f &newdest_neu, const float wp_speed_xy, const float wp_speed_z, const uint8_t _minimum_avoid_height)
MAV_COLLISION_THREAT_LEVEL _threat_level
Definition: AP_Avoidance.h:110
AP_Int16 _fail_distance_xy
Definition: AP_Avoidance.h:190
void enable()
Definition: AP_Avoidance.h:82
virtual void handle_recovery(uint8_t recovery_action)=0
uint8_t _obstacle_count
Definition: AP_Avoidance.h:176
void disable()
Definition: AP_Avoidance.h:83
uint32_t src_id_for_adsb_vehicle(AP_ADSB::adsb_vehicle_t vehicle) const
static Vector2f perpendicular_xy(const Location &p1, const Vector3f &v1, const Location &p2)
MAV_COLLISION_THREAT_LEVEL threat_level
Definition: AP_Avoidance.h:54
static const uint8_t _gcs_cleared_messages_duration
Definition: AP_Avoidance.h:114
bool get_vector_perpendicular(const AP_Avoidance::Obstacle *obstacle, Vector3f &vec_neu)
MAV_COLLISION_SRC src
Definition: AP_Avoidance.h:46
static const uint8_t _gcs_notify_interval
Definition: AP_Avoidance.h:143
AP_Int16 _fail_distance_z
Definition: AP_Avoidance.h:191
AP_Int8 _fail_action
Definition: AP_Avoidance.h:187
bool obstacle_is_more_serious_threat(const AP_Avoidance::Obstacle &obstacle) const
static Vector3f perpendicular_xyz(const Location &p1, const Vector3f &v1, const Location &p2)
MAV_COLLISION_ACTION mav_avoidance_action()
Definition: AP_Avoidance.h:123
AP_Float _warn_distance_xy
Definition: AP_Avoidance.h:196
AP_Float _warn_distance_z
Definition: AP_Avoidance.h:197
void update_threat_level(const Location &my_loc, const Vector3f &my_vel, AP_Avoidance::Obstacle &obstacle)
AP_Avoidance(AP_AHRS &ahrs, class AP_ADSB &adsb)
void get_adsb_samples()
void handle_msg(const mavlink_message_t &msg)
void add_obstacle(uint32_t obstacle_timestamp_ms, const MAV_COLLISION_SRC src, uint32_t src_id, const Location &loc, const Vector3f &vel_ned)
AP_Avoidance::Obstacle * _obstacles
Definition: AP_Avoidance.h:174
int8_t _current_most_serious_threat
Definition: AP_Avoidance.h:177