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