forked from ArduPilot/ardupilot
-
Notifications
You must be signed in to change notification settings - Fork 1
/
mode_auto.cpp
2357 lines (2012 loc) · 79.5 KB
/
mode_auto.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
#include "Copter.h"
#if MODE_AUTO_ENABLED
/*
* Init and run calls for auto flight mode
*
* This file contains the implementation for Land, Waypoint navigation and Takeoff from Auto mode
* Command execution code (i.e. command_logic.pde) should:
* a) switch to Auto flight mode with set_mode() function. This will cause auto_init to be called
* b) call one of the three auto initialisation functions: auto_wp_start(), auto_takeoff_start(), auto_land_start()
* c) call one of the verify functions auto_wp_verify(), auto_takeoff_verify, auto_land_verify repeated to check if the command has completed
* The main loop (i.e. fast loop) will call update_flight_modes() which will in turn call auto_run() which, based upon the auto_mode variable will call
* correct auto_wp_run, auto_takeoff_run or auto_land_run to actually implement the feature
*/
/*
* While in the auto flight mode, navigation or do/now commands can be run.
* Code in this file implements the navigation commands
*/
// auto_init - initialise auto controller
bool ModeAuto::init(bool ignore_checks)
{
auto_RTL = false;
if (mission.num_commands() > 1 || ignore_checks) {
// reject switching to auto mode if landed with motors armed but first command is not a takeoff (reduce chance of flips)
if (motors->armed() && copter.ap.land_complete && !mission.starts_with_takeoff_cmd()) {
gcs().send_text(MAV_SEVERITY_CRITICAL, "Auto: Missing Takeoff Cmd");
return false;
}
_mode = SubMode::LOITER;
// stop ROI from carrying over from previous runs of the mission
// To-Do: reset the yaw as part of auto_wp_start when the previous command was not a wp command to remove the need for this special ROI check
if (auto_yaw.mode() == AutoYaw::Mode::ROI) {
auto_yaw.set_mode(AutoYaw::Mode::HOLD);
}
// initialise waypoint and spline controller
wp_nav->wp_and_spline_init();
// initialise desired speed overrides
desired_speed_override = {0, 0, 0};
// set flag to start mission
waiting_to_start = true;
// initialise mission change check (ignore results)
IGNORE_RETURN(mis_change_detector.check_for_mission_change());
// clear guided limits
copter.mode_guided.limit_clear();
// reset flag indicating if pilot has applied roll or pitch inputs during landing
copter.ap.land_repo_active = false;
#if AC_PRECLAND_ENABLED
// initialise precland state machine
copter.precland_statemachine.init();
#endif
return true;
} else {
return false;
}
}
// stop mission when we leave auto mode
void ModeAuto::exit()
{
if (copter.mode_auto.mission.state() == AP_Mission::MISSION_RUNNING) {
copter.mode_auto.mission.stop();
}
#if HAL_MOUNT_ENABLED
copter.camera_mount.set_mode_to_default();
#endif // HAL_MOUNT_ENABLED
auto_RTL = false;
}
// auto_run - runs the auto controller
// should be called at 100hz or more
void ModeAuto::run()
{
// start or update mission
if (waiting_to_start) {
// don't start the mission until we have an origin
Location loc;
if (copter.ahrs.get_origin(loc)) {
// start/resume the mission (based on MIS_RESTART parameter)
mission.start_or_resume();
waiting_to_start = false;
// initialise mission change check (ignore results)
IGNORE_RETURN(mis_change_detector.check_for_mission_change());
}
} else {
// check for mission changes
if (mis_change_detector.check_for_mission_change()) {
// if mission is running restart the current command if it is a waypoint or spline command
if ((mission.state() == AP_Mission::MISSION_RUNNING) && (_mode == SubMode::WP)) {
if (mission.restart_current_nav_cmd()) {
gcs().send_text(MAV_SEVERITY_CRITICAL, "Auto mission changed, restarted command");
} else {
// failed to restart mission for some reason
gcs().send_text(MAV_SEVERITY_CRITICAL, "Auto mission changed but failed to restart command");
}
}
}
mission.update();
}
// call the correct auto controller
switch (_mode) {
case SubMode::TAKEOFF:
takeoff_run();
break;
case SubMode::WP:
case SubMode::CIRCLE_MOVE_TO_EDGE:
wp_run();
break;
case SubMode::LAND:
land_run();
break;
case SubMode::RTL:
rtl_run();
break;
case SubMode::CIRCLE:
circle_run();
break;
case SubMode::NAVGUIDED:
case SubMode::NAV_SCRIPT_TIME:
#if AC_NAV_GUIDED || AP_SCRIPTING_ENABLED
nav_guided_run();
#endif
break;
case SubMode::LOITER:
loiter_run();
break;
case SubMode::LOITER_TO_ALT:
loiter_to_alt_run();
break;
#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED && AC_PAYLOAD_PLACE_ENABLED
case SubMode::NAV_PAYLOAD_PLACE:
payload_place.run();
break;
#endif
case SubMode::NAV_ATTITUDE_TIME:
nav_attitude_time_run();
break;
}
// only pretend to be in auto RTL so long as mission still thinks its in a landing sequence or the mission has completed
const bool auto_rtl_active = mission.get_in_landing_sequence_flag() || mission.get_in_return_path_flag() || mission.state() == AP_Mission::mission_state::MISSION_COMPLETE;
if (auto_RTL && !auto_rtl_active) {
auto_RTL = false;
// log exit from Auto RTL
#if HAL_LOGGING_ENABLED
copter.logger.Write_Mode((uint8_t)copter.flightmode->mode_number(), ModeReason::AUTO_RTL_EXIT);
#endif
}
}
// return true if a position estimate is required
bool ModeAuto::requires_GPS() const
{
// position estimate is required in all sub modes except attitude control
return _mode != SubMode::NAV_ATTITUDE_TIME;
}
// set submode. This may re-trigger the vehicle's EKF failsafe if the new submode requires a position estimate
void ModeAuto::set_submode(SubMode new_submode)
{
// return immediately if the submode has not been changed
if (new_submode == _mode) {
return;
}
// backup old mode
SubMode old_submode = _mode;
// set mode
_mode = new_submode;
// if changing out of the nav-attitude-time submode, recheck the EKF failsafe
// this may trigger a flight mode change if the EKF failsafe is active
if (old_submode == SubMode::NAV_ATTITUDE_TIME) {
copter.failsafe_ekf_recheck();
}
}
bool ModeAuto::option_is_enabled(Option option) const
{
return ((copter.g2.auto_options & (uint32_t)option) != 0);
}
bool ModeAuto::allows_arming(AP_Arming::Method method) const
{
if (auto_RTL) {
return false;
}
return option_is_enabled(Option::AllowArming);
}
#if WEATHERVANE_ENABLED
bool ModeAuto::allows_weathervaning() const
{
return option_is_enabled(Option::AllowWeatherVaning);
}
#endif
// Go straight to landing sequence via DO_LAND_START, if succeeds pretend to be Auto RTL mode
bool ModeAuto::jump_to_landing_sequence_auto_RTL(ModeReason reason)
{
if (!mission.jump_to_landing_sequence(get_stopping_point())) {
LOGGER_WRITE_ERROR(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(Number::AUTO_RTL));
// make sad noise
if (copter.ap.initialised) {
AP_Notify::events.user_mode_change_failed = 1;
}
gcs().send_text(MAV_SEVERITY_WARNING, "Mode change to AUTO RTL failed: No landing sequence found");
return false;
}
return enter_auto_rtl(reason);
}
// Join mission after DO_RETURN_PATH_START waypoint, if succeeds pretend to be Auto RTL mode
bool ModeAuto::return_path_start_auto_RTL(ModeReason reason)
{
if (!mission.jump_to_closest_mission_leg(get_stopping_point())) {
LOGGER_WRITE_ERROR(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(Number::AUTO_RTL));
// make sad noise
if (copter.ap.initialised) {
AP_Notify::events.user_mode_change_failed = 1;
}
gcs().send_text(MAV_SEVERITY_WARNING, "Mode change to AUTO RTL failed: No return path found");
return false;
}
return enter_auto_rtl(reason);
}
// Try join return path else do land start
bool ModeAuto::return_path_or_jump_to_landing_sequence_auto_RTL(ModeReason reason)
{
const Location stopping_point = get_stopping_point();
if (!mission.jump_to_closest_mission_leg(stopping_point) && !mission.jump_to_landing_sequence(stopping_point)) {
LOGGER_WRITE_ERROR(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(Number::AUTO_RTL));
// make sad noise
if (copter.ap.initialised) {
AP_Notify::events.user_mode_change_failed = 1;
}
gcs().send_text(MAV_SEVERITY_WARNING, "Mode change to AUTO RTL failed: No return path or landing sequence found");
return false;
}
return enter_auto_rtl(reason);
}
// Enter auto rtl pseudo mode
bool ModeAuto::enter_auto_rtl(ModeReason reason)
{
mission.set_force_resume(true);
// if not already in auto switch to auto
if ((copter.flightmode == this) || set_mode(Mode::Number::AUTO, reason)) {
auto_RTL = true;
#if HAL_LOGGING_ENABLED
// log entry into AUTO RTL
copter.logger.Write_Mode((uint8_t)copter.flightmode->mode_number(), reason);
#endif
// make happy noise
if (copter.ap.initialised) {
AP_Notify::events.user_mode_change = 1;
}
return true;
}
// mode change failed, revert force resume flag
mission.set_force_resume(false);
LOGGER_WRITE_ERROR(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(Number::AUTO_RTL));
// make sad noise
if (copter.ap.initialised) {
AP_Notify::events.user_mode_change_failed = 1;
}
return false;
}
// lua scripts use this to retrieve the contents of the active command
bool ModeAuto::nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2, int16_t &arg3, int16_t &arg4)
{
#if AP_SCRIPTING_ENABLED
if (_mode == SubMode::NAV_SCRIPT_TIME) {
id = nav_scripting.id;
cmd = nav_scripting.command;
arg1 = nav_scripting.arg1;
arg2 = nav_scripting.arg2;
arg3 = nav_scripting.arg3;
arg4 = nav_scripting.arg4;
return true;
}
#endif
return false;
}
// lua scripts use this to indicate when they have complete the command
void ModeAuto::nav_script_time_done(uint16_t id)
{
#if AP_SCRIPTING_ENABLED
if ((_mode == SubMode::NAV_SCRIPT_TIME) && (id == nav_scripting.id)) {
nav_scripting.done = true;
}
#endif
}
// auto_loiter_start - initialises loitering in auto mode
// returns success/failure because this can be called by exit_mission
bool ModeAuto::loiter_start()
{
// return failure if GPS is bad
if (!copter.position_ok()) {
return false;
}
_mode = SubMode::LOITER;
// calculate stopping point
Vector3f stopping_point;
wp_nav->get_wp_stopping_point(stopping_point);
// initialise waypoint controller target to stopping point
wp_nav->set_wp_destination(stopping_point);
// hold yaw at current heading
auto_yaw.set_mode(AutoYaw::Mode::HOLD);
return true;
}
// auto_rtl_start - initialises RTL in AUTO flight mode
void ModeAuto::rtl_start()
{
// call regular rtl flight mode initialisation and ask it to ignore checks
if (copter.mode_rtl.init(true)) {
set_submode(SubMode::RTL);
} else {
// this should never happen because RTL never fails init if argument is true
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
}
}
// initialise waypoint controller to implement take-off
void ModeAuto::takeoff_start(const Location& dest_loc)
{
if (!copter.current_loc.initialised()) {
// this should never happen because mission commands are not executed until
// the AHRS/EKF origin is set by which time current_loc should also have been set
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
return;
}
// calculate current and target altitudes
// by default current_alt_cm and alt_target_cm are alt-above-EKF-origin
int32_t alt_target_cm;
bool alt_target_terrain = false;
float current_alt_cm = inertial_nav.get_position_z_up_cm();
float terrain_offset; // terrain's altitude in cm above the ekf origin
if ((dest_loc.get_alt_frame() == Location::AltFrame::ABOVE_TERRAIN) && wp_nav->get_terrain_offset(terrain_offset)) {
// subtract terrain offset to convert vehicle's alt-above-ekf-origin to alt-above-terrain
current_alt_cm -= terrain_offset;
// specify alt_target_cm as alt-above-terrain
alt_target_cm = dest_loc.alt;
alt_target_terrain = true;
} else {
// set horizontal target
Location dest(dest_loc);
dest.lat = copter.current_loc.lat;
dest.lng = copter.current_loc.lng;
// get altitude target above EKF origin
if (!dest.get_alt_cm(Location::AltFrame::ABOVE_ORIGIN, alt_target_cm)) {
// this failure could only happen if take-off alt was specified as an alt-above terrain and we have no terrain data
LOGGER_WRITE_ERROR(LogErrorSubsystem::TERRAIN, LogErrorCode::MISSING_TERRAIN_DATA);
// fall back to altitude above current altitude
alt_target_cm = current_alt_cm + dest.alt;
}
}
// sanity check target
int32_t alt_target_min_cm = current_alt_cm + (copter.ap.land_complete ? 100 : 0);
alt_target_cm = MAX(alt_target_cm, alt_target_min_cm);
// initialise yaw
auto_yaw.set_mode(AutoYaw::Mode::HOLD);
// clear i term when we're taking off
pos_control->init_z_controller();
// initialise alt for WP_NAVALT_MIN and set completion alt
auto_takeoff.start(alt_target_cm, alt_target_terrain);
// set submode
set_submode(SubMode::TAKEOFF);
}
// auto_wp_start - initialises waypoint controller to implement flying to a particular destination
bool ModeAuto::wp_start(const Location& dest_loc)
{
// init wpnav and set origin if transitioning from takeoff
if (!wp_nav->is_active()) {
Vector3f stopping_point;
if (_mode == SubMode::TAKEOFF) {
Vector3p takeoff_complete_pos;
if (auto_takeoff.get_completion_pos(takeoff_complete_pos)) {
stopping_point = takeoff_complete_pos.tofloat();
}
}
float des_speed_xy_cm = is_positive(desired_speed_override.xy) ? (desired_speed_override.xy * 100) : 0;
wp_nav->wp_and_spline_init(des_speed_xy_cm, stopping_point);
// override speeds up and down if necessary
if (is_positive(desired_speed_override.up)) {
wp_nav->set_speed_up(desired_speed_override.up * 100.0);
}
if (is_positive(desired_speed_override.down)) {
wp_nav->set_speed_down(desired_speed_override.down * 100.0);
}
}
if (!wp_nav->set_wp_destination_loc(dest_loc)) {
return false;
}
// initialise yaw
// To-Do: reset the yaw only when the previous navigation command is not a WP. this would allow removing the special check for ROI
if (auto_yaw.mode() != AutoYaw::Mode::ROI && !(auto_yaw.mode() == AutoYaw::Mode::FIXED && copter.g.wp_yaw_behavior == WP_YAW_BEHAVIOR_NONE)) {
auto_yaw.set_mode_to_default(false);
}
// set submode
set_submode(SubMode::WP);
return true;
}
// auto_land_start - initialises controller to implement a landing
void ModeAuto::land_start()
{
// set horizontal speed and acceleration limits
pos_control->set_max_speed_accel_xy(wp_nav->get_default_speed_xy(), wp_nav->get_wp_acceleration());
pos_control->set_correction_speed_accel_xy(wp_nav->get_default_speed_xy(), wp_nav->get_wp_acceleration());
// initialise the vertical position controller
if (!pos_control->is_active_xy()) {
pos_control->init_xy_controller();
}
// set vertical speed and acceleration limits
pos_control->set_max_speed_accel_z(wp_nav->get_default_speed_down(), wp_nav->get_default_speed_up(), wp_nav->get_accel_z());
pos_control->set_correction_speed_accel_z(wp_nav->get_default_speed_down(), wp_nav->get_default_speed_up(), wp_nav->get_accel_z());
// initialise the vertical position controller
if (!pos_control->is_active_z()) {
pos_control->init_z_controller();
}
// initialise yaw
auto_yaw.set_mode(AutoYaw::Mode::HOLD);
#if AP_LANDINGGEAR_ENABLED
// optionally deploy landing gear
copter.landinggear.deploy_for_landing();
#endif
// reset flag indicating if pilot has applied roll or pitch inputs during landing
copter.ap.land_repo_active = false;
// this will be set true if prec land is later active
copter.ap.prec_land_active = false;
// set submode
set_submode(SubMode::LAND);
}
// circle_movetoedge_start - initialise waypoint controller to move to edge of a circle with it's center at the specified location
// we assume the caller has performed all required GPS_ok checks
void ModeAuto::circle_movetoedge_start(const Location &circle_center, float radius_m, bool ccw_turn)
{
// set circle center
copter.circle_nav->set_center(circle_center);
// set circle radius
if (!is_zero(radius_m)) {
copter.circle_nav->set_radius_cm(radius_m * 100.0f);
}
// set circle direction by using rate
float current_rate = copter.circle_nav->get_rate();
current_rate = ccw_turn ? -fabsf(current_rate) : fabsf(current_rate);
copter.circle_nav->set_rate(current_rate);
// check our distance from edge of circle
Vector3f circle_edge_neu;
float dist_to_edge;
copter.circle_nav->get_closest_point_on_circle(circle_edge_neu, dist_to_edge);
// if more than 3m then fly to edge
if (dist_to_edge > 300.0f) {
// convert circle_edge_neu to Location
Location circle_edge(circle_edge_neu, Location::AltFrame::ABOVE_ORIGIN);
// convert altitude to same as command
circle_edge.set_alt_cm(circle_center.alt, circle_center.get_alt_frame());
// initialise wpnav to move to edge of circle
if (!wp_nav->set_wp_destination_loc(circle_edge)) {
// failure to set destination can only be because of missing terrain data
copter.failsafe_terrain_on_event();
}
// if we are outside the circle, point at the edge, otherwise hold yaw
const float dist_to_center = get_horizontal_distance_cm(inertial_nav.get_position_xy_cm().topostype(), copter.circle_nav->get_center().xy());
// initialise yaw
// To-Do: reset the yaw only when the previous navigation command is not a WP. this would allow removing the special check for ROI
if (auto_yaw.mode() != AutoYaw::Mode::ROI) {
if (dist_to_center > copter.circle_nav->get_radius() && dist_to_center > 500) {
auto_yaw.set_mode_to_default(false);
} else {
// vehicle is within circle so hold yaw to avoid spinning as we move to edge of circle
auto_yaw.set_mode(AutoYaw::Mode::HOLD);
}
}
// set the submode to move to the edge of the circle
set_submode(SubMode::CIRCLE_MOVE_TO_EDGE);
} else {
circle_start();
}
}
// auto_circle_start - initialises controller to fly a circle in AUTO flight mode
// assumes that circle_nav object has already been initialised with circle center and radius
void ModeAuto::circle_start()
{
// initialise circle controller
copter.circle_nav->init(copter.circle_nav->get_center(), copter.circle_nav->center_is_terrain_alt(), copter.circle_nav->get_rate());
if (auto_yaw.mode() != AutoYaw::Mode::ROI) {
auto_yaw.set_mode(AutoYaw::Mode::CIRCLE);
}
// set submode to circle
set_submode(SubMode::CIRCLE);
}
#if AC_NAV_GUIDED
// auto_nav_guided_start - hand over control to external navigation controller in AUTO mode
void ModeAuto::nav_guided_start()
{
// call regular guided flight mode initialisation
if (!copter.mode_guided.init(true)) {
// this should never happen because guided mode never fails to init
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
return;
}
// initialise guided start time and position as reference for limit checking
copter.mode_guided.limit_init_time_and_pos();
// set submode
set_submode(SubMode::NAVGUIDED);
}
#endif //AC_NAV_GUIDED
bool ModeAuto::is_landing() const
{
switch(_mode) {
case SubMode::LAND:
return true;
case SubMode::RTL:
return copter.mode_rtl.is_landing();
default:
return false;
}
return false;
}
bool ModeAuto::is_taking_off() const
{
return ((_mode == SubMode::TAKEOFF) && !auto_takeoff.complete);
}
#if AC_PAYLOAD_PLACE_ENABLED
// auto_payload_place_start - initialises controller to implement a placing
void PayloadPlace::start_descent()
{
auto *pos_control = copter.pos_control;
auto *wp_nav = copter.wp_nav;
// set horizontal speed and acceleration limits
pos_control->set_max_speed_accel_xy(wp_nav->get_default_speed_xy(), wp_nav->get_wp_acceleration());
pos_control->set_correction_speed_accel_xy(wp_nav->get_default_speed_xy(), wp_nav->get_wp_acceleration());
// initialise the vertical position controller
if (!pos_control->is_active_xy()) {
pos_control->init_xy_controller();
}
// set vertical speed and acceleration limits
pos_control->set_max_speed_accel_z(wp_nav->get_default_speed_down(), wp_nav->get_default_speed_up(), wp_nav->get_accel_z());
pos_control->set_correction_speed_accel_z(wp_nav->get_default_speed_down(), wp_nav->get_default_speed_up(), wp_nav->get_accel_z());
// initialise the vertical position controller
if (!pos_control->is_active_z()) {
pos_control->init_z_controller();
}
// initialise yaw
copter.flightmode->auto_yaw.set_mode(Mode::AutoYaw::Mode::HOLD);
state = PayloadPlace::State::Descent_Start;
}
#endif
// returns true if pilot's yaw input should be used to adjust vehicle's heading
bool ModeAuto::use_pilot_yaw(void) const
{
const bool allow_yaw_option = !option_is_enabled(Option::IgnorePilotYaw);
const bool rtl_allow_yaw = (_mode == SubMode::RTL) && copter.mode_rtl.use_pilot_yaw();
const bool landing = _mode == SubMode::LAND;
return allow_yaw_option || rtl_allow_yaw || landing;
}
bool ModeAuto::set_speed_xy(float speed_xy_cms)
{
copter.wp_nav->set_speed_xy(speed_xy_cms);
desired_speed_override.xy = speed_xy_cms * 0.01;
return true;
}
bool ModeAuto::set_speed_up(float speed_up_cms)
{
copter.wp_nav->set_speed_up(speed_up_cms);
desired_speed_override.up = speed_up_cms * 0.01;
return true;
}
bool ModeAuto::set_speed_down(float speed_down_cms)
{
copter.wp_nav->set_speed_down(speed_down_cms);
desired_speed_override.down = speed_down_cms * 0.01;
return true;
}
// start_command - this function will be called when the ap_mission lib wishes to start a new command
bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd)
{
switch(cmd.id) {
///
/// navigation commands
///
case MAV_CMD_NAV_VTOL_TAKEOFF:
case MAV_CMD_NAV_TAKEOFF: // 22
do_takeoff(cmd);
break;
case MAV_CMD_NAV_WAYPOINT: // 16 Navigate to Waypoint
do_nav_wp(cmd);
break;
case MAV_CMD_NAV_VTOL_LAND:
case MAV_CMD_NAV_LAND: // 21 LAND to Waypoint
do_land(cmd);
break;
case MAV_CMD_NAV_LOITER_UNLIM: // 17 Loiter indefinitely
do_loiter_unlimited(cmd);
break;
case MAV_CMD_NAV_LOITER_TURNS: //18 Loiter N Times
do_circle(cmd);
break;
case MAV_CMD_NAV_LOITER_TIME: // 19
do_loiter_time(cmd);
break;
case MAV_CMD_NAV_LOITER_TO_ALT:
do_loiter_to_alt(cmd);
break;
case MAV_CMD_NAV_RETURN_TO_LAUNCH: //20
do_RTL();
break;
case MAV_CMD_NAV_SPLINE_WAYPOINT: // 82 Navigate to Waypoint using spline
do_spline_wp(cmd);
break;
#if AC_NAV_GUIDED
case MAV_CMD_NAV_GUIDED_ENABLE: // 92 accept navigation commands from external nav computer
do_nav_guided_enable(cmd);
break;
#endif
case MAV_CMD_NAV_DELAY: // 93 Delay the next navigation command
do_nav_delay(cmd);
break;
#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED && AC_PAYLOAD_PLACE_ENABLED
case MAV_CMD_NAV_PAYLOAD_PLACE: // 94 place at Waypoint
do_payload_place(cmd);
break;
#endif
#if AP_SCRIPTING_ENABLED
case MAV_CMD_NAV_SCRIPT_TIME:
do_nav_script_time(cmd);
break;
#endif
case MAV_CMD_NAV_ATTITUDE_TIME:
do_nav_attitude_time(cmd);
break;
//
// conditional commands
//
case MAV_CMD_CONDITION_DELAY: // 112
do_wait_delay(cmd);
break;
case MAV_CMD_CONDITION_DISTANCE: // 114
do_within_distance(cmd);
break;
case MAV_CMD_CONDITION_YAW: // 115
do_yaw(cmd);
break;
///
/// do commands
///
case MAV_CMD_DO_CHANGE_SPEED: // 178
do_change_speed(cmd);
break;
case MAV_CMD_DO_SET_HOME: // 179
do_set_home(cmd);
break;
case MAV_CMD_DO_SET_ROI: // 201
// point the copter and camera at a region of interest (ROI)
do_roi(cmd);
break;
#if HAL_MOUNT_ENABLED
case MAV_CMD_DO_MOUNT_CONTROL: // 205
// point the camera to a specified angle
do_mount_control(cmd);
break;
#endif
#if AC_NAV_GUIDED
case MAV_CMD_DO_GUIDED_LIMITS: // 220 accept guided mode limits
do_guided_limits(cmd);
break;
#endif
#if AP_WINCH_ENABLED
case MAV_CMD_DO_WINCH: // Mission command to control winch
do_winch(cmd);
break;
#endif
case MAV_CMD_DO_RETURN_PATH_START:
case MAV_CMD_DO_LAND_START:
break;
default:
// unable to use the command, allow the vehicle to try the next command
return false;
}
// always return success
return true;
}
// exit_mission - function that is called once the mission completes
void ModeAuto::exit_mission()
{
// play a tone
AP_Notify::events.mission_complete = 1;
// if we are not on the ground switch to loiter or land
if (!copter.ap.land_complete) {
// try to enter loiter but if that fails land
if (!loiter_start()) {
set_mode(Mode::Number::LAND, ModeReason::MISSION_END);
}
} else {
// if we've landed it's safe to disarm
copter.arming.disarm(AP_Arming::Method::MISSIONEXIT);
}
}
// do_guided - start guided mode
bool ModeAuto::do_guided(const AP_Mission::Mission_Command& cmd)
{
// only process guided waypoint if we are in guided mode
if (copter.flightmode->mode_number() != Mode::Number::GUIDED && !(copter.flightmode->mode_number() == Mode::Number::AUTO && _mode == SubMode::NAVGUIDED)) {
return false;
}
// switch to handle different commands
switch (cmd.id) {
case MAV_CMD_NAV_WAYPOINT:
{
// set wp_nav's destination
Location dest(cmd.content.location);
return copter.mode_guided.set_destination(dest);
}
case MAV_CMD_CONDITION_YAW:
do_yaw(cmd);
return true;
default:
// reject unrecognised command
return false;
}
return true;
}
uint32_t ModeAuto::wp_distance() const
{
switch (_mode) {
case SubMode::CIRCLE:
return copter.circle_nav->get_distance_to_target();
case SubMode::WP:
case SubMode::CIRCLE_MOVE_TO_EDGE:
default:
return wp_nav->get_wp_distance_to_destination();
}
}
int32_t ModeAuto::wp_bearing() const
{
switch (_mode) {
case SubMode::CIRCLE:
return copter.circle_nav->get_bearing_to_target();
case SubMode::WP:
case SubMode::CIRCLE_MOVE_TO_EDGE:
default:
return wp_nav->get_wp_bearing_to_destination();
}
}
bool ModeAuto::get_wp(Location& destination) const
{
switch (_mode) {
case SubMode::NAVGUIDED:
return copter.mode_guided.get_wp(destination);
case SubMode::WP:
return wp_nav->get_oa_wp_destination(destination);
case SubMode::RTL:
return copter.mode_rtl.get_wp(destination);
default:
return false;
}
}
/*******************************************************************************
Verify command Handlers
Each type of mission element has a "verify" operation. The verify
operation returns true when the mission element has completed and we
should move onto the next mission element.
Return true if we do not recognize the command so that we move on to the next command
*******************************************************************************/
// verify_command - callback function called from ap-mission at 10hz or higher when a command is being run
// 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
bool ModeAuto::verify_command(const AP_Mission::Mission_Command& cmd)
{
if (copter.flightmode != &copter.mode_auto) {
return false;
}
bool cmd_complete = false;
switch (cmd.id) {
//
// navigation commands
//
case MAV_CMD_NAV_VTOL_TAKEOFF:
case MAV_CMD_NAV_TAKEOFF:
cmd_complete = verify_takeoff();
break;
case MAV_CMD_NAV_WAYPOINT:
cmd_complete = verify_nav_wp(cmd);
break;
case MAV_CMD_NAV_VTOL_LAND:
case MAV_CMD_NAV_LAND:
cmd_complete = verify_land();
break;
#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED && AC_PAYLOAD_PLACE_ENABLED
case MAV_CMD_NAV_PAYLOAD_PLACE:
cmd_complete = payload_place.verify();
break;
#endif
case MAV_CMD_NAV_LOITER_UNLIM:
cmd_complete = verify_loiter_unlimited();
break;
case MAV_CMD_NAV_LOITER_TURNS:
cmd_complete = verify_circle(cmd);
break;
case MAV_CMD_NAV_LOITER_TIME:
cmd_complete = verify_loiter_time(cmd);
break;
case MAV_CMD_NAV_LOITER_TO_ALT:
return verify_loiter_to_alt();
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
cmd_complete = verify_RTL();
break;
case MAV_CMD_NAV_SPLINE_WAYPOINT:
cmd_complete = verify_spline_wp(cmd);
break;
#if AC_NAV_GUIDED
case MAV_CMD_NAV_GUIDED_ENABLE:
cmd_complete = verify_nav_guided_enable(cmd);
break;
#endif
case MAV_CMD_NAV_DELAY:
cmd_complete = verify_nav_delay(cmd);
break;
#if AP_SCRIPTING_ENABLED
case MAV_CMD_NAV_SCRIPT_TIME:
cmd_complete = verify_nav_script_time();
break;
#endif
case MAV_CMD_NAV_ATTITUDE_TIME:
cmd_complete = verify_nav_attitude_time(cmd);
break;
///
/// conditional commands
///
case MAV_CMD_CONDITION_DELAY:
cmd_complete = verify_wait_delay();
break;
case MAV_CMD_CONDITION_DISTANCE:
cmd_complete = verify_within_distance();
break;
case MAV_CMD_CONDITION_YAW:
cmd_complete = verify_yaw();
break;
// do commands (always return true)
case MAV_CMD_DO_CHANGE_SPEED:
case MAV_CMD_DO_SET_HOME:
case MAV_CMD_DO_SET_ROI:
#if HAL_MOUNT_ENABLED
case MAV_CMD_DO_MOUNT_CONTROL:
#endif
#if AC_NAV_GUIDED
case MAV_CMD_DO_GUIDED_LIMITS: