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/ArduPlane/avoidance_adsb.cpp
Views: 1798
1
2
#include <stdio.h>
3
#include "Plane.h"
4
5
#if HAL_ADSB_ENABLED
6
void Plane::avoidance_adsb_update(void)
7
{
8
adsb.update();
9
avoidance_adsb.update();
10
}
11
12
13
MAV_COLLISION_ACTION AP_Avoidance_Plane::handle_avoidance(const AP_Avoidance::Obstacle *obstacle, MAV_COLLISION_ACTION requested_action)
14
{
15
MAV_COLLISION_ACTION actual_action = requested_action;
16
bool failsafe_state_change = false;
17
18
// check for changes in failsafe
19
if (!plane.failsafe.adsb) {
20
plane.failsafe.adsb = true;
21
failsafe_state_change = true;
22
// record flight mode in case it's required for the recovery
23
prev_control_mode_number = plane.control_mode->mode_number();
24
}
25
26
// take no action in some flight modes
27
bool flightmode_prohibits_action = false;
28
if (plane.control_mode == &plane.mode_manual ||
29
(plane.control_mode == &plane.mode_auto && !plane.auto_state.takeoff_complete) ||
30
(plane.flight_stage == AP_FixedWing::FlightStage::LAND) || // TODO: consider allowing action during approach
31
plane.control_mode == &plane.mode_autotune) {
32
flightmode_prohibits_action = true;
33
}
34
#if HAL_QUADPLANE_ENABLED
35
if (plane.control_mode == &plane.mode_qland) {
36
flightmode_prohibits_action = true;
37
}
38
#endif
39
if (flightmode_prohibits_action) {
40
actual_action = MAV_COLLISION_ACTION_NONE;
41
}
42
43
// take action based on requested action
44
switch (actual_action) {
45
46
case MAV_COLLISION_ACTION_RTL:
47
if (failsafe_state_change) {
48
plane.set_mode(plane.mode_rtl, ModeReason::AVOIDANCE);
49
}
50
break;
51
52
case MAV_COLLISION_ACTION_HOVER:
53
if (failsafe_state_change) {
54
#if HAL_QUADPLANE_ENABLED
55
if (plane.quadplane.is_flying()) {
56
plane.set_mode(plane.mode_qloiter, ModeReason::AVOIDANCE);
57
break;
58
}
59
#endif
60
plane.set_mode(plane.mode_loiter, ModeReason::AVOIDANCE);
61
}
62
break;
63
64
case MAV_COLLISION_ACTION_ASCEND_OR_DESCEND: {
65
// climb or descend to avoid obstacle
66
Location loc = plane.next_WP_loc;
67
if (handle_avoidance_vertical(obstacle, failsafe_state_change, loc)) {
68
plane.set_guided_WP(loc);
69
} else {
70
actual_action = MAV_COLLISION_ACTION_NONE;
71
}
72
break;
73
}
74
case MAV_COLLISION_ACTION_MOVE_HORIZONTALLY: {
75
// move horizontally to avoid obstacle
76
Location loc = plane.next_WP_loc;
77
if (handle_avoidance_horizontal(obstacle, failsafe_state_change, loc)) {
78
plane.set_guided_WP(loc);
79
} else {
80
actual_action = MAV_COLLISION_ACTION_NONE;
81
}
82
break;
83
}
84
case MAV_COLLISION_ACTION_MOVE_PERPENDICULAR:
85
{
86
// move horizontally and vertically to avoid obstacle
87
Location loc = plane.next_WP_loc;
88
const bool success_vert = handle_avoidance_vertical(obstacle, failsafe_state_change, loc);
89
const bool success_hor = handle_avoidance_horizontal(obstacle, failsafe_state_change, loc);
90
if (success_vert || success_hor) {
91
plane.set_guided_WP(loc);
92
} else {
93
actual_action = MAV_COLLISION_ACTION_NONE;
94
}
95
}
96
break;
97
98
// unsupported actions and those that require no response
99
case MAV_COLLISION_ACTION_NONE:
100
return actual_action;
101
case MAV_COLLISION_ACTION_REPORT:
102
default:
103
break;
104
}
105
106
if (failsafe_state_change) {
107
gcs().send_text(MAV_SEVERITY_ALERT, "Avoid: Performing action: %d", actual_action);
108
}
109
110
// return with action taken
111
return actual_action;
112
}
113
114
void AP_Avoidance_Plane::handle_recovery(RecoveryAction recovery_action)
115
{
116
// check we are coming out of failsafe
117
if (plane.failsafe.adsb) {
118
plane.failsafe.adsb = false;
119
gcs().send_text(MAV_SEVERITY_INFO, "Avoid: Resuming with action: %u", (unsigned)recovery_action);
120
121
// restore flight mode if requested and user has not changed mode since
122
if (plane.control_mode_reason == ModeReason::AVOIDANCE) {
123
switch (recovery_action) {
124
125
case RecoveryAction::REMAIN_IN_AVOID_ADSB:
126
// do nothing, we'll stay in the AVOID_ADSB mode which is guided which will loiter
127
break;
128
129
case RecoveryAction::RESUME_PREVIOUS_FLIGHTMODE:
130
plane.set_mode_by_number(prev_control_mode_number, ModeReason::AVOIDANCE_RECOVERY);
131
break;
132
133
case RecoveryAction::RTL:
134
plane.set_mode(plane.mode_rtl, ModeReason::AVOIDANCE_RECOVERY);
135
break;
136
137
case RecoveryAction::RESUME_IF_AUTO_ELSE_LOITER:
138
if (prev_control_mode_number == Mode::Number::AUTO) {
139
plane.set_mode(plane.mode_auto, ModeReason::AVOIDANCE_RECOVERY);
140
} else {
141
// let ModeAvoidADSB continue in its guided
142
// behaviour, but reset the loiter location,
143
// rather than where the avoidance location was
144
plane.set_guided_WP(plane.current_loc);
145
}
146
break;
147
148
default:
149
// user has specified an invalid recovery action;
150
// loiter where we are
151
plane.set_guided_WP(plane.current_loc);
152
break;
153
} // switch
154
}
155
}
156
}
157
158
// check flight mode is avoid_adsb
159
bool AP_Avoidance_Plane::check_flightmode(bool allow_mode_change)
160
{
161
// ensure plane is in avoid_adsb mode
162
if (allow_mode_change && plane.control_mode != &plane.mode_avoidADSB) {
163
plane.set_mode(plane.mode_avoidADSB, ModeReason::AVOIDANCE);
164
}
165
166
// check flight mode
167
return (plane.control_mode == &plane.mode_avoidADSB);
168
}
169
170
bool AP_Avoidance_Plane::handle_avoidance_vertical(const AP_Avoidance::Obstacle *obstacle, bool allow_mode_change, Location &new_loc)
171
{
172
// ensure copter is in avoid_adsb mode
173
if (!check_flightmode(allow_mode_change)) {
174
return false;
175
}
176
177
// get best vector away from obstacle
178
if (plane.current_loc.alt > obstacle->_location.alt) {
179
// should climb
180
new_loc.alt = plane.current_loc.alt + 1000; // set alt demand to be 10m above us, climb rate will be TECS_CLMB_MAX
181
return true;
182
183
} else if (plane.current_loc.alt > plane.g.RTL_altitude*100) {
184
// should descend while above RTL alt
185
// TODO: consider using a lower altitude than RTL_altitude since it's default (100m) is quite high
186
new_loc.alt = plane.current_loc.alt - 1000; // set alt demand to be 10m below us, sink rate will be TECS_SINK_MAX
187
return true;
188
}
189
190
return false;
191
}
192
193
bool AP_Avoidance_Plane::handle_avoidance_horizontal(const AP_Avoidance::Obstacle *obstacle, bool allow_mode_change, Location &new_loc)
194
{
195
// ensure plane is in avoid_adsb mode
196
if (!check_flightmode(allow_mode_change)) {
197
return false;
198
}
199
200
// get best vector away from obstacle
201
Vector3f velocity_neu;
202
if (get_vector_perpendicular(obstacle, velocity_neu)) {
203
// remove vertical component
204
velocity_neu.z = 0.0f;
205
206
// check for divide by zero
207
if (is_zero(velocity_neu.x) && is_zero(velocity_neu.y)) {
208
return false;
209
}
210
211
// re-normalize
212
velocity_neu.normalize();
213
214
// push vector further away.
215
velocity_neu *= 10000;
216
217
// set target
218
new_loc.offset(velocity_neu.x, velocity_neu.y);
219
return true;
220
}
221
222
// if we got this far we failed to set the new target
223
return false;
224
}
225
226
#endif // HAL_ADSB_ENABLED
227
228
229