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.cpp
Views: 1798
1
#include <AP_HAL/AP_HAL.h>
2
#include "AC_WPNav.h"
3
4
extern const AP_HAL::HAL& hal;
5
6
// maximum velocities and accelerations
7
#define WPNAV_WP_SPEED 1000.0f // default horizontal speed between waypoints in cm/s
8
#define WPNAV_WP_SPEED_MIN 10.0f // minimum horizontal speed between waypoints in cm/s
9
#define WPNAV_WP_RADIUS 200.0f // default waypoint radius in cm
10
#define WPNAV_WP_RADIUS_MIN 5.0f // minimum waypoint radius in cm
11
#define WPNAV_WP_SPEED_UP 250.0f // default maximum climb velocity
12
#define WPNAV_WP_SPEED_DOWN 150.0f // default maximum descent velocity
13
#define WPNAV_WP_ACCEL_Z_DEFAULT 100.0f // default vertical acceleration between waypoints in cm/s/s
14
15
const AP_Param::GroupInfo AC_WPNav::var_info[] = {
16
// index 0 was used for the old orientation matrix
17
18
// @Param: SPEED
19
// @DisplayName: Waypoint Horizontal Speed Target
20
// @Description: Defines the speed in cm/s which the aircraft will attempt to maintain horizontally during a WP mission
21
// @Units: cm/s
22
// @Range: 10 2000
23
// @Increment: 50
24
// @User: Standard
25
AP_GROUPINFO("SPEED", 0, AC_WPNav, _wp_speed_cms, WPNAV_WP_SPEED),
26
27
// @Param: RADIUS
28
// @DisplayName: Waypoint Radius
29
// @Description: Defines the distance from a waypoint, that when crossed indicates the wp has been hit.
30
// @Units: cm
31
// @Range: 5 1000
32
// @Increment: 1
33
// @User: Standard
34
AP_GROUPINFO("RADIUS", 1, AC_WPNav, _wp_radius_cm, WPNAV_WP_RADIUS),
35
36
// @Param: SPEED_UP
37
// @DisplayName: Waypoint Climb Speed Target
38
// @Description: Defines the speed in cm/s which the aircraft will attempt to maintain while climbing during a WP mission
39
// @Units: cm/s
40
// @Range: 10 1000
41
// @Increment: 50
42
// @User: Standard
43
AP_GROUPINFO("SPEED_UP", 2, AC_WPNav, _wp_speed_up_cms, WPNAV_WP_SPEED_UP),
44
45
// @Param: SPEED_DN
46
// @DisplayName: Waypoint Descent Speed Target
47
// @Description: Defines the speed in cm/s which the aircraft will attempt to maintain while descending during a WP mission
48
// @Units: cm/s
49
// @Range: 10 500
50
// @Increment: 10
51
// @User: Standard
52
AP_GROUPINFO("SPEED_DN", 3, AC_WPNav, _wp_speed_down_cms, WPNAV_WP_SPEED_DOWN),
53
54
// @Param: ACCEL
55
// @DisplayName: Waypoint Acceleration
56
// @Description: Defines the horizontal acceleration in cm/s/s used during missions
57
// @Units: cm/s/s
58
// @Range: 50 500
59
// @Increment: 10
60
// @User: Standard
61
AP_GROUPINFO("ACCEL", 5, AC_WPNav, _wp_accel_cmss, WPNAV_ACCELERATION),
62
63
// @Param: ACCEL_Z
64
// @DisplayName: Waypoint Vertical Acceleration
65
// @Description: Defines the vertical acceleration in cm/s/s used during missions
66
// @Units: cm/s/s
67
// @Range: 50 500
68
// @Increment: 10
69
// @User: Standard
70
AP_GROUPINFO("ACCEL_Z", 6, AC_WPNav, _wp_accel_z_cmss, WPNAV_WP_ACCEL_Z_DEFAULT),
71
72
// @Param: RFND_USE
73
// @DisplayName: Waypoint missions use rangefinder for terrain following
74
// @Description: This controls if waypoint missions use rangefinder for terrain following
75
// @Values: 0:Disable,1:Enable
76
// @User: Advanced
77
AP_GROUPINFO("RFND_USE", 10, AC_WPNav, _rangefinder_use, 1),
78
79
// @Param: JERK
80
// @DisplayName: Waypoint Jerk
81
// @Description: Defines the horizontal jerk in m/s/s used during missions
82
// @Units: m/s/s/s
83
// @Range: 1 20
84
// @User: Standard
85
AP_GROUPINFO("JERK", 11, AC_WPNav, _wp_jerk, 1.0f),
86
87
// @Param: TER_MARGIN
88
// @DisplayName: Waypoint Terrain following altitude margin
89
// @Description: Waypoint Terrain following altitude margin. Vehicle will stop if distance from target altitude is larger than this margin (in meters)
90
// @Units: m
91
// @Range: 0.1 100
92
// @User: Advanced
93
AP_GROUPINFO("TER_MARGIN", 12, AC_WPNav, _terrain_margin, 10.0),
94
95
// @Param: ACCEL_C
96
// @DisplayName: Waypoint Cornering Acceleration
97
// @Description: Defines the maximum cornering acceleration in cm/s/s used during missions. If zero uses 2x accel value.
98
// @Units: cm/s/s
99
// @Range: 0 500
100
// @Increment: 10
101
// @User: Standard
102
AP_GROUPINFO("ACCEL_C", 13, AC_WPNav, _wp_accel_c_cmss, 0.0),
103
104
AP_GROUPEND
105
};
106
107
// Default constructor.
108
// Note that the Vector/Matrix constructors already implicitly zero
109
// their values.
110
//
111
AC_WPNav::AC_WPNav(const AP_InertialNav& inav, const AP_AHRS_View& ahrs, AC_PosControl& pos_control, const AC_AttitudeControl& attitude_control) :
112
_inav(inav),
113
_ahrs(ahrs),
114
_pos_control(pos_control),
115
_attitude_control(attitude_control)
116
{
117
AP_Param::setup_object_defaults(this, var_info);
118
119
// init flags
120
_flags.reached_destination = false;
121
_flags.fast_waypoint = false;
122
123
// initialise old WPNAV_SPEED values
124
_last_wp_speed_cms = _wp_speed_cms;
125
_last_wp_speed_up_cms = _wp_speed_up_cms;
126
_last_wp_speed_down_cms = get_default_speed_down();
127
}
128
129
// get expected source of terrain data if alt-above-terrain command is executed (used by Copter's ModeRTL)
130
AC_WPNav::TerrainSource AC_WPNav::get_terrain_source() const
131
{
132
// use range finder if connected
133
if (_rangefinder_available && _rangefinder_use) {
134
return AC_WPNav::TerrainSource::TERRAIN_FROM_RANGEFINDER;
135
}
136
#if AP_TERRAIN_AVAILABLE
137
const AP_Terrain *terrain = AP::terrain();
138
if (terrain != nullptr && terrain->enabled()) {
139
return AC_WPNav::TerrainSource::TERRAIN_FROM_TERRAINDATABASE;
140
} else {
141
return AC_WPNav::TerrainSource::TERRAIN_UNAVAILABLE;
142
}
143
#else
144
return AC_WPNav::TerrainSource::TERRAIN_UNAVAILABLE;
145
#endif
146
}
147
148
///
149
/// waypoint navigation
150
///
151
152
/// wp_and_spline_init - initialise straight line and spline waypoint controllers
153
/// speed_cms should be a positive value or left at zero to use the default speed
154
/// stopping_point should be the vehicle's stopping point (equal to the starting point of the next segment) if know or left as zero
155
/// should be called once before the waypoint controller is used but does not need to be called before subsequent updates to destination
156
void AC_WPNav::wp_and_spline_init(float speed_cms, Vector3f stopping_point)
157
{
158
// check _wp_radius_cm is reasonable
159
_wp_radius_cm.set_and_save_ifchanged(MAX(_wp_radius_cm, WPNAV_WP_RADIUS_MIN));
160
161
// check _wp_speed
162
_wp_speed_cms.set_and_save_ifchanged(MAX(_wp_speed_cms, WPNAV_WP_SPEED_MIN));
163
164
// initialise position controller
165
_pos_control.init_z_controller_stopping_point();
166
_pos_control.init_xy_controller_stopping_point();
167
168
// initialize the desired wp speed
169
_check_wp_speed_change = !is_positive(speed_cms);
170
_wp_desired_speed_xy_cms = is_positive(speed_cms) ? speed_cms : _wp_speed_cms;
171
_wp_desired_speed_xy_cms = MAX(_wp_desired_speed_xy_cms, WPNAV_WP_SPEED_MIN);
172
173
// initialise position controller speed and acceleration
174
_pos_control.set_max_speed_accel_xy(_wp_desired_speed_xy_cms, get_wp_acceleration());
175
_pos_control.set_correction_speed_accel_xy(_wp_desired_speed_xy_cms, get_wp_acceleration());
176
_pos_control.set_max_speed_accel_z(-get_default_speed_down(), _wp_speed_up_cms, _wp_accel_z_cmss);
177
_pos_control.set_correction_speed_accel_z(-get_default_speed_down(), _wp_speed_up_cms, _wp_accel_z_cmss);
178
179
// calculate scurve jerk and jerk time
180
if (!is_positive(_wp_jerk)) {
181
_wp_jerk.set(get_wp_acceleration());
182
}
183
calc_scurve_jerk_and_snap();
184
185
_scurve_prev_leg.init();
186
_scurve_this_leg.init();
187
_scurve_next_leg.init();
188
_track_scalar_dt = 1.0f;
189
190
_flags.reached_destination = true;
191
_flags.fast_waypoint = false;
192
193
// initialise origin and destination to stopping point
194
if (stopping_point.is_zero()) {
195
get_wp_stopping_point(stopping_point);
196
}
197
_origin = _destination = stopping_point;
198
_terrain_alt = false;
199
_this_leg_is_spline = false;
200
201
// initialise the terrain velocity to the current maximum velocity
202
_offset_vel = _wp_desired_speed_xy_cms;
203
_offset_accel = 0.0;
204
_paused = false;
205
206
// mark as active
207
_wp_last_update = AP_HAL::millis();
208
}
209
210
/// set_speed_xy - allows main code to pass target horizontal velocity for wp navigation
211
void AC_WPNav::set_speed_xy(float speed_cms)
212
{
213
// range check target speed and protect against divide by zero
214
if (speed_cms >= WPNAV_WP_SPEED_MIN && is_positive(_wp_desired_speed_xy_cms)) {
215
// update horizontal velocity speed offset scalar
216
_offset_vel = speed_cms * _offset_vel / _wp_desired_speed_xy_cms;
217
218
// initialize the desired wp speed
219
_wp_desired_speed_xy_cms = speed_cms;
220
221
// update position controller speed and acceleration
222
_pos_control.set_max_speed_accel_xy(_wp_desired_speed_xy_cms, get_wp_acceleration());
223
_pos_control.set_correction_speed_accel_xy(_wp_desired_speed_xy_cms, get_wp_acceleration());
224
225
// change track speed
226
update_track_with_speed_accel_limits();
227
}
228
}
229
230
/// set current target climb rate during wp navigation
231
void AC_WPNav::set_speed_up(float speed_up_cms)
232
{
233
_pos_control.set_max_speed_accel_z(_pos_control.get_max_speed_down_cms(), speed_up_cms, _pos_control.get_max_accel_z_cmss());
234
update_track_with_speed_accel_limits();
235
}
236
237
/// set current target descent rate during wp navigation
238
void AC_WPNav::set_speed_down(float speed_down_cms)
239
{
240
_pos_control.set_max_speed_accel_z(speed_down_cms, _pos_control.get_max_speed_up_cms(), _pos_control.get_max_accel_z_cmss());
241
update_track_with_speed_accel_limits();
242
}
243
244
/// set_wp_destination waypoint using location class
245
/// returns false if conversion from location to vector from ekf origin cannot be calculated
246
bool AC_WPNav::set_wp_destination_loc(const Location& destination)
247
{
248
bool terr_alt;
249
Vector3f dest_neu;
250
251
// convert destination location to vector
252
if (!get_vector_NEU(destination, dest_neu, terr_alt)) {
253
return false;
254
}
255
256
// set target as vector from EKF origin
257
return set_wp_destination(dest_neu, terr_alt);
258
}
259
260
/// set next destination using location class
261
/// returns false if conversion from location to vector from ekf origin cannot be calculated
262
bool AC_WPNav::set_wp_destination_next_loc(const Location& destination)
263
{
264
bool terr_alt;
265
Vector3f dest_neu;
266
267
// convert destination location to vector
268
if (!get_vector_NEU(destination, dest_neu, terr_alt)) {
269
return false;
270
}
271
272
// set target as vector from EKF origin
273
return set_wp_destination_next(dest_neu, terr_alt);
274
}
275
276
// get destination as a location. Altitude frame will be above origin or above terrain
277
// returns false if unable to return a destination (for example if origin has not yet been set)
278
bool AC_WPNav::get_wp_destination_loc(Location& destination) const
279
{
280
if (!AP::ahrs().get_origin(destination)) {
281
return false;
282
}
283
284
destination = Location{get_wp_destination(), _terrain_alt ? Location::AltFrame::ABOVE_TERRAIN : Location::AltFrame::ABOVE_ORIGIN};
285
return true;
286
}
287
288
/// set_wp_destination - set destination waypoints using position vectors (distance from ekf origin in cm)
289
/// terrain_alt should be true if destination.z is an altitude above terrain (false if alt-above-ekf-origin)
290
/// returns false on failure (likely caused by missing terrain data)
291
bool AC_WPNav::set_wp_destination(const Vector3f& destination, bool terrain_alt)
292
{
293
// re-initialise if previous destination has been interrupted
294
if (!is_active() || !_flags.reached_destination) {
295
wp_and_spline_init(_wp_desired_speed_xy_cms);
296
}
297
298
_scurve_prev_leg.init();
299
float origin_speed = 0.0f;
300
301
// use previous destination as origin
302
_origin = _destination;
303
304
if (terrain_alt == _terrain_alt) {
305
if (_this_leg_is_spline) {
306
// if previous leg was a spline we can use current target velocity vector for origin velocity vector
307
Vector3f curr_target_vel = _pos_control.get_vel_desired_cms();
308
curr_target_vel.z -= _pos_control.get_vel_offset_z_cms();
309
origin_speed = curr_target_vel.length();
310
} else {
311
// store previous leg
312
_scurve_prev_leg = _scurve_this_leg;
313
}
314
} else {
315
316
// get current alt above terrain
317
float origin_terr_offset;
318
if (!get_terrain_offset(origin_terr_offset)) {
319
return false;
320
}
321
322
// convert origin to alt-above-terrain if necessary
323
if (terrain_alt) {
324
// new destination is alt-above-terrain, previous destination was alt-above-ekf-origin
325
_origin.z -= origin_terr_offset;
326
_pos_control.init_pos_terrain_cm(origin_terr_offset);
327
} else {
328
// new destination is alt-above-ekf-origin, previous destination was alt-above-terrain
329
_origin.z += origin_terr_offset;
330
_pos_control.init_pos_terrain_cm(0.0);
331
}
332
}
333
334
// update destination
335
_destination = destination;
336
_terrain_alt = terrain_alt;
337
338
if (_flags.fast_waypoint && !_this_leg_is_spline && !_next_leg_is_spline && !_scurve_next_leg.finished()) {
339
_scurve_this_leg = _scurve_next_leg;
340
} else {
341
_scurve_this_leg.calculate_track(_origin, _destination,
342
_pos_control.get_max_speed_xy_cms(), _pos_control.get_max_speed_up_cms(), _pos_control.get_max_speed_down_cms(),
343
get_wp_acceleration(), _wp_accel_z_cmss,
344
_scurve_snap * 100.0f, _scurve_jerk * 100.0f);
345
if (!is_zero(origin_speed)) {
346
// rebuild start of scurve if we have a non-zero origin speed
347
_scurve_this_leg.set_origin_speed_max(origin_speed);
348
}
349
}
350
351
_this_leg_is_spline = false;
352
_scurve_next_leg.init();
353
_next_destination.zero(); // clear next destination
354
_flags.fast_waypoint = false; // default waypoint back to slow
355
_flags.reached_destination = false;
356
357
return true;
358
}
359
360
/// set next destination using position vector (distance from ekf origin in cm)
361
/// terrain_alt should be true if destination.z is a desired altitude above terrain
362
/// provide next_destination
363
bool AC_WPNav::set_wp_destination_next(const Vector3f& destination, bool terrain_alt)
364
{
365
// do not add next point if alt types don't match
366
if (terrain_alt != _terrain_alt) {
367
return true;
368
}
369
370
_scurve_next_leg.calculate_track(_destination, destination,
371
_pos_control.get_max_speed_xy_cms(), _pos_control.get_max_speed_up_cms(), _pos_control.get_max_speed_down_cms(),
372
get_wp_acceleration(), _wp_accel_z_cmss,
373
_scurve_snap * 100.0f, _scurve_jerk * 100.0);
374
if (_this_leg_is_spline) {
375
const float this_leg_dest_speed_max = _spline_this_leg.get_destination_speed_max();
376
const float next_leg_origin_speed_max = _scurve_next_leg.set_origin_speed_max(this_leg_dest_speed_max);
377
_spline_this_leg.set_destination_speed_max(next_leg_origin_speed_max);
378
}
379
_next_leg_is_spline = false;
380
381
// next destination provided so fast waypoint
382
_flags.fast_waypoint = true;
383
384
// record next destination
385
_next_destination = destination;
386
387
return true;
388
}
389
390
/// set waypoint destination using NED position vector from ekf origin in meters
391
bool AC_WPNav::set_wp_destination_NED(const Vector3f& destination_NED)
392
{
393
// convert NED to NEU and do not use terrain following
394
return set_wp_destination(Vector3f(destination_NED.x * 100.0f, destination_NED.y * 100.0f, -destination_NED.z * 100.0f), false);
395
}
396
397
/// set waypoint destination using NED position vector from ekf origin in meters
398
bool AC_WPNav::set_wp_destination_next_NED(const Vector3f& destination_NED)
399
{
400
// convert NED to NEU and do not use terrain following
401
return set_wp_destination_next(Vector3f(destination_NED.x * 100.0f, destination_NED.y * 100.0f, -destination_NED.z * 100.0f), false);
402
}
403
404
/// shifts the origin and destination horizontally to the current position
405
/// used to reset the track when taking off without horizontal position control
406
/// relies on set_wp_destination or set_wp_origin_and_destination having been called first
407
void AC_WPNav::shift_wp_origin_and_destination_to_current_pos_xy()
408
{
409
// Reset position controller to current location
410
_pos_control.init_xy_controller();
411
412
// get current and target locations
413
const Vector2f& curr_pos = _inav.get_position_xy_cm();
414
415
// shift origin and destination horizontally
416
_origin.xy() = curr_pos;
417
_destination.xy() = curr_pos;
418
}
419
420
/// shifts the origin and destination horizontally to the achievable stopping point
421
/// used to reset the track when horizontal navigation is enabled after having been disabled (see Copter's wp_navalt_min)
422
/// relies on set_wp_destination or set_wp_origin_and_destination having been called first
423
void AC_WPNav::shift_wp_origin_and_destination_to_stopping_point_xy()
424
{
425
// relax position control in xy axis
426
// removing velocity error also impacts stopping point calculation
427
_pos_control.relax_velocity_controller_xy();
428
429
// get current and target locations
430
Vector2f stopping_point;
431
get_wp_stopping_point_xy(stopping_point);
432
433
// shift origin and destination horizontally
434
_origin.xy() = stopping_point;
435
_destination.xy() = stopping_point;
436
437
// move pos controller target horizontally
438
_pos_control.set_pos_desired_xy_cm(stopping_point);
439
}
440
441
/// get_wp_stopping_point_xy - returns vector to stopping point based on a horizontal position and velocity
442
void AC_WPNav::get_wp_stopping_point_xy(Vector2f& stopping_point) const
443
{
444
Vector2p stop;
445
_pos_control.get_stopping_point_xy_cm(stop);
446
stopping_point = stop.tofloat();
447
}
448
449
/// get_wp_stopping_point - returns vector to stopping point based on 3D position and velocity
450
void AC_WPNav::get_wp_stopping_point(Vector3f& stopping_point) const
451
{
452
Vector3p stop;
453
_pos_control.get_stopping_point_xy_cm(stop.xy());
454
_pos_control.get_stopping_point_z_cm(stop.z);
455
stopping_point = stop.tofloat();
456
}
457
458
/// advance_wp_target_along_track - move target location along track from origin to destination
459
bool AC_WPNav::advance_wp_target_along_track(float dt)
460
{
461
// calculate terrain adjustments
462
float terr_offset = 0.0f;
463
if (_terrain_alt && !get_terrain_offset(terr_offset)) {
464
return false;
465
}
466
const float offset_z_scaler = _pos_control.pos_offset_z_scaler(terr_offset, get_terrain_margin() * 100.0);
467
468
// input shape the terrain offset
469
_pos_control.set_pos_terrain_target_cm(terr_offset);
470
471
// get position controller's position offset (post input shaping) so it can be used in position error calculation
472
const Vector3p& psc_pos_offset = _pos_control.get_pos_offset_cm();
473
474
// get current position and adjust altitude to origin and destination's frame (i.e. _frame)
475
Vector3f curr_pos = _inav.get_position_neu_cm() - psc_pos_offset.tofloat();
476
curr_pos.z -= terr_offset;
477
Vector3f curr_target_vel = _pos_control.get_vel_desired_cms();
478
curr_target_vel.z -= _pos_control.get_vel_offset_z_cms();
479
480
// Use _track_scalar_dt to slow down progression of the position target moving too far in front of aircraft
481
// _track_scalar_dt does not scale the velocity or acceleration
482
float track_scaler_dt = 1.0f;
483
// check target velocity is non-zero
484
if (is_positive(curr_target_vel.length_squared())) {
485
Vector3f track_direction = curr_target_vel.normalized();
486
const float track_error = _pos_control.get_pos_error_cm().dot(track_direction);
487
const float track_velocity = _inav.get_velocity_neu_cms().dot(track_direction);
488
// set time scaler to be consistent with the achievable aircraft speed with a 5% buffer for short term variation.
489
track_scaler_dt = constrain_float(0.05f + (track_velocity - _pos_control.get_pos_xy_p().kP() * track_error) / curr_target_vel.length(), 0.0f, 1.0f);
490
}
491
492
// Use vel_scaler_dt to slow down the trajectory time
493
// vel_scaler_dt scales the velocity and acceleration to be kinematically consistent
494
float vel_scaler_dt = 1.0;
495
if (is_positive(_wp_desired_speed_xy_cms)) {
496
update_vel_accel(_offset_vel, _offset_accel, dt, 0.0, 0.0);
497
const float vel_input = !_paused ? _wp_desired_speed_xy_cms * offset_z_scaler : 0.0;
498
shape_vel_accel(vel_input, 0.0, _offset_vel, _offset_accel, -get_wp_acceleration(), get_wp_acceleration(),
499
_pos_control.get_shaping_jerk_xy_cmsss(), dt, true);
500
vel_scaler_dt = _offset_vel / _wp_desired_speed_xy_cms;
501
}
502
503
// change s-curve time speed with a time constant of maximum acceleration / maximum jerk
504
float track_scaler_tc = 1.0f;
505
if (!is_zero(_wp_jerk)) {
506
track_scaler_tc = 0.01f * get_wp_acceleration()/_wp_jerk;
507
}
508
_track_scalar_dt += (track_scaler_dt - _track_scalar_dt) * (dt / track_scaler_tc);
509
510
// target position, velocity and acceleration from straight line or spline calculators
511
Vector3f target_pos, target_vel, target_accel;
512
513
bool s_finished;
514
if (!_this_leg_is_spline) {
515
// update target position, velocity and acceleration
516
target_pos = _origin;
517
s_finished = _scurve_this_leg.advance_target_along_track(_scurve_prev_leg, _scurve_next_leg, _wp_radius_cm, get_corner_acceleration(), _flags.fast_waypoint, _track_scalar_dt * vel_scaler_dt * dt, target_pos, target_vel, target_accel);
518
} else {
519
// splinetarget_vel
520
target_vel = curr_target_vel;
521
_spline_this_leg.advance_target_along_track(_track_scalar_dt * vel_scaler_dt * dt, target_pos, target_vel);
522
s_finished = _spline_this_leg.reached_destination();
523
}
524
525
Vector3f accel_offset;
526
if (is_positive(target_vel.length_squared())) {
527
Vector3f track_direction = target_vel.normalized();
528
accel_offset = track_direction * _offset_accel * target_vel.length() / _wp_desired_speed_xy_cms;
529
}
530
531
target_vel *= vel_scaler_dt;
532
target_accel *= sq(vel_scaler_dt);
533
target_accel += accel_offset;
534
535
// pass new target to the position controller
536
_pos_control.set_pos_vel_accel(target_pos.topostype(), target_vel, target_accel);
537
538
// check if we've reached the waypoint
539
if (!_flags.reached_destination) {
540
if (s_finished) {
541
// "fast" waypoints are complete once the intermediate point reaches the destination
542
if (_flags.fast_waypoint) {
543
_flags.reached_destination = true;
544
} else {
545
// regular waypoints also require the copter to be within the waypoint radius
546
const Vector3f dist_to_dest = curr_pos - _destination;
547
if (dist_to_dest.length_squared() <= sq(_wp_radius_cm)) {
548
_flags.reached_destination = true;
549
}
550
}
551
}
552
}
553
554
// successfully advanced along track
555
return true;
556
}
557
558
/// recalculate path with update speed and/or acceleration limits
559
void AC_WPNav::update_track_with_speed_accel_limits()
560
{
561
// update this leg
562
if (_this_leg_is_spline) {
563
_spline_this_leg.set_speed_accel(_pos_control.get_max_speed_xy_cms(), _pos_control.get_max_speed_up_cms(), _pos_control.get_max_speed_down_cms(),
564
get_wp_acceleration(), _wp_accel_z_cmss);
565
} else {
566
_scurve_this_leg.set_speed_max(_pos_control.get_max_speed_xy_cms(), _pos_control.get_max_speed_up_cms(), _pos_control.get_max_speed_down_cms());
567
}
568
569
// update next leg
570
if (_next_leg_is_spline) {
571
_spline_next_leg.set_speed_accel(_pos_control.get_max_speed_xy_cms(), _pos_control.get_max_speed_up_cms(), _pos_control.get_max_speed_down_cms(),
572
get_wp_acceleration(), _wp_accel_z_cmss);
573
} else {
574
_scurve_next_leg.set_speed_max(_pos_control.get_max_speed_xy_cms(), _pos_control.get_max_speed_up_cms(), _pos_control.get_max_speed_down_cms());
575
}
576
}
577
578
/// get_wp_distance_to_destination - get horizontal distance to destination in cm
579
float AC_WPNav::get_wp_distance_to_destination() const
580
{
581
return get_horizontal_distance_cm(_inav.get_position_xy_cm(), _destination.xy());
582
}
583
584
/// get_wp_bearing_to_destination - get bearing to next waypoint in centi-degrees
585
int32_t AC_WPNav::get_wp_bearing_to_destination() const
586
{
587
return get_bearing_cd(_inav.get_position_xy_cm(), _destination.xy());
588
}
589
590
/// update_wpnav - run the wp controller - should be called at 100hz or higher
591
bool AC_WPNav::update_wpnav()
592
{
593
// check for changes in speed parameter values
594
if (_check_wp_speed_change) {
595
if (!is_equal(_wp_speed_cms.get(), _last_wp_speed_cms)) {
596
set_speed_xy(_wp_speed_cms);
597
_last_wp_speed_cms = _wp_speed_cms;
598
}
599
}
600
if (!is_equal(_wp_speed_up_cms.get(), _last_wp_speed_up_cms)) {
601
set_speed_up(_wp_speed_up_cms);
602
_last_wp_speed_up_cms = _wp_speed_up_cms;
603
}
604
if (!is_equal(_wp_speed_down_cms.get(), _last_wp_speed_down_cms)) {
605
set_speed_down(_wp_speed_down_cms);
606
_last_wp_speed_down_cms = _wp_speed_down_cms;
607
}
608
609
// advance the target if necessary
610
bool ret = true;
611
if (!advance_wp_target_along_track(_pos_control.get_dt())) {
612
// To-Do: handle inability to advance along track (probably because of missing terrain data)
613
ret = false;
614
}
615
616
_pos_control.update_xy_controller();
617
618
_wp_last_update = AP_HAL::millis();
619
620
return ret;
621
}
622
623
// returns true if update_wpnav has been run very recently
624
bool AC_WPNav::is_active() const
625
{
626
return (AP_HAL::millis() - _wp_last_update) < 200;
627
}
628
629
// force stopping at next waypoint. Used by Dijkstra's object avoidance when path from destination to next destination is not clear
630
// only affects regular (e.g. non-spline) waypoints
631
// returns true if this had any affect on the path
632
bool AC_WPNav::force_stop_at_next_wp()
633
{
634
// exit immediately if vehicle was going to stop anyway
635
if (!_flags.fast_waypoint) {
636
return false;
637
}
638
639
_flags.fast_waypoint = false;
640
641
// update this_leg's final velocity and next leg's initial velocity to zero
642
if (!_this_leg_is_spline) {
643
_scurve_this_leg.set_destination_speed_max(0);
644
}
645
if (!_next_leg_is_spline) {
646
_scurve_next_leg.init();
647
}
648
649
return true;
650
}
651
652
// get terrain's altitude (in cm above the ekf origin) at the current position (+ve means terrain below vehicle is above ekf origin's altitude)
653
bool AC_WPNav::get_terrain_offset(float& offset_cm)
654
{
655
// calculate offset based on source (rangefinder or terrain database)
656
switch (get_terrain_source()) {
657
case AC_WPNav::TerrainSource::TERRAIN_UNAVAILABLE:
658
return false;
659
case AC_WPNav::TerrainSource::TERRAIN_FROM_RANGEFINDER:
660
if (_rangefinder_healthy) {
661
offset_cm = _rangefinder_terrain_offset_cm;
662
return true;
663
}
664
return false;
665
case AC_WPNav::TerrainSource::TERRAIN_FROM_TERRAINDATABASE:
666
#if AP_TERRAIN_AVAILABLE
667
float terr_alt = 0.0f;
668
AP_Terrain *terrain = AP::terrain();
669
if (terrain != nullptr &&
670
terrain->height_above_terrain(terr_alt, true)) {
671
offset_cm = _inav.get_position_z_up_cm() - (terr_alt * 100.0);
672
return true;
673
}
674
#endif
675
return false;
676
}
677
678
// we should never get here
679
return false;
680
}
681
682
///
683
/// spline methods
684
///
685
686
/// set_spline_destination waypoint using location class
687
/// returns false if conversion from location to vector from ekf origin cannot be calculated
688
/// next_destination should be the next segment's destination
689
/// next_is_spline should be true if path to next_destination should be a spline
690
bool AC_WPNav::set_spline_destination_loc(const Location& destination, const Location& next_destination, bool next_is_spline)
691
{
692
// convert destination location to vector
693
Vector3f dest_neu;
694
bool dest_terr_alt;
695
if (!get_vector_NEU(destination, dest_neu, dest_terr_alt)) {
696
return false;
697
}
698
699
// convert next destination to vector
700
Vector3f next_dest_neu;
701
bool next_dest_terr_alt;
702
if (!get_vector_NEU(next_destination, next_dest_neu, next_dest_terr_alt)) {
703
return false;
704
}
705
706
// set target as vector from EKF origin
707
return set_spline_destination(dest_neu, dest_terr_alt, next_dest_neu, next_dest_terr_alt, next_is_spline);
708
}
709
710
/// set next destination (e.g. the one after the current destination) as a spline segment specified as a location
711
/// returns false if conversion from location to vector from ekf origin cannot be calculated
712
/// next_next_destination should be the next segment's destination
713
bool AC_WPNav::set_spline_destination_next_loc(const Location& next_destination, const Location& next_next_destination, bool next_next_is_spline)
714
{
715
// convert next_destination location to vector
716
Vector3f next_dest_neu;
717
bool next_dest_terr_alt;
718
if (!get_vector_NEU(next_destination, next_dest_neu, next_dest_terr_alt)) {
719
return false;
720
}
721
722
// convert next_next_destination to vector
723
Vector3f next_next_dest_neu;
724
bool next_next_dest_terr_alt;
725
if (!get_vector_NEU(next_next_destination, next_next_dest_neu, next_next_dest_terr_alt)) {
726
return false;
727
}
728
729
// set target as vector from EKF origin
730
return set_spline_destination_next(next_dest_neu, next_dest_terr_alt, next_next_dest_neu, next_next_dest_terr_alt, next_next_is_spline);
731
}
732
733
/// set_spline_destination waypoint using position vector (distance from ekf origin in cm)
734
/// terrain_alt should be true if destination.z is a desired altitude above terrain (false if its desired altitudes above ekf origin)
735
/// next_destination should be set to the next segment's destination
736
/// next_terrain_alt should be true if next_destination.z is a desired altitude above terrain (false if its desired altitudes above ekf origin)
737
/// next_destination.z must be in the same "frame" as destination.z (i.e. if destination is a alt-above-terrain, next_destination should be too)
738
bool AC_WPNav::set_spline_destination(const Vector3f& destination, bool terrain_alt, const Vector3f& next_destination, bool next_terrain_alt, bool next_is_spline)
739
{
740
// re-initialise if previous destination has been interrupted
741
if (!is_active() || !_flags.reached_destination) {
742
wp_and_spline_init(_wp_desired_speed_xy_cms);
743
}
744
745
// update spline calculators speeds and accelerations
746
_spline_this_leg.set_speed_accel(_pos_control.get_max_speed_xy_cms(), _pos_control.get_max_speed_up_cms(), _pos_control.get_max_speed_down_cms(),
747
_pos_control.get_max_accel_xy_cmss(), _pos_control.get_max_accel_z_cmss());
748
749
// calculate origin and origin velocity vector
750
Vector3f origin_vector;
751
if (terrain_alt == _terrain_alt) {
752
if (_flags.fast_waypoint) {
753
// calculate origin vector
754
if (_this_leg_is_spline) {
755
// if previous leg was a spline we can use destination velocity vector for origin velocity vector
756
origin_vector = _spline_this_leg.get_destination_vel();
757
} else {
758
// use direction of the previous straight line segment
759
origin_vector = _destination - _origin;
760
}
761
}
762
763
// use previous destination as origin
764
_origin = _destination;
765
} else {
766
767
// use previous destination as origin
768
_origin = _destination;
769
770
// get current alt above terrain
771
float origin_terr_offset;
772
if (!get_terrain_offset(origin_terr_offset)) {
773
return false;
774
}
775
776
// convert origin to alt-above-terrain if necessary
777
if (terrain_alt) {
778
// new destination is alt-above-terrain, previous destination was alt-above-ekf-origin
779
_origin.z -= origin_terr_offset;
780
_pos_control.init_pos_terrain_cm(origin_terr_offset);
781
} else {
782
// new destination is alt-above-ekf-origin, previous destination was alt-above-terrain
783
_origin.z += origin_terr_offset;
784
_pos_control.init_pos_terrain_cm(0.0);
785
}
786
}
787
788
// store destination location
789
_destination = destination;
790
_terrain_alt = terrain_alt;
791
792
// calculate destination velocity vector
793
Vector3f destination_vector;
794
if (terrain_alt == next_terrain_alt) {
795
if (next_is_spline) {
796
// leave this segment moving parallel to vector from origin to next destination
797
destination_vector = next_destination - _origin;
798
} else {
799
// leave this segment moving parallel to next segment
800
destination_vector = next_destination - _destination;
801
}
802
}
803
_flags.fast_waypoint = !destination_vector.is_zero();
804
805
// setup spline leg
806
_spline_this_leg.set_origin_and_destination(_origin, _destination, origin_vector, destination_vector);
807
_this_leg_is_spline = true;
808
_flags.reached_destination = false;
809
810
return true;
811
}
812
813
/// set next destination (e.g. the one after the current destination) as an offset (in cm, NEU frame) from the EKF origin
814
/// next_terrain_alt should be true if next_destination.z is a desired altitude above terrain (false if its desired altitudes above ekf origin)
815
/// next_next_destination should be set to the next segment's destination
816
/// next_next_terrain_alt should be true if next_next_destination.z is a desired altitude above terrain (false if it is desired altitude above ekf origin)
817
/// next_next_destination.z must be in the same "frame" as destination.z (i.e. if next_destination is a alt-above-terrain, next_next_destination should be too)
818
bool AC_WPNav::set_spline_destination_next(const Vector3f& next_destination, bool next_terrain_alt, const Vector3f& next_next_destination, bool next_next_terrain_alt, bool next_next_is_spline)
819
{
820
// do not add next point if alt types don't match
821
if (next_terrain_alt != _terrain_alt) {
822
return true;
823
}
824
825
// calculate origin and origin velocity vector
826
Vector3f origin_vector;
827
if (_this_leg_is_spline) {
828
// if previous leg was a spline we can use destination velocity vector for origin velocity vector
829
origin_vector = _spline_this_leg.get_destination_vel();
830
} else {
831
// use the direction of the previous straight line segment
832
origin_vector = _destination - _origin;
833
}
834
835
// calculate destination velocity vector
836
Vector3f destination_vector;
837
if (next_terrain_alt == next_next_terrain_alt) {
838
if (next_next_is_spline) {
839
// leave this segment moving parallel to vector from this leg's origin (i.e. prev leg's destination) to next next destination
840
destination_vector = next_next_destination - _destination;
841
} else {
842
// leave this segment moving parallel to next segment
843
destination_vector = next_next_destination - next_destination;
844
}
845
}
846
847
// update spline calculators speeds and accelerations
848
_spline_next_leg.set_speed_accel(_pos_control.get_max_speed_xy_cms(), _pos_control.get_max_speed_up_cms(), _pos_control.get_max_speed_down_cms(),
849
_pos_control.get_max_accel_xy_cmss(), _pos_control.get_max_accel_z_cmss());
850
851
// setup next spline leg. Note this could be made local
852
_spline_next_leg.set_origin_and_destination(_destination, next_destination, origin_vector, destination_vector);
853
_next_leg_is_spline = true;
854
855
// next destination provided so fast waypoint
856
_flags.fast_waypoint = true;
857
858
// update this_leg's final velocity to match next spline leg
859
if (!_this_leg_is_spline) {
860
_scurve_this_leg.set_destination_speed_max(_spline_next_leg.get_origin_speed_max());
861
} else {
862
_spline_this_leg.set_destination_speed_max(_spline_next_leg.get_origin_speed_max());
863
}
864
865
return true;
866
}
867
868
// convert location to vector from ekf origin. terrain_alt is set to true if resulting vector's z-axis should be treated as alt-above-terrain
869
// returns false if conversion failed (likely because terrain data was not available)
870
bool AC_WPNav::get_vector_NEU(const Location &loc, Vector3f &vec, bool &terrain_alt)
871
{
872
// convert location to NE vector2f
873
Vector2f res_vec;
874
if (!loc.get_vector_xy_from_origin_NE(res_vec)) {
875
return false;
876
}
877
878
// convert altitude
879
if (loc.get_alt_frame() == Location::AltFrame::ABOVE_TERRAIN) {
880
int32_t terr_alt;
881
if (!loc.get_alt_cm(Location::AltFrame::ABOVE_TERRAIN, terr_alt)) {
882
return false;
883
}
884
vec.z = terr_alt;
885
terrain_alt = true;
886
} else {
887
terrain_alt = false;
888
int32_t temp_alt;
889
if (!loc.get_alt_cm(Location::AltFrame::ABOVE_ORIGIN, temp_alt)) {
890
return false;
891
}
892
vec.z = temp_alt;
893
terrain_alt = false;
894
}
895
896
// copy xy (we do this to ensure we do not adjust vector unless the overall conversion is successful
897
vec.x = res_vec.x;
898
vec.y = res_vec.y;
899
900
return true;
901
}
902
903
// helper function to calculate scurve jerk and jerk_time values
904
// updates _scurve_jerk and _scurve_snap
905
void AC_WPNav::calc_scurve_jerk_and_snap()
906
{
907
// calculate jerk
908
_scurve_jerk = MIN(_attitude_control.get_ang_vel_roll_max_rads() * GRAVITY_MSS, _attitude_control.get_ang_vel_pitch_max_rads() * GRAVITY_MSS);
909
if (is_zero(_scurve_jerk)) {
910
_scurve_jerk = _wp_jerk;
911
} else {
912
_scurve_jerk = MIN(_scurve_jerk, _wp_jerk);
913
}
914
915
// calculate maximum snap
916
// Snap (the rate of change of jerk) uses the attitude control input time constant because multicopters
917
// lean to accelerate. This means the change in angle is equivalent to the change in acceleration
918
_scurve_snap = (_scurve_jerk * M_PI) / (2.0 * MAX(_attitude_control.get_input_tc(), 0.1f));
919
const float snap = MIN(_attitude_control.get_accel_roll_max_radss(), _attitude_control.get_accel_pitch_max_radss()) * GRAVITY_MSS;
920
if (is_positive(snap)) {
921
_scurve_snap = MIN(_scurve_snap, snap);
922
}
923
// reduce maximum snap by a factor of two from what the aircraft is capable of
924
_scurve_snap *= 0.5;
925
}
926
927