CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Avoidance/AP_Avoidance.h
Views: 1798
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_ADSB/AP_ADSB.h>
29
30
#if HAL_ADSB_ENABLED
31
32
#define AP_AVOIDANCE_STATE_RECOVERY_TIME_MS 2000 // we will not downgrade state any faster than this (2 seconds)
33
34
#define AP_AVOIDANCE_ESCAPE_TIME_SEC 2 // vehicle runs from thread for 2 seconds
35
36
class AP_Avoidance {
37
public:
38
39
// constructor
40
AP_Avoidance(class AP_ADSB &adsb);
41
42
/* Do not allow copies */
43
CLASS_NO_COPY(AP_Avoidance);
44
45
// get singleton instance
46
static AP_Avoidance *get_singleton() {
47
return _singleton;
48
}
49
50
// F_RCVRY possible parameter values:
51
enum class RecoveryAction {
52
REMAIN_IN_AVOID_ADSB = 0,
53
RESUME_PREVIOUS_FLIGHTMODE = 1,
54
RTL = 2,
55
RESUME_IF_AUTO_ELSE_LOITER = 3,
56
};
57
58
// obstacle class to hold latest information for a known obstacles
59
class Obstacle {
60
public:
61
MAV_COLLISION_SRC src;
62
uint32_t src_id;
63
uint32_t timestamp_ms;
64
65
Location _location;
66
Vector3f _velocity;
67
68
// fields relating to this being a threat. These would be the reason to have a separate list of threats:
69
MAV_COLLISION_THREAT_LEVEL threat_level;
70
float closest_approach_xy; // metres
71
float closest_approach_z; // metres
72
float time_to_closest_approach; // seconds, 3D approach
73
float distance_to_closest_approach; // metres, 3D
74
uint32_t last_gcs_report_time; // millis
75
};
76
77
78
// add obstacle to the list of known obstacles
79
void add_obstacle(uint32_t obstacle_timestamp_ms,
80
const MAV_COLLISION_SRC src,
81
uint32_t src_id,
82
const Location &loc,
83
const Vector3f &vel_ned);
84
85
void add_obstacle(uint32_t obstacle_timestamp_ms,
86
const MAV_COLLISION_SRC src,
87
uint32_t src_id,
88
const Location &loc,
89
float cog,
90
float hspeed,
91
float vspeed);
92
93
// update should be called at 10hz or higher
94
void update();
95
96
// enable or disable avoidance
97
void enable() { _enabled.set(true); };
98
void disable() { _enabled.set(false); };
99
100
// current overall threat level
101
MAV_COLLISION_THREAT_LEVEL current_threat_level() const;
102
103
// add obstacles into the Avoidance system from MAVLink messages
104
void handle_msg(const mavlink_message_t &msg);
105
106
// for holding parameters
107
static const struct AP_Param::GroupInfo var_info[];
108
109
protected:
110
111
// top level avoidance handler. This calls the vehicle specific handle_avoidance with requested action
112
void handle_avoidance_local(AP_Avoidance::Obstacle *threat);
113
114
// avoid the most significant threat. child classes must override this method
115
// function returns the action that it is actually taking
116
virtual MAV_COLLISION_ACTION handle_avoidance(const AP_Avoidance::Obstacle *obstacle, MAV_COLLISION_ACTION requested_action) = 0;
117
118
// recover after all threats have cleared. child classes must override this method
119
// recovery_action is from F_RCVRY parameter
120
virtual void handle_recovery(RecoveryAction recovery_action) = 0;
121
122
uint32_t _last_state_change_ms = 0;
123
MAV_COLLISION_THREAT_LEVEL _threat_level = MAV_COLLISION_THREAT_LEVEL_NONE;
124
125
// gcs notification
126
// specifies how long we should continue sending messages about a threat after it has cleared
127
static const uint8_t _gcs_cleared_messages_duration = 5; // seconds
128
uint32_t _gcs_cleared_messages_first_sent;
129
130
void handle_threat_gcs_notify(AP_Avoidance::Obstacle *threat);
131
132
AP_Avoidance::Obstacle *most_serious_threat();
133
134
// returns an entry from the MAV_COLLISION_ACTION representative
135
// of what the current avoidance handler is up to.
136
MAV_COLLISION_ACTION mav_avoidance_action() { return _latest_action; }
137
138
// get target destination that best gets vehicle away from the nearest obstacle
139
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);
140
141
// get unit vector away from the nearest obstacle
142
bool get_vector_perpendicular(const AP_Avoidance::Obstacle *obstacle, Vector3f &vec_neu) const;
143
144
// helper functions to calculate destination to get us away from obstacle
145
// Note: v1 is NED
146
static Vector3f perpendicular_xyz(const Location &p1, const Vector3f &v1, const Location &p2);
147
static Vector2f perpendicular_xy(const Location &p1, const Vector3f &v1, const Location &p2);
148
149
private:
150
151
void send_collision_all(const AP_Avoidance::Obstacle &threat, MAV_COLLISION_ACTION behaviour) const;
152
153
// constants
154
const uint32_t MAX_OBSTACLE_AGE_MS = 5000; // obstacles that have not been heard from for 5 seconds are removed from the list
155
const static uint8_t _gcs_notify_interval = 1; // seconds
156
157
// speed below which we will fly directly away from a threat
158
// rather than perpendicular to its velocity:
159
const uint8_t _low_velocity_threshold = 1; // meters/second
160
161
// check to see if we are initialised (and possibly do initialisation)
162
bool check_startup();
163
164
// initialize _obstacle_list
165
void init();
166
167
// free _obstacle_list
168
void deinit();
169
170
// get unique id for adsb
171
uint32_t src_id_for_adsb_vehicle(const AP_ADSB::adsb_vehicle_t &vehicle) const;
172
173
void check_for_threats();
174
void update_threat_level(const Location &my_loc,
175
const Vector3f &my_vel,
176
AP_Avoidance::Obstacle &obstacle);
177
178
// calls into the AP_ADSB library to retrieve vehicle data
179
void get_adsb_samples();
180
181
// returns true if the obstacle should be considered more of a
182
// threat than the current most serious threat
183
bool obstacle_is_more_serious_threat(const AP_Avoidance::Obstacle &obstacle) const;
184
185
// internal variables
186
AP_Avoidance::Obstacle *_obstacles;
187
uint8_t _obstacles_allocated;
188
uint8_t _obstacle_count;
189
int8_t _current_most_serious_threat;
190
MAV_COLLISION_ACTION _latest_action = MAV_COLLISION_ACTION_NONE;
191
192
// external references
193
class AP_ADSB &_adsb;
194
195
// parameters
196
AP_Int8 _enabled;
197
AP_Int8 _obstacles_max;
198
199
AP_Int8 _fail_action;
200
AP_Int8 _fail_recovery;
201
AP_Int8 _fail_time_horizon;
202
AP_Int16 _fail_distance_xy;
203
AP_Int16 _fail_distance_z;
204
AP_Int16 _fail_altitude_minimum;
205
206
AP_Int8 _warn_action;
207
AP_Int8 _warn_time_horizon;
208
AP_Float _warn_distance_xy;
209
AP_Float _warn_distance_z;
210
211
// multi-thread support for avoidance
212
HAL_Semaphore _rsem;
213
214
static AP_Avoidance *_singleton;
215
};
216
217
float closest_approach_xy(const Location &my_loc,
218
const Vector3f &my_vel,
219
const Location &obstacle_loc,
220
const Vector3f &obstacle_vel,
221
uint8_t time_horizon);
222
223
float closest_approach_z(const Location &my_loc,
224
const Vector3f &my_vel,
225
const Location &obstacle_loc,
226
const Vector3f &obstacle_vel,
227
uint8_t time_horizon);
228
229
230
namespace AP {
231
AP_Avoidance *ap_avoidance();
232
};
233
234
#endif
235
236
237