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/Rover/mode_auto.cpp
Views: 1798
1
#include "Rover.h"
2
3
#define AUTO_GUIDED_SEND_TARGET_MS 1000
4
5
bool ModeAuto::_enter()
6
{
7
// fail to enter auto if no mission commands
8
if (mission.num_commands() <= 1) {
9
gcs().send_text(MAV_SEVERITY_NOTICE, "No Mission. Can't set AUTO.");
10
return false;
11
}
12
13
// initialise waypoint navigation library
14
g2.wp_nav.init();
15
16
// other initialisation
17
auto_triggered = false;
18
19
// clear guided limits
20
rover.mode_guided.limit_clear();
21
22
// initialise submode to stop or loiter
23
if (rover.is_boat()) {
24
if (!start_loiter()) {
25
start_stop();
26
}
27
} else {
28
start_stop();
29
}
30
31
// set flag to start mission
32
waiting_to_start = true;
33
34
return true;
35
}
36
37
void ModeAuto::_exit()
38
{
39
// stop running the mission
40
if (mission.state() == AP_Mission::MISSION_RUNNING) {
41
mission.stop();
42
}
43
}
44
45
void ModeAuto::update()
46
{
47
// check if mission exists (due to being cleared while disarmed in AUTO,
48
// if no mission, then stop...needs mode change out of AUTO, mission load,
49
// and change back to AUTO to run a mission at this point
50
if (!hal.util->get_soft_armed() && mission.num_commands() <= 1) {
51
start_stop();
52
}
53
// start or update mission
54
if (waiting_to_start) {
55
// don't start the mission until we have an origin
56
Location loc;
57
if (ahrs.get_origin(loc)) {
58
// start/resume the mission (based on MIS_RESTART parameter)
59
mission.start_or_resume();
60
waiting_to_start = false;
61
62
// initialise mission change check
63
IGNORE_RETURN(mis_change_detector.check_for_mission_change());
64
}
65
} else {
66
// check for mission changes
67
if (mis_change_detector.check_for_mission_change()) {
68
// if mission is running restart the current command if it is a waypoint command
69
if ((mission.state() == AP_Mission::MISSION_RUNNING) && (_submode == SubMode::WP)) {
70
if (mission.restart_current_nav_cmd()) {
71
gcs().send_text(MAV_SEVERITY_CRITICAL, "Auto mission changed, restarted command");
72
} else {
73
// failed to restart mission for some reason
74
gcs().send_text(MAV_SEVERITY_CRITICAL, "Auto mission changed but failed to restart command");
75
}
76
}
77
}
78
79
mission.update();
80
}
81
82
switch (_submode) {
83
case SubMode::WP:
84
{
85
// boats loiter once the waypoint is reached
86
bool keep_navigating = true;
87
if (rover.is_boat() && g2.wp_nav.reached_destination() && !g2.wp_nav.is_fast_waypoint()) {
88
keep_navigating = !start_loiter();
89
}
90
91
// update navigation controller
92
if (keep_navigating) {
93
navigate_to_waypoint();
94
}
95
break;
96
}
97
98
case SubMode::HeadingAndSpeed:
99
{
100
if (!_reached_heading) {
101
// run steering and throttle controllers
102
calc_steering_to_heading(_desired_yaw_cd);
103
calc_throttle(calc_speed_nudge(_desired_speed, is_negative(_desired_speed)), true);
104
// check if we have reached within 5 degrees of target
105
_reached_heading = (fabsf(_desired_yaw_cd - ahrs.yaw_sensor) < 500);
106
} else {
107
// we have reached the destination so stay here
108
if (rover.is_boat()) {
109
if (!start_loiter()) {
110
stop_vehicle();
111
}
112
} else {
113
stop_vehicle();
114
}
115
}
116
break;
117
}
118
119
case SubMode::RTL:
120
rover.mode_rtl.update();
121
break;
122
123
case SubMode::Loiter:
124
rover.mode_loiter.update();
125
break;
126
127
case SubMode::Guided:
128
{
129
// send location target to offboard navigation system
130
send_guided_position_target();
131
rover.mode_guided.update();
132
break;
133
}
134
135
case SubMode::Stop:
136
stop_vehicle();
137
break;
138
139
case SubMode::NavScriptTime:
140
rover.mode_guided.update();
141
break;
142
143
case SubMode::Circle:
144
g2.mode_circle.update();
145
break;
146
}
147
}
148
149
void ModeAuto::calc_throttle(float target_speed, bool avoidance_enabled)
150
{
151
// If not autostarting set the throttle to minimum
152
if (!check_trigger()) {
153
stop_vehicle();
154
return;
155
}
156
Mode::calc_throttle(target_speed, avoidance_enabled);
157
}
158
159
// return heading (in degrees) to target destination (aka waypoint)
160
float ModeAuto::wp_bearing() const
161
{
162
switch (_submode) {
163
case SubMode::WP:
164
return g2.wp_nav.wp_bearing_cd() * 0.01f;
165
case SubMode::HeadingAndSpeed:
166
case SubMode::Stop:
167
return 0.0f;
168
case SubMode::RTL:
169
return rover.mode_rtl.wp_bearing();
170
case SubMode::Loiter:
171
return rover.mode_loiter.wp_bearing();
172
case SubMode::Guided:
173
case SubMode::NavScriptTime:
174
return rover.mode_guided.wp_bearing();
175
case SubMode::Circle:
176
return g2.mode_circle.wp_bearing();
177
}
178
179
// this line should never be reached
180
return 0.0f;
181
}
182
183
// return short-term target heading in degrees (i.e. target heading back to line between waypoints)
184
float ModeAuto::nav_bearing() const
185
{
186
switch (_submode) {
187
case SubMode::WP:
188
return g2.wp_nav.nav_bearing_cd() * 0.01f;
189
case SubMode::HeadingAndSpeed:
190
case SubMode::Stop:
191
return 0.0f;
192
case SubMode::RTL:
193
return rover.mode_rtl.nav_bearing();
194
case SubMode::Loiter:
195
return rover.mode_loiter.nav_bearing();
196
case SubMode::Guided:
197
case SubMode::NavScriptTime:
198
return rover.mode_guided.nav_bearing();
199
case SubMode::Circle:
200
return g2.mode_circle.nav_bearing();
201
}
202
203
// this line should never be reached
204
return 0.0f;
205
}
206
207
// return cross track error (i.e. vehicle's distance from the line between waypoints)
208
float ModeAuto::crosstrack_error() const
209
{
210
switch (_submode) {
211
case SubMode::WP:
212
return g2.wp_nav.crosstrack_error();
213
case SubMode::HeadingAndSpeed:
214
case SubMode::Stop:
215
return 0.0f;
216
case SubMode::RTL:
217
return rover.mode_rtl.crosstrack_error();
218
case SubMode::Loiter:
219
return rover.mode_loiter.crosstrack_error();
220
case SubMode::Guided:
221
case SubMode::NavScriptTime:
222
return rover.mode_guided.crosstrack_error();
223
case SubMode::Circle:
224
return g2.mode_circle.crosstrack_error();
225
}
226
227
// this line should never be reached
228
return 0.0f;
229
}
230
231
// return desired lateral acceleration
232
float ModeAuto::get_desired_lat_accel() const
233
{
234
switch (_submode) {
235
case SubMode::WP:
236
return g2.wp_nav.get_lat_accel();
237
case SubMode::HeadingAndSpeed:
238
case SubMode::Stop:
239
return 0.0f;
240
case SubMode::RTL:
241
return rover.mode_rtl.get_desired_lat_accel();
242
case SubMode::Loiter:
243
return rover.mode_loiter.get_desired_lat_accel();
244
case SubMode::Guided:
245
case SubMode::NavScriptTime:
246
return rover.mode_guided.get_desired_lat_accel();
247
case SubMode::Circle:
248
return g2.mode_circle.get_desired_lat_accel();
249
}
250
251
// this line should never be reached
252
return 0.0f;
253
}
254
255
// return distance (in meters) to destination
256
float ModeAuto::get_distance_to_destination() const
257
{
258
switch (_submode) {
259
case SubMode::WP:
260
return _distance_to_destination;
261
case SubMode::HeadingAndSpeed:
262
case SubMode::Stop:
263
// no valid distance so return zero
264
return 0.0f;
265
case SubMode::RTL:
266
return rover.mode_rtl.get_distance_to_destination();
267
case SubMode::Loiter:
268
return rover.mode_loiter.get_distance_to_destination();
269
case SubMode::Guided:
270
case SubMode::NavScriptTime:
271
return rover.mode_guided.get_distance_to_destination();
272
case SubMode::Circle:
273
return g2.mode_circle.get_distance_to_destination();
274
}
275
276
// this line should never be reached
277
return 0.0f;
278
}
279
280
// get desired location
281
bool ModeAuto::get_desired_location(Location& destination) const
282
{
283
switch (_submode) {
284
case SubMode::WP:
285
if (g2.wp_nav.is_destination_valid()) {
286
destination = g2.wp_nav.get_oa_destination();
287
return true;
288
}
289
return false;
290
case SubMode::HeadingAndSpeed:
291
case SubMode::Stop:
292
// no desired location for this submode
293
return false;
294
case SubMode::RTL:
295
return rover.mode_rtl.get_desired_location(destination);
296
case SubMode::Loiter:
297
return rover.mode_loiter.get_desired_location(destination);
298
case SubMode::Guided:
299
case SubMode::NavScriptTime:
300
return rover.mode_guided.get_desired_location(destination);
301
case SubMode::Circle:
302
return g2.mode_circle.get_desired_location(destination);
303
}
304
305
// we should never reach here but just in case
306
return false;
307
}
308
309
// set desired location to drive to
310
bool ModeAuto::set_desired_location(const Location &destination, Location next_destination)
311
{
312
// call parent
313
if (!Mode::set_desired_location(destination, next_destination)) {
314
return false;
315
}
316
317
_submode = SubMode::WP;
318
319
return true;
320
}
321
322
// return true if vehicle has reached or even passed destination
323
bool ModeAuto::reached_destination() const
324
{
325
switch (_submode) {
326
case SubMode::WP:
327
return g2.wp_nav.reached_destination();
328
break;
329
case SubMode::HeadingAndSpeed:
330
case SubMode::Stop:
331
// always return true because this is the safer option to allow missions to continue
332
return true;
333
break;
334
case SubMode::RTL:
335
return rover.mode_rtl.reached_destination();
336
break;
337
case SubMode::Loiter:
338
return rover.mode_loiter.reached_destination();
339
break;
340
case SubMode::Guided:
341
case SubMode::NavScriptTime:
342
return rover.mode_guided.reached_destination();
343
case SubMode::Circle:
344
return g2.mode_circle.reached_destination();
345
}
346
347
// we should never reach here but just in case, return true to allow missions to continue
348
return true;
349
}
350
351
// set desired speed in m/s
352
bool ModeAuto::set_desired_speed(float speed)
353
{
354
switch (_submode) {
355
case SubMode::WP:
356
case SubMode::Stop:
357
return g2.wp_nav.set_speed_max(speed);
358
case SubMode::HeadingAndSpeed:
359
_desired_speed = speed;
360
return true;
361
case SubMode::RTL:
362
return rover.mode_rtl.set_desired_speed(speed);
363
case SubMode::Loiter:
364
return rover.mode_loiter.set_desired_speed(speed);
365
case SubMode::Guided:
366
case SubMode::NavScriptTime:
367
return rover.mode_guided.set_desired_speed(speed);
368
case SubMode::Circle:
369
return g2.mode_circle.set_desired_speed(speed);
370
}
371
return false;
372
}
373
374
// start RTL (within auto)
375
void ModeAuto::start_RTL()
376
{
377
if (rover.mode_rtl.enter()) {
378
_submode = SubMode::RTL;
379
}
380
}
381
382
// lua scripts use this to retrieve the contents of the active command
383
bool ModeAuto::nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2, int16_t &arg3, int16_t &arg4)
384
{
385
#if AP_SCRIPTING_ENABLED
386
if (_submode == SubMode::NavScriptTime) {
387
id = nav_scripting.id;
388
cmd = nav_scripting.command;
389
arg1 = nav_scripting.arg1;
390
arg2 = nav_scripting.arg2;
391
arg3 = nav_scripting.arg3;
392
arg4 = nav_scripting.arg4;
393
return true;
394
}
395
#endif
396
return false;
397
}
398
399
// lua scripts use this to indicate when they have complete the command
400
void ModeAuto::nav_script_time_done(uint16_t id)
401
{
402
#if AP_SCRIPTING_ENABLED
403
if ((_submode == SubMode::NavScriptTime) && (id == nav_scripting.id)) {
404
nav_scripting.done = true;
405
}
406
#endif
407
}
408
409
// check for triggering of start of auto mode
410
bool ModeAuto::check_trigger(void)
411
{
412
// check for user pressing the auto trigger to off
413
if (auto_triggered && g.auto_trigger_pin != -1 && rover.check_digital_pin(g.auto_trigger_pin) == 1) {
414
gcs().send_text(MAV_SEVERITY_WARNING, "AUTO triggered off");
415
auto_triggered = false;
416
return false;
417
}
418
419
// if already triggered, then return true, so you don't
420
// need to hold the switch down
421
if (auto_triggered) {
422
return true;
423
}
424
425
// return true if auto trigger and kickstart are disabled
426
if (g.auto_trigger_pin == -1 && is_zero(g.auto_kickstart)) {
427
// no trigger configured - let's go!
428
auto_triggered = true;
429
return true;
430
}
431
432
// check if trigger pin has been pushed
433
if (g.auto_trigger_pin != -1 && rover.check_digital_pin(g.auto_trigger_pin) == 0) {
434
gcs().send_text(MAV_SEVERITY_WARNING, "Triggered AUTO with pin");
435
auto_triggered = true;
436
return true;
437
}
438
439
// check if mission is started by giving vehicle a kick with acceleration > AUTO_KICKSTART
440
if (!is_zero(g.auto_kickstart)) {
441
const float xaccel = rover.ins.get_accel().x;
442
if (xaccel >= g.auto_kickstart) {
443
gcs().send_text(MAV_SEVERITY_WARNING, "Triggered AUTO xaccel=%.1f", static_cast<double>(xaccel));
444
auto_triggered = true;
445
return true;
446
}
447
}
448
449
return false;
450
}
451
452
bool ModeAuto::start_loiter()
453
{
454
if (rover.mode_loiter.enter()) {
455
_submode = SubMode::Loiter;
456
return true;
457
}
458
return false;
459
}
460
461
// hand over control to external navigation controller in AUTO mode
462
void ModeAuto::start_guided(const Location& loc)
463
{
464
if (rover.mode_guided.enter()) {
465
_submode = SubMode::Guided;
466
467
// initialise guided start time and position as reference for limit checking
468
rover.mode_guided.limit_init_time_and_location();
469
470
// sanity check target location
471
if ((loc.lat != 0) || (loc.lng != 0)) {
472
guided_target.loc = loc;
473
guided_target.loc.sanitize(rover.current_loc);
474
guided_target.valid = true;
475
} else {
476
guided_target.valid = false;
477
}
478
}
479
}
480
481
// start stopping vehicle as quickly as possible
482
void ModeAuto::start_stop()
483
{
484
_submode = SubMode::Stop;
485
}
486
487
// send latest position target to offboard navigation system
488
void ModeAuto::send_guided_position_target()
489
{
490
if (!guided_target.valid) {
491
return;
492
}
493
494
// send at maximum of 1hz
495
const uint32_t now_ms = AP_HAL::millis();
496
if ((guided_target.last_sent_ms == 0) || (now_ms - guided_target.last_sent_ms > AUTO_GUIDED_SEND_TARGET_MS)) {
497
guided_target.last_sent_ms = now_ms;
498
499
// get system id and component id of offboard navigation system
500
uint8_t sysid;
501
uint8_t compid;
502
mavlink_channel_t chan;
503
if (GCS_MAVLINK::find_by_mavtype(MAV_TYPE_ONBOARD_CONTROLLER, sysid, compid, chan)) {
504
gcs().chan(chan-MAVLINK_COMM_0)->send_set_position_target_global_int(sysid, compid, guided_target.loc);
505
}
506
}
507
508
}
509
510
/********************************************************************************/
511
// Command Event Handlers
512
/********************************************************************************/
513
bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd)
514
{
515
switch (cmd.id) {
516
case MAV_CMD_NAV_WAYPOINT: // Navigate to Waypoint
517
return do_nav_wp(cmd, false);
518
519
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
520
do_RTL();
521
break;
522
523
case MAV_CMD_NAV_LOITER_UNLIM: // Loiter indefinitely
524
case MAV_CMD_NAV_LOITER_TIME: // Loiter for specified time
525
return do_nav_wp(cmd, true);
526
527
case MAV_CMD_NAV_LOITER_TURNS:
528
return do_circle(cmd);
529
530
case MAV_CMD_NAV_GUIDED_ENABLE: // accept navigation commands from external nav computer
531
do_nav_guided_enable(cmd);
532
break;
533
534
case MAV_CMD_NAV_SET_YAW_SPEED:
535
do_nav_set_yaw_speed(cmd);
536
break;
537
538
case MAV_CMD_NAV_DELAY: // 93 Delay the next navigation command
539
do_nav_delay(cmd);
540
break;
541
542
#if AP_SCRIPTING_ENABLED
543
case MAV_CMD_NAV_SCRIPT_TIME:
544
do_nav_script_time(cmd);
545
break;
546
#endif
547
548
// Conditional commands
549
case MAV_CMD_CONDITION_DELAY:
550
do_wait_delay(cmd);
551
break;
552
553
case MAV_CMD_CONDITION_DISTANCE:
554
do_within_distance(cmd);
555
break;
556
557
// Do commands
558
case MAV_CMD_DO_CHANGE_SPEED:
559
do_change_speed(cmd);
560
break;
561
562
case MAV_CMD_DO_SET_HOME:
563
do_set_home(cmd);
564
break;
565
566
#if HAL_MOUNT_ENABLED
567
// Sets the region of interest (ROI) for a sensor set or the
568
// vehicle itself. This can then be used by the vehicles control
569
// system to control the vehicle attitude and the attitude of various
570
// devices such as cameras.
571
// |Region of interest mode. (see MAV_ROI enum)| Waypoint index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple cameras etc.)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z|
572
case MAV_CMD_DO_SET_ROI:
573
if (cmd.content.location.alt == 0 && cmd.content.location.lat == 0 && cmd.content.location.lng == 0) {
574
// switch off the camera tracking if enabled
575
if (rover.camera_mount.get_mode() == MAV_MOUNT_MODE_GPS_POINT) {
576
rover.camera_mount.set_mode_to_default();
577
}
578
} else {
579
// send the command to the camera mount
580
rover.camera_mount.set_roi_target(cmd.content.location);
581
}
582
break;
583
#endif
584
585
case MAV_CMD_DO_SET_REVERSE:
586
do_set_reverse(cmd);
587
break;
588
589
case MAV_CMD_DO_GUIDED_LIMITS:
590
do_guided_limits(cmd);
591
break;
592
593
default:
594
// return false for unhandled commands
595
return false;
596
}
597
598
// if we got this far we must have been successful
599
return true;
600
}
601
602
// exit_mission - callback function called from ap-mission when the mission has completed
603
void ModeAuto::exit_mission()
604
{
605
// play a tone
606
AP_Notify::events.mission_complete = 1;
607
// send message
608
gcs().send_text(MAV_SEVERITY_NOTICE, "Mission Complete");
609
610
switch ((DoneBehaviour)g2.mis_done_behave) {
611
case DoneBehaviour::HOLD:
612
// the default "start_stop" behaviour is used
613
break;
614
case DoneBehaviour::LOITER:
615
if (start_loiter()) {
616
return;
617
}
618
break;
619
case DoneBehaviour::ACRO:
620
if (rover.set_mode(rover.mode_acro, ModeReason::MISSION_END)) {
621
return;
622
}
623
break;
624
case DoneBehaviour::MANUAL:
625
if (rover.set_mode(rover.mode_manual, ModeReason::MISSION_END)) {
626
return;
627
}
628
break;
629
}
630
631
start_stop();
632
}
633
634
// verify_command_callback - callback function called from ap-mission at 10hz or higher when a command is being run
635
// we double check that the flight mode is AUTO to avoid the possibility of ap-mission triggering actions while we're not in AUTO mode
636
bool ModeAuto::verify_command_callback(const AP_Mission::Mission_Command& cmd)
637
{
638
const bool cmd_complete = verify_command(cmd);
639
640
// send message to GCS
641
if (cmd_complete) {
642
gcs().send_mission_item_reached_message(cmd.index);
643
}
644
645
return cmd_complete;
646
}
647
648
/*******************************************************************************
649
Verify command Handlers
650
651
Each type of mission element has a "verify" operation. The verify
652
operation returns true when the mission element has completed and we
653
should move onto the next mission element.
654
Return true if we do not recognize the command so that we move on to the next command
655
*******************************************************************************/
656
657
bool ModeAuto::verify_command(const AP_Mission::Mission_Command& cmd)
658
{
659
switch (cmd.id) {
660
case MAV_CMD_NAV_WAYPOINT:
661
return verify_nav_wp(cmd);
662
663
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
664
return verify_RTL();
665
666
case MAV_CMD_NAV_LOITER_UNLIM:
667
return verify_loiter_unlimited(cmd);
668
669
case MAV_CMD_NAV_LOITER_TURNS:
670
return verify_circle(cmd);
671
672
case MAV_CMD_NAV_LOITER_TIME:
673
return verify_loiter_time(cmd);
674
675
case MAV_CMD_NAV_GUIDED_ENABLE:
676
return verify_nav_guided_enable(cmd);
677
678
case MAV_CMD_NAV_DELAY:
679
return verify_nav_delay(cmd);
680
681
#if AP_SCRIPTING_ENABLED
682
case MAV_CMD_NAV_SCRIPT_TIME:
683
return verify_nav_script_time();
684
#endif
685
686
case MAV_CMD_CONDITION_DELAY:
687
return verify_wait_delay();
688
689
case MAV_CMD_CONDITION_DISTANCE:
690
return verify_within_distance();
691
692
case MAV_CMD_NAV_SET_YAW_SPEED:
693
return verify_nav_set_yaw_speed();
694
695
// do commands (always return true)
696
case MAV_CMD_DO_CHANGE_SPEED:
697
case MAV_CMD_DO_SET_HOME:
698
case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
699
case MAV_CMD_DO_SET_ROI:
700
case MAV_CMD_DO_SET_REVERSE:
701
case MAV_CMD_DO_FENCE_ENABLE:
702
case MAV_CMD_DO_GUIDED_LIMITS:
703
return true;
704
705
default:
706
// error message
707
gcs().send_text(MAV_SEVERITY_WARNING, "Skipping invalid cmd #%i", cmd.id);
708
// return true if we do not recognize the command so that we move on to the next command
709
return true;
710
}
711
}
712
713
/********************************************************************************/
714
// Nav (Must) commands
715
/********************************************************************************/
716
717
void ModeAuto::do_RTL(void)
718
{
719
// start rtl in auto mode
720
start_RTL();
721
}
722
723
bool ModeAuto::do_nav_wp(const AP_Mission::Mission_Command& cmd, bool always_stop_at_destination)
724
{
725
// retrieve and sanitize target location
726
Location cmdloc = cmd.content.location;
727
cmdloc.sanitize(rover.current_loc);
728
729
// delayed stored in p1 in seconds
730
loiter_duration = ((int16_t) cmd.p1 < 0) ? 0 : cmd.p1;
731
loiter_start_time = 0;
732
if (loiter_duration > 0) {
733
always_stop_at_destination = true;
734
}
735
736
// do not add next wp if there are no more navigation commands
737
AP_Mission::Mission_Command next_cmd;
738
if (always_stop_at_destination || !mission.get_next_nav_cmd(cmd.index+1, next_cmd)) {
739
// single destination
740
if (!set_desired_location(cmdloc)) {
741
return false;
742
}
743
} else {
744
// retrieve and sanitize next destination location
745
Location next_cmdloc = next_cmd.content.location;
746
next_cmdloc.sanitize(cmdloc);
747
if (!set_desired_location(cmdloc, next_cmdloc)) {
748
return false;
749
}
750
}
751
752
// just starting so we haven't previously reached the waypoint
753
previously_reached_wp = false;
754
755
return true;
756
}
757
758
// do_nav_delay - Delay the next navigation command
759
void ModeAuto::do_nav_delay(const AP_Mission::Mission_Command& cmd)
760
{
761
nav_delay_time_start_ms = millis();
762
763
// boats loiter, cars and balancebots stop
764
if (rover.is_boat()) {
765
if (!start_loiter()) {
766
start_stop();
767
}
768
} else {
769
start_stop();
770
}
771
772
if (cmd.content.nav_delay.seconds > 0) {
773
// relative delay
774
nav_delay_time_max_ms = cmd.content.nav_delay.seconds * 1000; // convert seconds to milliseconds
775
} else {
776
// absolute delay to utc time
777
#if AP_RTC_ENABLED
778
nav_delay_time_max_ms = AP::rtc().get_time_utc(cmd.content.nav_delay.hour_utc, cmd.content.nav_delay.min_utc, cmd.content.nav_delay.sec_utc, 0);
779
#else
780
nav_delay_time_max_ms = 0;
781
#endif
782
}
783
gcs().send_text(MAV_SEVERITY_INFO, "Delaying %u sec", (unsigned)(nav_delay_time_max_ms/1000));
784
}
785
786
// start guided within auto to allow external navigation system to control vehicle
787
void ModeAuto::do_nav_guided_enable(const AP_Mission::Mission_Command& cmd)
788
{
789
if (cmd.p1 > 0) {
790
start_guided(cmd.content.location);
791
}
792
}
793
794
// do_set_yaw_speed - turn to a specified heading and achieve a given speed
795
void ModeAuto::do_nav_set_yaw_speed(const AP_Mission::Mission_Command& cmd)
796
{
797
float desired_heading_cd;
798
799
// get final angle, 1 = Relative, 0 = Absolute
800
if (cmd.content.set_yaw_speed.relative_angle > 0) {
801
// relative angle
802
desired_heading_cd = wrap_180_cd(ahrs.yaw_sensor + cmd.content.set_yaw_speed.angle_deg * 100.0f);
803
} else {
804
// absolute angle
805
desired_heading_cd = cmd.content.set_yaw_speed.angle_deg * 100.0f;
806
}
807
808
// set targets
809
const float speed_max = g2.wp_nav.get_default_speed();
810
_desired_speed = constrain_float(cmd.content.set_yaw_speed.speed, -speed_max, speed_max);
811
_desired_yaw_cd = desired_heading_cd;
812
_reached_heading = false;
813
_submode = SubMode::HeadingAndSpeed;
814
}
815
816
/********************************************************************************/
817
// Verify Nav (Must) commands
818
/********************************************************************************/
819
bool ModeAuto::verify_nav_wp(const AP_Mission::Mission_Command& cmd)
820
{
821
// exit immediately if we haven't reached the destination
822
if (!reached_destination()) {
823
return false;
824
}
825
826
// Check if this is the first time we have noticed reaching the waypoint
827
if (!previously_reached_wp) {
828
previously_reached_wp = true;
829
830
// check if we are loitering at this waypoint - the message sent to the GCS is different
831
if (loiter_duration > 0) {
832
// send message including loiter time
833
gcs().send_text(MAV_SEVERITY_INFO, "Reached waypoint #%u. Loiter for %u seconds",
834
(unsigned int)cmd.index,
835
(unsigned int)loiter_duration);
836
// record the current time i.e. start timer
837
loiter_start_time = millis();
838
} else {
839
// send simpler message to GCS
840
gcs().send_text(MAV_SEVERITY_INFO, "Reached waypoint #%u", (unsigned int)cmd.index);
841
}
842
}
843
844
// Check if we have loitered long enough
845
if (loiter_duration == 0) {
846
return true;
847
} else {
848
return (((millis() - loiter_start_time) / 1000) >= loiter_duration);
849
}
850
}
851
852
// verify_nav_delay - check if we have waited long enough
853
bool ModeAuto::verify_nav_delay(const AP_Mission::Mission_Command& cmd)
854
{
855
if (millis() - nav_delay_time_start_ms > nav_delay_time_max_ms) {
856
nav_delay_time_max_ms = 0;
857
return true;
858
}
859
860
return false;
861
}
862
863
bool ModeAuto::verify_RTL() const
864
{
865
return reached_destination();
866
}
867
868
bool ModeAuto::verify_loiter_unlimited(const AP_Mission::Mission_Command& cmd)
869
{
870
verify_nav_wp(cmd);
871
return false;
872
}
873
874
// verify_loiter_time - check if we have loitered long enough
875
bool ModeAuto::verify_loiter_time(const AP_Mission::Mission_Command& cmd)
876
{
877
const bool result = verify_nav_wp(cmd);
878
if (result) {
879
gcs().send_text(MAV_SEVERITY_WARNING, "Finished active loiter");
880
}
881
return result;
882
}
883
884
// check if guided has completed
885
bool ModeAuto::verify_nav_guided_enable(const AP_Mission::Mission_Command& cmd)
886
{
887
// if we failed to enter guided or this command disables guided
888
// return true so we move to next command
889
if (_submode != SubMode::Guided || cmd.p1 == 0) {
890
return true;
891
}
892
893
// if a location target was set, return true once vehicle is close
894
if (guided_target.valid) {
895
if (rover.current_loc.get_distance(guided_target.loc) <= g2.wp_nav.get_radius()) {
896
return true;
897
}
898
}
899
900
// guided command complete once a limit is breached
901
return rover.mode_guided.limit_breached();
902
}
903
904
// verify_yaw - return true if we have reached the desired heading
905
bool ModeAuto::verify_nav_set_yaw_speed()
906
{
907
if (_submode == SubMode::HeadingAndSpeed) {
908
return _reached_heading;
909
}
910
// we should never reach here but just in case, return true to allow missions to continue
911
return true;
912
}
913
914
bool ModeAuto::do_circle(const AP_Mission::Mission_Command& cmd)
915
{
916
// retrieve and sanitize target location
917
Location circle_center = cmd.content.location;
918
circle_center.sanitize(rover.current_loc);
919
920
// calculate radius
921
uint16_t circle_radius_m = HIGHBYTE(cmd.p1); // circle radius held in high byte of p1
922
if (cmd.id == MAV_CMD_NAV_LOITER_TURNS &&
923
cmd.type_specific_bits & (1U << 0)) {
924
// special storage handling allows for larger radii
925
circle_radius_m *= 10;
926
}
927
928
// initialise circle mode
929
if (g2.mode_circle.set_center(circle_center, circle_radius_m, cmd.content.location.loiter_ccw)) {
930
_submode = SubMode::Circle;
931
return true;
932
}
933
return false;
934
}
935
936
bool ModeAuto::verify_circle(const AP_Mission::Mission_Command& cmd)
937
{
938
const float turns = cmd.get_loiter_turns();
939
// check if we have completed circling
940
return ((g2.mode_circle.get_angle_total_rad() / M_2PI) >= turns);
941
}
942
943
/********************************************************************************/
944
// Condition (May) commands
945
/********************************************************************************/
946
947
void ModeAuto::do_wait_delay(const AP_Mission::Mission_Command& cmd)
948
{
949
condition_start = millis();
950
condition_value = static_cast<int32_t>(cmd.content.delay.seconds * 1000); // convert seconds to milliseconds
951
}
952
953
void ModeAuto::do_within_distance(const AP_Mission::Mission_Command& cmd)
954
{
955
condition_value = cmd.content.distance.meters;
956
}
957
958
/********************************************************************************/
959
// Verify Condition (May) commands
960
/********************************************************************************/
961
962
bool ModeAuto::verify_wait_delay()
963
{
964
if (static_cast<uint32_t>(millis() - condition_start) > static_cast<uint32_t>(condition_value)) {
965
condition_value = 0;
966
return true;
967
}
968
return false;
969
}
970
971
bool ModeAuto::verify_within_distance()
972
{
973
if (get_distance_to_destination() < condition_value) {
974
condition_value = 0;
975
return true;
976
}
977
return false;
978
}
979
980
981
/********************************************************************************/
982
// Do (Now) commands
983
/********************************************************************************/
984
985
void ModeAuto::do_change_speed(const AP_Mission::Mission_Command& cmd)
986
{
987
// set speed for active mode
988
if (set_desired_speed(cmd.content.speed.target_ms)) {
989
gcs().send_text(MAV_SEVERITY_INFO, "speed: %.1f m/s", static_cast<double>(cmd.content.speed.target_ms));
990
}
991
}
992
993
void ModeAuto::do_set_home(const AP_Mission::Mission_Command& cmd)
994
{
995
if (cmd.p1 == 1 && rover.have_position) {
996
if (!rover.set_home_to_current_location(false)) {
997
// ignored...
998
}
999
} else {
1000
if (!rover.set_home(cmd.content.location, false)) {
1001
// ignored...
1002
}
1003
}
1004
}
1005
1006
void ModeAuto::do_set_reverse(const AP_Mission::Mission_Command& cmd)
1007
{
1008
set_reversed(cmd.p1 == 1);
1009
}
1010
1011
// set timeout and position limits for guided within auto
1012
void ModeAuto::do_guided_limits(const AP_Mission::Mission_Command& cmd)
1013
{
1014
rover.mode_guided.limit_set(
1015
cmd.p1 * 1000, // convert seconds to ms
1016
cmd.content.guided_limits.horiz_max);
1017
}
1018
1019
#if AP_SCRIPTING_ENABLED
1020
// start accepting position, velocity and acceleration targets from lua scripts
1021
void ModeAuto::do_nav_script_time(const AP_Mission::Mission_Command& cmd)
1022
{
1023
// call regular guided flight mode initialisation
1024
if (rover.mode_guided.enter()) {
1025
_submode = SubMode::NavScriptTime;
1026
nav_scripting.done = false;
1027
nav_scripting.id++;
1028
nav_scripting.start_ms = millis();
1029
nav_scripting.command = cmd.content.nav_script_time.command;
1030
nav_scripting.timeout_s = cmd.content.nav_script_time.timeout_s;
1031
nav_scripting.arg1 = cmd.content.nav_script_time.arg1.get();
1032
nav_scripting.arg2 = cmd.content.nav_script_time.arg2.get();
1033
nav_scripting.arg3 = cmd.content.nav_script_time.arg3;
1034
nav_scripting.arg4 = cmd.content.nav_script_time.arg4;
1035
} else {
1036
// for safety we set nav_scripting to done to protect against the mission getting stuck
1037
nav_scripting.done = true;
1038
}
1039
}
1040
1041
// check if verify_nav_script_time command has completed
1042
bool ModeAuto::verify_nav_script_time()
1043
{
1044
// if done or timeout then return true
1045
if (nav_scripting.done ||
1046
((nav_scripting.timeout_s > 0) &&
1047
(AP_HAL::millis() - nav_scripting.start_ms) > (nav_scripting.timeout_s * 1000))) {
1048
return true;
1049
}
1050
return false;
1051
}
1052
#endif
1053
1054