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_Follow/AP_Follow.cpp
Views: 1798
1
/*
2
This program is free software: you can redistribute it and/or modify
3
it under the terms of the GNU General Public License as published by
4
the Free Software Foundation, either version 3 of the License, or
5
(at your option) any later version.
6
7
This program is distributed in the hope that it will be useful,
8
but WITHOUT ANY WARRANTY; without even the implied warranty of
9
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10
GNU General Public License for more details.
11
12
You should have received a copy of the GNU General Public License
13
along with this program. If not, see <http://www.gnu.org/licenses/>.
14
*/
15
16
#include "AP_Follow_config.h"
17
18
#if AP_FOLLOW_ENABLED
19
20
#include <AP_HAL/AP_HAL.h>
21
#include "AP_Follow.h"
22
#include <ctype.h>
23
#include <stdio.h>
24
25
#include <AP_AHRS/AP_AHRS.h>
26
#include <AP_Logger/AP_Logger.h>
27
#include <GCS_MAVLink/GCS.h>
28
#include <AP_Vehicle/AP_Vehicle_Type.h>
29
30
extern const AP_HAL::HAL& hal;
31
32
#define AP_FOLLOW_TIMEOUT_MS 3000 // position estimate timeout after 1 second
33
#define AP_FOLLOW_SYSID_TIMEOUT_MS 10000 // forget sysid we are following if we have not heard from them in 10 seconds
34
35
#define AP_FOLLOW_OFFSET_TYPE_NED 0 // offsets are in north-east-down frame
36
#define AP_FOLLOW_OFFSET_TYPE_RELATIVE 1 // offsets are relative to lead vehicle's heading
37
38
#define AP_FOLLOW_ALTITUDE_TYPE_RELATIVE 1 // relative altitude is used by default
39
40
#define AP_FOLLOW_POS_P_DEFAULT 0.1f // position error gain default
41
42
#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
43
#define AP_FOLLOW_ALT_TYPE_DEFAULT 0
44
#else
45
#define AP_FOLLOW_ALT_TYPE_DEFAULT AP_FOLLOW_ALTITUDE_TYPE_RELATIVE
46
#endif
47
48
AP_Follow *AP_Follow::_singleton;
49
50
// table of user settable parameters
51
const AP_Param::GroupInfo AP_Follow::var_info[] = {
52
53
// @Param: _ENABLE
54
// @DisplayName: Follow enable/disable
55
// @Description: Enabled/disable following a target
56
// @Values: 0:Disabled,1:Enabled
57
// @User: Standard
58
AP_GROUPINFO_FLAGS("_ENABLE", 1, AP_Follow, _enabled, 0, AP_PARAM_FLAG_ENABLE),
59
60
// 2 is reserved for TYPE parameter
61
62
// @Param: _SYSID
63
// @DisplayName: Follow target's mavlink system id
64
// @Description: Follow target's mavlink system id
65
// @Range: 0 255
66
// @User: Standard
67
AP_GROUPINFO("_SYSID", 3, AP_Follow, _sysid, 0),
68
69
// 4 is reserved for MARGIN parameter
70
71
// @Param: _DIST_MAX
72
// @DisplayName: Follow distance maximum
73
// @Description: Follow distance maximum. targets further than this will be ignored
74
// @Units: m
75
// @Range: 1 1000
76
// @User: Standard
77
AP_GROUPINFO("_DIST_MAX", 5, AP_Follow, _dist_max, 100),
78
79
// @Param: _OFS_TYPE
80
// @DisplayName: Follow offset type
81
// @Description: Follow offset type
82
// @Values: 0:North-East-Down, 1:Relative to lead vehicle heading
83
// @User: Standard
84
AP_GROUPINFO("_OFS_TYPE", 6, AP_Follow, _offset_type, AP_FOLLOW_OFFSET_TYPE_NED),
85
86
// @Param: _OFS_X
87
// @DisplayName: Follow offsets in meters north/forward
88
// @Description: Follow offsets in meters north/forward. If positive, this vehicle fly ahead or north of lead vehicle. Depends on FOLL_OFS_TYPE
89
// @Range: -100 100
90
// @Units: m
91
// @Increment: 1
92
// @User: Standard
93
94
// @Param: _OFS_Y
95
// @DisplayName: Follow offsets in meters east/right
96
// @Description: Follow offsets in meters east/right. If positive, this vehicle will fly to the right or east of lead vehicle. Depends on FOLL_OFS_TYPE
97
// @Range: -100 100
98
// @Units: m
99
// @Increment: 1
100
// @User: Standard
101
102
// @Param: _OFS_Z
103
// @DisplayName: Follow offsets in meters down
104
// @Description: Follow offsets in meters down. If positive, this vehicle will fly below the lead vehicle
105
// @Range: -100 100
106
// @Units: m
107
// @Increment: 1
108
// @User: Standard
109
AP_GROUPINFO("_OFS", 7, AP_Follow, _offset, 0),
110
111
#if !(APM_BUILD_TYPE(APM_BUILD_Rover))
112
// @Param: _YAW_BEHAVE
113
// @DisplayName: Follow yaw behaviour
114
// @Description: Follow yaw behaviour
115
// @Values: 0:None,1:Face Lead Vehicle,2:Same as Lead vehicle,3:Direction of Flight
116
// @User: Standard
117
AP_GROUPINFO("_YAW_BEHAVE", 8, AP_Follow, _yaw_behave, 1),
118
#endif
119
120
// @Param: _POS_P
121
// @DisplayName: Follow position error P gain
122
// @Description: Follow position error P gain. Converts the difference between desired vertical speed and actual speed into a desired acceleration that is passed to the throttle acceleration controller
123
// @Range: 0.01 1.00
124
// @Increment: 0.01
125
// @User: Standard
126
AP_SUBGROUPINFO(_p_pos, "_POS_", 9, AP_Follow, AC_P),
127
128
#if !(APM_BUILD_TYPE(APM_BUILD_Rover))
129
// @Param: _ALT_TYPE
130
// @DisplayName: Follow altitude type
131
// @Description: Follow altitude type
132
// @Values: 0:absolute, 1:relative
133
// @User: Standard
134
AP_GROUPINFO("_ALT_TYPE", 10, AP_Follow, _alt_type, AP_FOLLOW_ALT_TYPE_DEFAULT),
135
#endif
136
137
// @Param: _OPTIONS
138
// @DisplayName: Follow options
139
// @Description: Follow options bitmask
140
// @Values: 0:None,1: Mount Follows lead vehicle on mode enter
141
// @User: Standard
142
AP_GROUPINFO("_OPTIONS", 11, AP_Follow, _options, 0),
143
144
AP_GROUPEND
145
};
146
147
/*
148
The constructor also initialises the proximity sensor. Note that this
149
constructor is not called until detect() returns true, so we
150
already know that we should setup the proximity sensor
151
*/
152
AP_Follow::AP_Follow() :
153
_p_pos(AP_FOLLOW_POS_P_DEFAULT)
154
{
155
_singleton = this;
156
AP_Param::setup_object_defaults(this, var_info);
157
}
158
159
// restore offsets to zero if necessary, should be called when vehicle exits follow mode
160
void AP_Follow::clear_offsets_if_required()
161
{
162
if (_offsets_were_zero) {
163
_offset.set(Vector3f());
164
}
165
_offsets_were_zero = false;
166
}
167
168
// get target's estimated location
169
bool AP_Follow::get_target_location_and_velocity(Location &loc, Vector3f &vel_ned) const
170
{
171
// exit immediately if not enabled
172
if (!_enabled) {
173
return false;
174
}
175
176
// check for timeout
177
if ((_last_location_update_ms == 0) || (AP_HAL::millis() - _last_location_update_ms > AP_FOLLOW_TIMEOUT_MS)) {
178
return false;
179
}
180
181
// calculate time since last actual position update
182
const float dt = (AP_HAL::millis() - _last_location_update_ms) * 0.001f;
183
184
// get velocity estimate
185
if (!get_velocity_ned(vel_ned, dt)) {
186
return false;
187
}
188
189
// project the vehicle position
190
Location last_loc = _target_location;
191
last_loc.offset(vel_ned.x * dt, vel_ned.y * dt);
192
last_loc.alt -= vel_ned.z * 100.0f * dt; // convert m/s to cm/s, multiply by dt. minus because NED
193
194
// return latest position estimate
195
loc = last_loc;
196
return true;
197
}
198
199
// get distance vector to target (in meters) and target's velocity all in NED frame
200
bool AP_Follow::get_target_dist_and_vel_ned(Vector3f &dist_ned, Vector3f &dist_with_offs, Vector3f &vel_ned)
201
{
202
// get our location
203
Location current_loc;
204
if (!AP::ahrs().get_location(current_loc)) {
205
clear_dist_and_bearing_to_target();
206
return false;
207
}
208
209
// get target location and velocity
210
Location target_loc;
211
Vector3f veh_vel;
212
if (!get_target_location_and_velocity(target_loc, veh_vel)) {
213
clear_dist_and_bearing_to_target();
214
return false;
215
}
216
217
// change to altitude above home
218
if (target_loc.relative_alt == 1) {
219
current_loc.change_alt_frame(Location::AltFrame::ABOVE_HOME);
220
}
221
222
// calculate difference
223
const Vector3f dist_vec = current_loc.get_distance_NED(target_loc);
224
225
// fail if too far
226
if (is_positive(_dist_max.get()) && (dist_vec.length() > _dist_max)) {
227
clear_dist_and_bearing_to_target();
228
return false;
229
}
230
231
// initialise offsets from distance vector if required
232
init_offsets_if_required(dist_vec);
233
234
// get offsets
235
Vector3f offsets;
236
if (!get_offsets_ned(offsets)) {
237
clear_dist_and_bearing_to_target();
238
return false;
239
}
240
241
// calculate results
242
dist_ned = dist_vec;
243
dist_with_offs = dist_vec + offsets;
244
vel_ned = veh_vel;
245
246
// record distance and heading for reporting purposes
247
if (is_zero(dist_with_offs.x) && is_zero(dist_with_offs.y)) {
248
clear_dist_and_bearing_to_target();
249
} else {
250
_dist_to_target = safe_sqrt(sq(dist_with_offs.x) + sq(dist_with_offs.y));
251
_bearing_to_target = degrees(atan2f(dist_with_offs.y, dist_with_offs.x));
252
}
253
254
return true;
255
}
256
257
// get target's heading in degrees (0 = north, 90 = east)
258
bool AP_Follow::get_target_heading_deg(float &heading) const
259
{
260
// exit immediately if not enabled
261
if (!_enabled) {
262
return false;
263
}
264
265
// check for timeout
266
if ((_last_heading_update_ms == 0) || (AP_HAL::millis() - _last_heading_update_ms > AP_FOLLOW_TIMEOUT_MS)) {
267
return false;
268
}
269
270
// return latest heading estimate
271
heading = _target_heading;
272
return true;
273
}
274
275
// returns true if we should extract information from msg
276
bool AP_Follow::should_handle_message(const mavlink_message_t &msg) const
277
{
278
// exit immediately if not enabled
279
if (!_enabled) {
280
return false;
281
}
282
283
// skip our own messages
284
if (msg.sysid == mavlink_system.sysid) {
285
return false;
286
}
287
288
// skip message if not from our target
289
if (_sysid != 0 && msg.sysid != _sysid) {
290
return false;
291
}
292
293
return true;
294
}
295
296
// handle mavlink DISTANCE_SENSOR messages
297
void AP_Follow::handle_msg(const mavlink_message_t &msg)
298
{
299
// this method should be called from an "update()" method:
300
if (_automatic_sysid) {
301
// maybe timeout who we were following...
302
if ((_last_location_update_ms == 0) ||
303
(AP_HAL::millis() - _last_location_update_ms > AP_FOLLOW_SYSID_TIMEOUT_MS)) {
304
_sysid.set(0);
305
}
306
}
307
308
if (!should_handle_message(msg)) {
309
return;
310
}
311
312
// decode global-position-int message
313
bool updated = false;
314
315
switch (msg.msgid) {
316
case MAVLINK_MSG_ID_GLOBAL_POSITION_INT: {
317
updated = handle_global_position_int_message(msg);
318
break;
319
}
320
case MAVLINK_MSG_ID_FOLLOW_TARGET: {
321
updated = handle_follow_target_message(msg);
322
break;
323
}
324
}
325
326
if (updated) {
327
#if HAL_LOGGING_ENABLED
328
Log_Write_FOLL();
329
#endif
330
}
331
}
332
333
bool AP_Follow::handle_global_position_int_message(const mavlink_message_t &msg)
334
{
335
// decode message
336
mavlink_global_position_int_t packet;
337
mavlink_msg_global_position_int_decode(&msg, &packet);
338
339
// ignore message if lat and lon are (exactly) zero
340
if ((packet.lat == 0 && packet.lon == 0)) {
341
return false;
342
}
343
344
_target_location.lat = packet.lat;
345
_target_location.lng = packet.lon;
346
347
// select altitude source based on FOLL_ALT_TYPE param
348
if (_alt_type == AP_FOLLOW_ALTITUDE_TYPE_RELATIVE) {
349
// above home alt
350
_target_location.set_alt_cm(packet.relative_alt / 10, Location::AltFrame::ABOVE_HOME);
351
} else {
352
// absolute altitude
353
_target_location.set_alt_cm(packet.alt / 10, Location::AltFrame::ABSOLUTE);
354
}
355
356
_target_velocity_ned.x = packet.vx * 0.01f; // velocity north
357
_target_velocity_ned.y = packet.vy * 0.01f; // velocity east
358
_target_velocity_ned.z = packet.vz * 0.01f; // velocity down
359
360
// get a local timestamp with correction for transport jitter
361
_last_location_update_ms = _jitter.correct_offboard_timestamp_msec(packet.time_boot_ms, AP_HAL::millis());
362
if (packet.hdg <= 36000) { // heading (UINT16_MAX if unknown)
363
_target_heading = packet.hdg * 0.01f; // convert centi-degrees to degrees
364
_last_heading_update_ms = _last_location_update_ms;
365
}
366
// initialise _sysid if zero to sender's id
367
if (_sysid == 0) {
368
_sysid.set(msg.sysid);
369
_automatic_sysid = true;
370
}
371
return true;
372
}
373
374
bool AP_Follow::handle_follow_target_message(const mavlink_message_t &msg)
375
{
376
// decode message
377
mavlink_follow_target_t packet;
378
mavlink_msg_follow_target_decode(&msg, &packet);
379
380
// ignore message if lat and lon are (exactly) zero
381
if ((packet.lat == 0 && packet.lon == 0)) {
382
return false;
383
}
384
// require at least position
385
if ((packet.est_capabilities & (1<<0)) == 0) {
386
return false;
387
}
388
389
Location new_loc = _target_location;
390
new_loc.lat = packet.lat;
391
new_loc.lng = packet.lon;
392
new_loc.set_alt_m(packet.alt, Location::AltFrame::ABSOLUTE);
393
394
// FOLLOW_TARGET is always AMSL, change the provided alt to
395
// above home if we are configured for relative alt
396
if (_alt_type == AP_FOLLOW_ALTITUDE_TYPE_RELATIVE &&
397
!new_loc.change_alt_frame(Location::AltFrame::ABOVE_HOME)) {
398
return false;
399
}
400
_target_location = new_loc;
401
402
if (packet.est_capabilities & (1<<1)) {
403
_target_velocity_ned.x = packet.vel[0]; // velocity north
404
_target_velocity_ned.y = packet.vel[1]; // velocity east
405
_target_velocity_ned.z = packet.vel[2]; // velocity down
406
} else {
407
_target_velocity_ned.zero();
408
}
409
410
// get a local timestamp with correction for transport jitter
411
_last_location_update_ms = _jitter.correct_offboard_timestamp_msec(packet.timestamp, AP_HAL::millis());
412
413
if (packet.est_capabilities & (1<<3)) {
414
Quaternion q{packet.attitude_q[0], packet.attitude_q[1], packet.attitude_q[2], packet.attitude_q[3]};
415
float r, p, y;
416
q.to_euler(r,p,y);
417
_target_heading = degrees(y);
418
_last_heading_update_ms = _last_location_update_ms;
419
}
420
421
// initialise _sysid if zero to sender's id
422
if (_sysid == 0) {
423
_sysid.set(msg.sysid);
424
_automatic_sysid = true;
425
}
426
427
return true;
428
}
429
430
// write out an onboard-log message to help diagnose follow problems:
431
#if HAL_LOGGING_ENABLED
432
void AP_Follow::Log_Write_FOLL()
433
{
434
// get estimated location and velocity
435
Location loc_estimate{};
436
Vector3f vel_estimate;
437
UNUSED_RESULT(get_target_location_and_velocity(loc_estimate, vel_estimate));
438
439
// log lead's estimated vs reported position
440
// @LoggerMessage: FOLL
441
// @Description: Follow library diagnostic data
442
// @Field: TimeUS: Time since system startup
443
// @Field: Lat: Target latitude
444
// @Field: Lon: Target longitude
445
// @Field: Alt: Target absolute altitude
446
// @Field: VelN: Target earth-frame velocity, North
447
// @Field: VelE: Target earth-frame velocity, East
448
// @Field: VelD: Target earth-frame velocity, Down
449
// @Field: LatE: Vehicle latitude
450
// @Field: LonE: Vehicle longitude
451
// @Field: AltE: Vehicle absolute altitude
452
AP::logger().WriteStreaming("FOLL",
453
"TimeUS,Lat,Lon,Alt,VelN,VelE,VelD,LatE,LonE,AltE", // labels
454
"sDUmnnnDUm", // units
455
"F--B000--B", // mults
456
"QLLifffLLi", // fmt
457
AP_HAL::micros64(),
458
_target_location.lat,
459
_target_location.lng,
460
_target_location.alt,
461
(double)_target_velocity_ned.x,
462
(double)_target_velocity_ned.y,
463
(double)_target_velocity_ned.z,
464
loc_estimate.lat,
465
loc_estimate.lng,
466
loc_estimate.alt
467
);
468
}
469
#endif // HAL_LOGGING_ENABLED
470
471
// get velocity estimate in m/s in NED frame using dt since last update
472
bool AP_Follow::get_velocity_ned(Vector3f &vel_ned, float dt) const
473
{
474
vel_ned = _target_velocity_ned + (_target_accel_ned * dt);
475
return true;
476
}
477
478
// initialise offsets to provided distance vector to other vehicle (in meters in NED frame) if required
479
void AP_Follow::init_offsets_if_required(const Vector3f &dist_vec_ned)
480
{
481
// return immediately if offsets have already been set
482
if (!_offset.get().is_zero()) {
483
return;
484
}
485
_offsets_were_zero = true;
486
487
float target_heading_deg;
488
if ((_offset_type == AP_FOLLOW_OFFSET_TYPE_RELATIVE) && get_target_heading_deg(target_heading_deg)) {
489
// rotate offsets from north facing to vehicle's perspective
490
_offset.set(rotate_vector(-dist_vec_ned, -target_heading_deg));
491
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Relative follow offset loaded");
492
} else {
493
// initialise offset in NED frame
494
_offset.set(-dist_vec_ned);
495
// ensure offset_type used matches frame of offsets saved
496
_offset_type.set(AP_FOLLOW_OFFSET_TYPE_NED);
497
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "N-E-D follow offset loaded");
498
}
499
}
500
501
// get offsets in meters in NED frame
502
bool AP_Follow::get_offsets_ned(Vector3f &offset) const
503
{
504
const Vector3f &off = _offset.get();
505
506
// if offsets are zero or type is NED, simply return offset vector
507
if (off.is_zero() || (_offset_type == AP_FOLLOW_OFFSET_TYPE_NED)) {
508
offset = off;
509
return true;
510
}
511
512
// offset type is relative, exit if we cannot get vehicle's heading
513
float target_heading_deg;
514
if (!get_target_heading_deg(target_heading_deg)) {
515
return false;
516
}
517
518
// rotate offsets from vehicle's perspective to NED
519
offset = rotate_vector(off, target_heading_deg);
520
return true;
521
}
522
523
// rotate 3D vector clockwise by specified angle (in degrees)
524
Vector3f AP_Follow::rotate_vector(const Vector3f &vec, float angle_deg) const
525
{
526
// rotate roll, pitch input from north facing to vehicle's perspective
527
Vector3f ret = vec;
528
ret.xy().rotate(radians(angle_deg));
529
530
return ret;
531
}
532
533
// set recorded distance and bearing to target to zero
534
void AP_Follow::clear_dist_and_bearing_to_target()
535
{
536
_dist_to_target = 0.0f;
537
_bearing_to_target = 0.0f;
538
}
539
540
// get target's estimated location and velocity (in NED), with offsets added
541
bool AP_Follow::get_target_location_and_velocity_ofs(Location &loc, Vector3f &vel_ned) const
542
{
543
Vector3f ofs;
544
if (!get_offsets_ned(ofs) ||
545
!get_target_location_and_velocity(loc, vel_ned)) {
546
return false;
547
}
548
// apply offsets
549
loc.offset(ofs.x, ofs.y);
550
loc.alt -= ofs.z*100;
551
return true;
552
}
553
554
// return true if we have a target
555
bool AP_Follow::have_target(void) const
556
{
557
if (!_enabled) {
558
return false;
559
}
560
561
// check for timeout
562
if ((_last_location_update_ms == 0) || (AP_HAL::millis() - _last_location_update_ms > AP_FOLLOW_TIMEOUT_MS)) {
563
return false;
564
}
565
return true;
566
}
567
568
namespace AP {
569
570
AP_Follow &follow()
571
{
572
return *AP_Follow::get_singleton();
573
}
574
575
}
576
577
#endif // AP_FOLLOW_ENABLED
578
579