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/AC_WPNav/AC_WPNav_OA.cpp
Views: 1798
1
#include "AC_WPNav_config.h"
2
3
#if AC_WPNAV_OA_ENABLED
4
5
#include <AP_Math/control.h>
6
#include <AP_InternalError/AP_InternalError.h>
7
#include "AC_WPNav_OA.h"
8
9
AC_WPNav_OA::AC_WPNav_OA(const AP_InertialNav& inav, const AP_AHRS_View& ahrs, AC_PosControl& pos_control, const AC_AttitudeControl& attitude_control) :
10
AC_WPNav(inav, ahrs, pos_control, attitude_control)
11
{
12
}
13
14
// returns object avoidance adjusted wp location using location class
15
// returns false if unable to convert from target vector to global coordinates
16
bool AC_WPNav_OA::get_oa_wp_destination(Location& destination) const
17
{
18
// if oa inactive return unadjusted location
19
if (_oa_state == AP_OAPathPlanner::OA_NOT_REQUIRED) {
20
return get_wp_destination_loc(destination);
21
}
22
23
// return latest destination provided by oa path planner
24
destination = _oa_destination;
25
return true;
26
}
27
28
/// set_wp_destination waypoint using position vector (distance from ekf origin in cm)
29
/// terrain_alt should be true if destination.z is a desired altitude above terrain
30
/// returns false on failure (likely caused by missing terrain data)
31
bool AC_WPNav_OA::set_wp_destination(const Vector3f& destination, bool terrain_alt)
32
{
33
const bool ret = AC_WPNav::set_wp_destination(destination, terrain_alt);
34
35
if (ret) {
36
// reset object avoidance state
37
_oa_state = AP_OAPathPlanner::OA_NOT_REQUIRED;
38
}
39
40
return ret;
41
}
42
43
/// get_wp_distance_to_destination - get horizontal distance to destination in cm
44
/// always returns distance to final destination (i.e. does not use oa adjusted destination)
45
float AC_WPNav_OA::get_wp_distance_to_destination() const
46
{
47
if (_oa_state == AP_OAPathPlanner::OA_NOT_REQUIRED) {
48
return AC_WPNav::get_wp_distance_to_destination();
49
}
50
51
return get_horizontal_distance_cm(_inav.get_position_xy_cm(), _destination_oabak.xy());
52
}
53
54
/// get_wp_bearing_to_destination - get bearing to next waypoint in centi-degrees
55
/// always returns bearing to final destination (i.e. does not use oa adjusted destination)
56
int32_t AC_WPNav_OA::get_wp_bearing_to_destination() const
57
{
58
if (_oa_state == AP_OAPathPlanner::OA_NOT_REQUIRED) {
59
return AC_WPNav::get_wp_bearing_to_destination();
60
}
61
62
return get_bearing_cd(_inav.get_position_xy_cm(), _destination_oabak.xy());
63
}
64
65
/// true when we have come within RADIUS cm of the waypoint
66
bool AC_WPNav_OA::reached_wp_destination() const
67
{
68
return (_oa_state == AP_OAPathPlanner::OA_NOT_REQUIRED) && AC_WPNav::reached_wp_destination();
69
}
70
71
/// update_wpnav - run the wp controller - should be called at 100hz or higher
72
bool AC_WPNav_OA::update_wpnav()
73
{
74
// run path planning around obstacles
75
AP_OAPathPlanner *oa_ptr = AP_OAPathPlanner::get_singleton();
76
Location current_loc;
77
if ((oa_ptr != nullptr) && AP::ahrs().get_location(current_loc)) {
78
79
// backup _origin and _destination when not doing oa
80
if (_oa_state == AP_OAPathPlanner::OA_NOT_REQUIRED) {
81
_origin_oabak = _origin;
82
_destination_oabak = _destination;
83
_terrain_alt_oabak = _terrain_alt;
84
_next_destination_oabak = _next_destination;
85
}
86
87
// convert origin, destination and next_destination to Locations and pass into oa
88
const Location origin_loc(_origin_oabak, _terrain_alt_oabak ? Location::AltFrame::ABOVE_TERRAIN : Location::AltFrame::ABOVE_ORIGIN);
89
const Location destination_loc(_destination_oabak, _terrain_alt_oabak ? Location::AltFrame::ABOVE_TERRAIN : Location::AltFrame::ABOVE_ORIGIN);
90
const Location next_destination_loc(_next_destination_oabak, _terrain_alt_oabak ? Location::AltFrame::ABOVE_TERRAIN : Location::AltFrame::ABOVE_ORIGIN);
91
Location oa_origin_new, oa_destination_new, oa_next_destination_new;
92
bool dest_to_next_dest_clear = true;
93
AP_OAPathPlanner::OAPathPlannerUsed path_planner_used = AP_OAPathPlanner::OAPathPlannerUsed::None;
94
const AP_OAPathPlanner::OA_RetState oa_retstate = oa_ptr->mission_avoidance(current_loc,
95
origin_loc,
96
destination_loc,
97
next_destination_loc,
98
oa_origin_new,
99
oa_destination_new,
100
oa_next_destination_new,
101
dest_to_next_dest_clear,
102
path_planner_used);
103
104
switch (oa_retstate) {
105
106
case AP_OAPathPlanner::OA_NOT_REQUIRED:
107
if (_oa_state != oa_retstate) {
108
// object avoidance has become inactive so reset target to original destination
109
if (!set_wp_destination(_destination_oabak, _terrain_alt_oabak)) {
110
// trigger terrain failsafe
111
return false;
112
}
113
114
// if path from destination to next_destination is clear
115
if (dest_to_next_dest_clear && (oa_ptr->get_options() & AP_OAPathPlanner::OA_OPTION_FAST_WAYPOINTS)) {
116
// set next destination if non-zero
117
if (!_next_destination_oabak.is_zero()) {
118
set_wp_destination_next(_next_destination_oabak);
119
}
120
}
121
_oa_state = oa_retstate;
122
}
123
124
// ensure we stop at next waypoint
125
// Note that this check is run on every iteration even if the path planner is not active
126
if (!dest_to_next_dest_clear) {
127
force_stop_at_next_wp();
128
}
129
break;
130
131
case AP_OAPathPlanner::OA_PROCESSING:
132
if (oa_ptr->get_options() & AP_OAPathPlanner::OA_OPTION_FAST_WAYPOINTS) {
133
// if fast waypoint option is set, proceed during processing
134
break;
135
}
136
FALLTHROUGH;
137
138
case AP_OAPathPlanner::OA_ERROR:
139
// during processing or in case of error stop the vehicle
140
// by setting the oa_destination to a stopping point
141
if ((_oa_state != AP_OAPathPlanner::OA_PROCESSING) && (_oa_state != AP_OAPathPlanner::OA_ERROR)) {
142
// calculate stopping point
143
Vector3f stopping_point;
144
get_wp_stopping_point(stopping_point);
145
_oa_destination = Location(stopping_point, Location::AltFrame::ABOVE_ORIGIN);
146
_oa_next_destination.zero();
147
if (set_wp_destination(stopping_point, false)) {
148
_oa_state = oa_retstate;
149
}
150
}
151
break;
152
153
case AP_OAPathPlanner::OA_SUCCESS:
154
155
// handling of returned destination depends upon path planner used
156
switch (path_planner_used) {
157
158
case AP_OAPathPlanner::OAPathPlannerUsed::None:
159
// this should never happen. this means the path planner has returned success but has failed to set the path planner used
160
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
161
return false;
162
163
case AP_OAPathPlanner::OAPathPlannerUsed::Dijkstras:
164
// Dijkstra's. Action is only needed if path planner has just became active or the target destination's lat or lon has changed
165
if ((_oa_state != AP_OAPathPlanner::OA_SUCCESS) || !oa_destination_new.same_latlon_as(_oa_destination)) {
166
Location origin_oabak_loc(_origin_oabak, _terrain_alt_oabak ? Location::AltFrame::ABOVE_TERRAIN : Location::AltFrame::ABOVE_ORIGIN);
167
Location destination_oabak_loc(_destination_oabak, _terrain_alt_oabak ? Location::AltFrame::ABOVE_TERRAIN : Location::AltFrame::ABOVE_ORIGIN);
168
oa_destination_new.linearly_interpolate_alt(origin_oabak_loc, destination_oabak_loc);
169
170
// set new OA adjusted destination
171
if (!set_wp_destination_loc(oa_destination_new)) {
172
// trigger terrain failsafe
173
return false;
174
}
175
// if new target set successfully, update oa state and destination
176
_oa_state = oa_retstate;
177
_oa_destination = oa_destination_new;
178
179
// if a next destination was provided then use it
180
if ((oa_ptr->get_options() & AP_OAPathPlanner::OA_OPTION_FAST_WAYPOINTS) && !oa_next_destination_new.is_zero()) {
181
// calculate oa_next_destination_new's altitude using linear interpolation between original origin and destination
182
// this "next destination" is still an intermediate point between the origin and destination
183
Location next_destination_oabak_loc(_next_destination_oabak, _terrain_alt_oabak ? Location::AltFrame::ABOVE_TERRAIN : Location::AltFrame::ABOVE_ORIGIN);
184
oa_next_destination_new.linearly_interpolate_alt(origin_oabak_loc, destination_oabak_loc);
185
if (set_wp_destination_next_loc(oa_next_destination_new)) {
186
_oa_next_destination = oa_next_destination_new;
187
}
188
}
189
}
190
break;
191
192
case AP_OAPathPlanner::OAPathPlannerUsed::BendyRulerHorizontal: {
193
_oa_state = oa_retstate;
194
_oa_destination = oa_destination_new;
195
196
// altitude target interpolated from current_loc's distance along the original path
197
Location target_alt_loc = current_loc;
198
target_alt_loc.linearly_interpolate_alt(origin_loc, destination_loc);
199
200
// correct target_alt_loc's alt-above-ekf-origin if using terrain altitudes
201
// positive terr_offset means terrain below vehicle is above ekf origin's altitude
202
float terr_offset = 0;
203
if (_terrain_alt_oabak && !get_terrain_offset(terr_offset)) {
204
// trigger terrain failsafe
205
return false;
206
}
207
208
// calculate final destination as an offset from EKF origin in NEU
209
Vector2f dest_NE;
210
if (!_oa_destination.get_vector_xy_from_origin_NE(dest_NE)) {
211
// this should never happen because we can only get here if we have an EKF origin
212
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
213
return false;
214
}
215
Vector3p dest_NEU{dest_NE.x, dest_NE.y, (float)target_alt_loc.alt};
216
217
// pass the desired position directly to the position controller
218
_pos_control.input_pos_xyz(dest_NEU, terr_offset, 1000.0);
219
220
// update horizontal position controller (vertical is updated in vehicle code)
221
_pos_control.update_xy_controller();
222
223
// return success without calling parent AC_WPNav
224
return true;
225
}
226
227
case AP_OAPathPlanner::OAPathPlannerUsed::BendyRulerVertical: {
228
_oa_state = oa_retstate;
229
_oa_destination = oa_destination_new;
230
231
// calculate final destination as an offset from EKF origin in NEU
232
Vector3f dest_NEU;
233
if (!_oa_destination.get_vector_from_origin_NEU(dest_NEU)) {
234
// this should never happen because we can only get here if we have an EKF origin
235
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
236
return false;
237
}
238
239
// pass the desired position directly to the position controller as an offset from EKF origin in NEU
240
Vector3p dest_NEU_p{dest_NEU.x, dest_NEU.y, dest_NEU.z};
241
_pos_control.input_pos_xyz(dest_NEU_p, 0, 1000.0);
242
243
// update horizontal position controller (vertical is updated in vehicle code)
244
_pos_control.update_xy_controller();
245
246
// return success without calling parent AC_WPNav
247
return true;
248
}
249
250
}
251
}
252
}
253
254
// run the non-OA update
255
return AC_WPNav::update_wpnav();
256
}
257
258
#endif // Ac_WPNAV_OA_ENABLED
259
260