forked from PX4/PX4-Autopilot
/
mission.cpp
1832 lines (1452 loc) · 61.5 KB
/
mission.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
/****************************************************************************
*
* Copyright (c) 2013-2018 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file navigator_mission.cpp
*
* Helper class to access missions
*
* @author Julian Oes <julian@oes.ch>
* @author Thomas Gubler <thomasgubler@gmail.com>
* @author Anton Babushkin <anton.babushkin@me.com>
* @author Ban Siesta <bansiesta@gmail.com>
* @author Simon Wilks <simon@uaventure.com>
* @author Andreas Antener <andreas@uaventure.com>
* @author Sander Smeets <sander@droneslab.com>
* @author Lorenz Meier <lorenz@px4.io>
*/
#include "mission.h"
#include "navigator.h"
#include <string.h>
#include <drivers/drv_hrt.h>
#include <dataman/dataman.h>
#include <systemlib/mavlink_log.h>
#include <systemlib/err.h>
#include <lib/ecl/geo/geo.h>
#include <lib/mathlib/mathlib.h>
#include <navigator/navigation.h>
#include <uORB/uORB.h>
#include <uORB/topics/mission.h>
#include <uORB/topics/mission_result.h>
using matrix::wrap_pi;
Mission::Mission(Navigator *navigator) :
MissionBlock(navigator),
ModuleParams(navigator)
{
}
void
Mission::on_inactive()
{
/* We need to reset the mission cruising speed, otherwise the
* mission velocity which might have been set using mission items
* is used for missions such as RTL. */
_navigator->set_cruising_speed();
/* Without home a mission can't be valid yet anyway, let's wait. */
if (!_navigator->home_position_valid()) {
return;
}
if (_inited) {
bool offboard_updated = false;
orb_check(_navigator->get_offboard_mission_sub(), &offboard_updated);
if (offboard_updated) {
update_offboard_mission();
if (_mission_type == MISSION_TYPE_NONE && _offboard_mission.count > 0) {
_mission_type = MISSION_TYPE_OFFBOARD;
}
}
/* reset the current offboard mission if needed */
if (need_to_reset_mission(false)) {
reset_offboard_mission(_offboard_mission);
update_offboard_mission();
_navigator->reset_cruising_speed();
}
} else {
/* load missions from storage */
mission_s mission_state = {};
dm_lock(DM_KEY_MISSION_STATE);
/* read current state */
int read_res = dm_read(DM_KEY_MISSION_STATE, 0, &mission_state, sizeof(mission_s));
dm_unlock(DM_KEY_MISSION_STATE);
if (read_res == sizeof(mission_s)) {
_offboard_mission.dataman_id = mission_state.dataman_id;
_offboard_mission.count = mission_state.count;
_current_offboard_mission_index = mission_state.current_seq;
// find and store landing start marker (if available)
find_offboard_land_start();
}
/* On init let's check the mission, maybe there is already one available. */
check_mission_valid(false);
_inited = true;
}
/* require takeoff after non-loiter or landing */
if (!_navigator->get_can_loiter_at_sp() || _navigator->get_land_detected()->landed) {
_need_takeoff = true;
}
/* reset so current mission item gets restarted if mission was paused */
_work_item_type = WORK_ITEM_TYPE_DEFAULT;
/* reset so MISSION_ITEM_REACHED isn't published */
_navigator->get_mission_result()->seq_reached = -1;
}
void
Mission::on_inactivation()
{
// Disable camera trigger
vehicle_command_s cmd = {};
cmd.command = vehicle_command_s::VEHICLE_CMD_DO_TRIGGER_CONTROL;
// Pause trigger
cmd.param1 = -1.0f;
cmd.param3 = 1.0f;
_navigator->publish_vehicle_cmd(&cmd);
}
void
Mission::on_activation()
{
if (_mission_waypoints_changed) {
// do not set the closest mission item in the normal mission mode
if (_mission_execution_mode != mission_result_s::MISSION_EXECUTION_MODE_NORMAL) {
_current_offboard_mission_index = index_closest_mission_item();
}
_mission_waypoints_changed = false;
}
// we already reset the mission items
_execution_mode_changed = false;
set_mission_items();
// unpause triggering if it was paused
vehicle_command_s cmd = {};
cmd.command = vehicle_command_s::VEHICLE_CMD_DO_TRIGGER_CONTROL;
// unpause trigger
cmd.param1 = -1.0f;
cmd.param3 = 0.0f;
_navigator->publish_vehicle_cmd(&cmd);
}
void
Mission::on_active()
{
check_mission_valid(false);
/* check if anything has changed */
bool offboard_updated = false;
orb_check(_navigator->get_offboard_mission_sub(), &offboard_updated);
if (offboard_updated) {
update_offboard_mission();
}
/* reset the current offboard mission if needed */
if (need_to_reset_mission(true)) {
reset_offboard_mission(_offboard_mission);
update_offboard_mission();
_navigator->reset_cruising_speed();
offboard_updated = true;
}
_mission_changed = false;
/* reset mission items if needed */
if (offboard_updated || _mission_waypoints_changed || _execution_mode_changed) {
if (_mission_waypoints_changed) {
// do not set the closest mission item in the normal mission mode
if (_mission_execution_mode != mission_result_s::MISSION_EXECUTION_MODE_NORMAL) {
_current_offboard_mission_index = index_closest_mission_item();
}
_mission_waypoints_changed = false;
}
_execution_mode_changed = false;
set_mission_items();
}
/* lets check if we reached the current mission item */
if (_mission_type != MISSION_TYPE_NONE && is_mission_item_reached()) {
/* If we just completed a takeoff which was inserted before the right waypoint,
there is no need to report that we reached it because we didn't. */
if (_work_item_type != WORK_ITEM_TYPE_TAKEOFF) {
set_mission_item_reached();
}
if (_mission_item.autocontinue) {
/* switch to next waypoint if 'autocontinue' flag set */
advance_mission();
set_mission_items();
}
} else if (_mission_type != MISSION_TYPE_NONE && _param_altmode.get() == MISSION_ALTMODE_FOH) {
altitude_sp_foh_update();
} else {
/* if waypoint position reached allow loiter on the setpoint */
if (_waypoint_position_reached && _mission_item.nav_cmd != NAV_CMD_IDLE) {
_navigator->set_can_loiter_at_sp(true);
}
}
/* check if a cruise speed change has been commanded */
if (_mission_type != MISSION_TYPE_NONE) {
cruising_speed_sp_update();
}
/* see if we need to update the current yaw heading */
if (_navigator->get_vroi().mode == vehicle_roi_s::ROI_LOCATION
|| (_param_yawmode.get() != MISSION_YAWMODE_NONE
&& _param_yawmode.get() < MISSION_YAWMODE_MAX
&& _mission_type != MISSION_TYPE_NONE)
|| _navigator->get_vstatus()->is_vtol) {
heading_sp_update();
}
/* check if landing needs to be aborted */
if ((_mission_item.nav_cmd == NAV_CMD_LAND)
&& (_navigator->abort_landing())) {
do_abort_landing();
}
if (_work_item_type == WORK_ITEM_TYPE_PRECISION_LAND) {
// switch out of precision land once landed
if (_navigator->get_land_detected()->landed) {
_navigator->get_precland()->on_inactivation();
_work_item_type = WORK_ITEM_TYPE_DEFAULT;
} else {
_navigator->get_precland()->on_active();
}
}
}
bool
Mission::set_current_offboard_mission_index(uint16_t index)
{
if (_navigator->get_mission_result()->valid &&
(index != _current_offboard_mission_index) && (index < _offboard_mission.count)) {
_current_offboard_mission_index = index;
// a mission offboard index is set manually which has the higher priority than the closest mission item
// as it is set by the user
_mission_waypoints_changed = false;
// update mission items if already in active mission
if (_navigator->is_planned_mission()) {
// prevent following "previous - current" line
_navigator->get_position_setpoint_triplet()->previous.valid = false;
_navigator->get_position_setpoint_triplet()->current.valid = false;
_navigator->get_position_setpoint_triplet()->next.valid = false;
set_mission_items();
}
return true;
}
return false;
}
void
Mission::set_closest_item_as_current()
{
_current_offboard_mission_index = index_closest_mission_item();
}
void
Mission::set_execution_mode(const uint8_t mode)
{
if (_mission_execution_mode != mode) {
_execution_mode_changed = true;
_navigator->get_mission_result()->execution_mode = mode;
switch (_mission_execution_mode) {
case mission_result_s::MISSION_EXECUTION_MODE_NORMAL:
case mission_result_s::MISSION_EXECUTION_MODE_FAST_FORWARD:
if (mode == mission_result_s::MISSION_EXECUTION_MODE_REVERSE) {
// command a transition if in vtol mc mode
if (_navigator->get_vstatus()->is_rotary_wing &&
_navigator->get_vstatus()->is_vtol &&
!_navigator->get_land_detected()->landed) {
set_vtol_transition_item(&_mission_item, vtol_vehicle_status_s::VEHICLE_VTOL_STATE_FW);
position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet();
pos_sp_triplet->previous = pos_sp_triplet->current;
generate_waypoint_from_heading(&pos_sp_triplet->current, _mission_item.yaw);
_navigator->set_position_setpoint_triplet_updated();
issue_command(_mission_item);
}
if (_mission_type == MISSION_TYPE_NONE && _offboard_mission.count > 0) {
_mission_type = MISSION_TYPE_OFFBOARD;
}
if (_current_offboard_mission_index > _offboard_mission.count - 1) {
_current_offboard_mission_index = _offboard_mission.count - 1;
} else if (_current_offboard_mission_index > 0) {
--_current_offboard_mission_index;
}
_work_item_type = WORK_ITEM_TYPE_DEFAULT;
}
break;
case mission_result_s::MISSION_EXECUTION_MODE_REVERSE:
if ((mode == mission_result_s::MISSION_EXECUTION_MODE_NORMAL) ||
(mode == mission_result_s::MISSION_EXECUTION_MODE_FAST_FORWARD)) {
// handle switch from reverse to forward mission
if (_current_offboard_mission_index < 0) {
_current_offboard_mission_index = 0;
} else if (_current_offboard_mission_index < _offboard_mission.count - 1) {
++_current_offboard_mission_index;
}
_work_item_type = WORK_ITEM_TYPE_DEFAULT;
}
break;
}
_mission_execution_mode = mode;
}
}
bool
Mission::find_offboard_land_start()
{
/* return true if a MAV_CMD_DO_LAND_START is found and internally save the index
* return false if not found
*
* TODO: implement full spec and find closest landing point geographically
*/
const dm_item_t dm_current = (dm_item_t)_offboard_mission.dataman_id;
for (size_t i = 0; i < _offboard_mission.count; i++) {
struct mission_item_s missionitem = {};
const ssize_t len = sizeof(missionitem);
if (dm_read(dm_current, i, &missionitem, len) != len) {
/* not supposed to happen unless the datamanager can't access the SD card, etc. */
PX4_ERR("dataman read failure");
break;
}
if ((missionitem.nav_cmd == NAV_CMD_DO_LAND_START) ||
((missionitem.nav_cmd == NAV_CMD_VTOL_LAND) && _navigator->get_vstatus()->is_vtol) ||
(missionitem.nav_cmd == NAV_CMD_LAND)) {
_land_start_available = true;
_land_start_index = i;
return true;
}
}
_land_start_available = false;
return false;
}
bool
Mission::land_start()
{
// if not currently landing, jump to do_land_start
if (_land_start_available) {
if (landing()) {
return true;
} else {
set_current_offboard_mission_index(get_land_start_index());
return landing();
}
}
return false;
}
bool
Mission::landing()
{
// vehicle is currently landing if
// mission valid, still flying, and in the landing portion of mission
const bool mission_valid = _navigator->get_mission_result()->valid;
const bool on_landing_stage = _land_start_available && (_current_offboard_mission_index >= get_land_start_index());
return mission_valid && on_landing_stage;
}
void
Mission::update_offboard_mission()
{
bool failed = true;
/* reset triplets */
_navigator->reset_triplets();
struct mission_s old_offboard_mission = _offboard_mission;
if (orb_copy(ORB_ID(mission), _navigator->get_offboard_mission_sub(), &_offboard_mission) == OK) {
/* determine current index */
if (_offboard_mission.current_seq >= 0 && _offboard_mission.current_seq < (int)_offboard_mission.count) {
_current_offboard_mission_index = _offboard_mission.current_seq;
} else {
/* if less items available, reset to first item */
if (_current_offboard_mission_index >= (int)_offboard_mission.count) {
_current_offboard_mission_index = 0;
} else if (_current_offboard_mission_index < 0) {
/* if not initialized, set it to 0 */
_current_offboard_mission_index = 0;
}
/* otherwise, just leave it */
}
check_mission_valid(true);
failed = !_navigator->get_mission_result()->valid;
if (!failed) {
/* reset mission failure if we have an updated valid mission */
_navigator->get_mission_result()->failure = false;
/* reset sequence info as well */
_navigator->get_mission_result()->seq_reached = -1;
_navigator->get_mission_result()->seq_total = _offboard_mission.count;
/* reset work item if new mission has been accepted */
_work_item_type = WORK_ITEM_TYPE_DEFAULT;
_mission_changed = true;
}
/* check if the mission waypoints changed while the vehicle is in air
* TODO add a flag to mission_s which actually tracks if the position of the waypoint changed */
if (((_offboard_mission.count != old_offboard_mission.count) ||
(_offboard_mission.dataman_id != old_offboard_mission.dataman_id)) &&
!_navigator->get_land_detected()->landed) {
_mission_waypoints_changed = true;
}
} else {
PX4_ERR("offboard mission update failed, handle: %d", _navigator->get_offboard_mission_sub());
}
if (failed) {
_offboard_mission.count = 0;
_offboard_mission.current_seq = 0;
_current_offboard_mission_index = 0;
PX4_ERR("mission check failed");
}
// find and store landing start marker (if available)
find_offboard_land_start();
set_current_offboard_mission_item();
}
void
Mission::advance_mission()
{
/* do not advance mission item if we're processing sub mission work items */
if (_work_item_type != WORK_ITEM_TYPE_DEFAULT) {
return;
}
switch (_mission_type) {
case MISSION_TYPE_OFFBOARD:
switch (_mission_execution_mode) {
case mission_result_s::MISSION_EXECUTION_MODE_NORMAL:
case mission_result_s::MISSION_EXECUTION_MODE_FAST_FORWARD: {
_current_offboard_mission_index++;
break;
}
case mission_result_s::MISSION_EXECUTION_MODE_REVERSE: {
// find next position item in reverse order
dm_item_t dm_current = (dm_item_t)(_offboard_mission.dataman_id);
for (int32_t i = _current_offboard_mission_index - 1; i >= 0; i--) {
struct mission_item_s missionitem = {};
const ssize_t len = sizeof(missionitem);
if (dm_read(dm_current, i, &missionitem, len) != len) {
/* not supposed to happen unless the datamanager can't access the SD card, etc. */
PX4_ERR("dataman read failure");
break;
}
if (item_contains_position(missionitem)) {
_current_offboard_mission_index = i;
return;
}
}
// finished flying back the mission
_current_offboard_mission_index = -1;
break;
}
default:
_current_offboard_mission_index++;
}
break;
case MISSION_TYPE_NONE:
default:
break;
}
}
void
Mission::set_mission_items()
{
/* reset the altitude foh (first order hold) logic, if altitude foh is enabled (param) a new foh element starts now */
_min_current_sp_distance_xy = FLT_MAX;
/* the home dist check provides user feedback, so we initialize it to this */
bool user_feedback_done = false;
/* mission item that comes after current if available */
struct mission_item_s mission_item_next_position;
bool has_next_position_item = false;
work_item_type new_work_item_type = WORK_ITEM_TYPE_DEFAULT;
if (prepare_mission_items(&_mission_item, &mission_item_next_position, &has_next_position_item)) {
/* if mission type changed, notify */
if (_mission_type != MISSION_TYPE_OFFBOARD) {
mavlink_log_info(_navigator->get_mavlink_log_pub(),
_mission_execution_mode == mission_result_s::MISSION_EXECUTION_MODE_REVERSE ? "Executing Reverse Mission" :
"Executing Mission");
user_feedback_done = true;
}
_mission_type = MISSION_TYPE_OFFBOARD;
} else {
/* no mission available or mission finished, switch to loiter */
if (_mission_type != MISSION_TYPE_NONE) {
if (_navigator->get_land_detected()->landed) {
mavlink_log_info(_navigator->get_mavlink_log_pub(),
_mission_execution_mode == mission_result_s::MISSION_EXECUTION_MODE_REVERSE ? "Reverse Mission finished, landed" :
"Mission finished, landed.");
} else {
/* https://en.wikipedia.org/wiki/Loiter_(aeronautics) */
mavlink_log_info(_navigator->get_mavlink_log_pub(),
_mission_execution_mode == mission_result_s::MISSION_EXECUTION_MODE_REVERSE ? "Reverse Mission finished, loitering" :
"Mission finished, loitering.");
/* use last setpoint for loiter */
_navigator->set_can_loiter_at_sp(true);
}
user_feedback_done = true;
}
_mission_type = MISSION_TYPE_NONE;
/* set loiter mission item and ensure that there is a minimum clearance from home */
set_loiter_item(&_mission_item, _navigator->get_takeoff_min_alt());
/* update position setpoint triplet */
position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet();
pos_sp_triplet->previous.valid = false;
mission_apply_limitation(_mission_item);
mission_item_to_position_setpoint(_mission_item, &pos_sp_triplet->current);
pos_sp_triplet->next.valid = false;
/* reuse setpoint for LOITER only if it's not IDLE */
_navigator->set_can_loiter_at_sp(pos_sp_triplet->current.type == position_setpoint_s::SETPOINT_TYPE_LOITER);
// set mission finished
_navigator->get_mission_result()->finished = true;
_navigator->set_mission_result_updated();
if (!user_feedback_done) {
/* only tell users that we got no mission if there has not been any
* better, more specific feedback yet
* https://en.wikipedia.org/wiki/Loiter_(aeronautics)
*/
if (_navigator->get_land_detected()->landed) {
/* landed, refusing to take off without a mission */
mavlink_log_critical(_navigator->get_mavlink_log_pub(), "No valid mission available, refusing takeoff.");
} else {
mavlink_log_critical(_navigator->get_mavlink_log_pub(), "No valid mission available, loitering.");
}
user_feedback_done = true;
}
_navigator->set_position_setpoint_triplet_updated();
return;
}
/*********************************** handle mission item *********************************************/
/* handle mission items depending on the mode */
const position_setpoint_s current_setpoint_copy = _navigator->get_position_setpoint_triplet()->current;
if (item_contains_position(_mission_item)) {
switch (_mission_execution_mode) {
case mission_result_s::MISSION_EXECUTION_MODE_NORMAL:
case mission_result_s::MISSION_EXECUTION_MODE_FAST_FORWARD: {
/* force vtol land */
if (_navigator->force_vtol() && _mission_item.nav_cmd == NAV_CMD_LAND) {
_mission_item.nav_cmd = NAV_CMD_VTOL_LAND;
}
position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet();
/* do takeoff before going to setpoint if needed and not already in takeoff */
/* in fixed-wing this whole block will be ignored and a takeoff item is always propagated */
if (do_need_vertical_takeoff() &&
_work_item_type == WORK_ITEM_TYPE_DEFAULT &&
new_work_item_type == WORK_ITEM_TYPE_DEFAULT) {
new_work_item_type = WORK_ITEM_TYPE_TAKEOFF;
/* use current mission item as next position item */
mission_item_next_position = _mission_item;
mission_item_next_position.nav_cmd = NAV_CMD_WAYPOINT;
has_next_position_item = true;
float takeoff_alt = calculate_takeoff_altitude(&_mission_item);
mavlink_log_info(_navigator->get_mavlink_log_pub(), "Takeoff to %.1f meters above home.",
(double)(takeoff_alt - _navigator->get_home_position()->alt));
_mission_item.nav_cmd = NAV_CMD_TAKEOFF;
_mission_item.lat = _navigator->get_global_position()->lat;
_mission_item.lon = _navigator->get_global_position()->lon;
/* hold heading for takeoff items */
_mission_item.yaw = _navigator->get_global_position()->yaw;
_mission_item.altitude = takeoff_alt;
_mission_item.altitude_is_relative = false;
_mission_item.autocontinue = true;
_mission_item.time_inside = 0.0f;
} else if (_mission_item.nav_cmd == NAV_CMD_TAKEOFF
&& _work_item_type == WORK_ITEM_TYPE_DEFAULT
&& new_work_item_type == WORK_ITEM_TYPE_DEFAULT
&& _navigator->get_vstatus()->is_rotary_wing) {
/* if there is no need to do a takeoff but we have a takeoff item, treat is as waypoint */
_mission_item.nav_cmd = NAV_CMD_WAYPOINT;
/* ignore yaw here, otherwise it might yaw before heading_sp_update takes over */
_mission_item.yaw = NAN;
/* since _mission_item.time_inside and and _mission_item.pitch_min build a union, we need to set time_inside to zero
* since in NAV_CMD_TAKEOFF mode there is currently no time_inside.
* Note also that resetting time_inside to zero will cause pitch_min to be zero as well.
*/
_mission_item.time_inside = 0.0f;
} else if (_mission_item.nav_cmd == NAV_CMD_VTOL_TAKEOFF
&& _work_item_type == WORK_ITEM_TYPE_DEFAULT
&& new_work_item_type == WORK_ITEM_TYPE_DEFAULT) {
if (_navigator->get_vstatus()->is_rotary_wing) {
/* haven't transitioned yet, trigger vtol takeoff logic below */
_work_item_type = WORK_ITEM_TYPE_TAKEOFF;
} else {
/* already in fixed-wing, go to waypoint */
_mission_item.nav_cmd = NAV_CMD_WAYPOINT;
}
/* ignore yaw here, otherwise it might yaw before heading_sp_update takes over */
_mission_item.yaw = NAN;
}
/* if we just did a normal takeoff navigate to the actual waypoint now */
if (_mission_item.nav_cmd == NAV_CMD_TAKEOFF &&
_work_item_type == WORK_ITEM_TYPE_TAKEOFF &&
new_work_item_type == WORK_ITEM_TYPE_DEFAULT) {
_mission_item.nav_cmd = NAV_CMD_WAYPOINT;
/* ignore yaw here, otherwise it might yaw before heading_sp_update takes over */
_mission_item.yaw = NAN;
/* since _mission_item.time_inside and and _mission_item.pitch_min build a union, we need to set time_inside to zero
* since in NAV_CMD_TAKEOFF mode there is currently no time_inside.
*/
_mission_item.time_inside = 0.0f;
}
/* if we just did a VTOL takeoff, prepare transition */
if (_mission_item.nav_cmd == NAV_CMD_VTOL_TAKEOFF &&
_work_item_type == WORK_ITEM_TYPE_TAKEOFF &&
new_work_item_type == WORK_ITEM_TYPE_DEFAULT &&
_navigator->get_vstatus()->is_rotary_wing &&
!_navigator->get_land_detected()->landed) {
/* check if the vtol_takeoff waypoint is on top of us */
if (do_need_move_to_takeoff()) {
new_work_item_type = WORK_ITEM_TYPE_TRANSITON_AFTER_TAKEOFF;
}
set_vtol_transition_item(&_mission_item, vtol_vehicle_status_s::VEHICLE_VTOL_STATE_FW);
/* set position setpoint to target during the transition */
// TODO: if has_next_position_item and use_next set next, or if use_heading set generated
generate_waypoint_from_heading(&pos_sp_triplet->current, _mission_item.yaw);
}
/* takeoff completed and transitioned, move to takeoff wp as fixed wing */
if (_mission_item.nav_cmd == NAV_CMD_VTOL_TAKEOFF
&& _work_item_type == WORK_ITEM_TYPE_TRANSITON_AFTER_TAKEOFF
&& new_work_item_type == WORK_ITEM_TYPE_DEFAULT) {
new_work_item_type = WORK_ITEM_TYPE_DEFAULT;
_mission_item.nav_cmd = NAV_CMD_WAYPOINT;
_mission_item.autocontinue = true;
_mission_item.time_inside = 0.0f;
}
/* move to land wp as fixed wing */
if (_mission_item.nav_cmd == NAV_CMD_VTOL_LAND
&& _work_item_type == WORK_ITEM_TYPE_DEFAULT
&& new_work_item_type == WORK_ITEM_TYPE_DEFAULT
&& !_navigator->get_land_detected()->landed) {
new_work_item_type = WORK_ITEM_TYPE_MOVE_TO_LAND;
/* use current mission item as next position item */
mission_item_next_position = _mission_item;
has_next_position_item = true;
float altitude = _navigator->get_global_position()->alt;
if (pos_sp_triplet->current.valid && pos_sp_triplet->current.type == position_setpoint_s::SETPOINT_TYPE_POSITION) {
altitude = pos_sp_triplet->current.alt;
}
_mission_item.altitude = altitude;
_mission_item.altitude_is_relative = false;
_mission_item.nav_cmd = NAV_CMD_WAYPOINT;
_mission_item.autocontinue = true;
_mission_item.time_inside = 0.0f;
_mission_item.vtol_back_transition = true;
}
/* transition to MC */
if (_mission_item.nav_cmd == NAV_CMD_VTOL_LAND
&& _work_item_type == WORK_ITEM_TYPE_MOVE_TO_LAND
&& new_work_item_type == WORK_ITEM_TYPE_DEFAULT
&& !_navigator->get_vstatus()->is_rotary_wing
&& !_navigator->get_land_detected()->landed) {
set_vtol_transition_item(&_mission_item, vtol_vehicle_status_s::VEHICLE_VTOL_STATE_MC);
new_work_item_type = WORK_ITEM_TYPE_MOVE_TO_LAND_AFTER_TRANSITION;
}
/* move to landing waypoint before descent if necessary */
if (do_need_move_to_land() &&
(_work_item_type == WORK_ITEM_TYPE_DEFAULT ||
_work_item_type == WORK_ITEM_TYPE_MOVE_TO_LAND_AFTER_TRANSITION) &&
new_work_item_type == WORK_ITEM_TYPE_DEFAULT) {
new_work_item_type = WORK_ITEM_TYPE_MOVE_TO_LAND;
/* use current mission item as next position item */
mission_item_next_position = _mission_item;
has_next_position_item = true;
/*
* Ignoring waypoint altitude:
* Set altitude to the same as we have now to prevent descending too fast into
* the ground. Actual landing will descend anyway until it touches down.
* XXX: We might want to change that at some point if it is clear to the user
* what the altitude means on this waypoint type.
*/
float altitude = _navigator->get_global_position()->alt;
if (pos_sp_triplet->current.valid
&& pos_sp_triplet->current.type == position_setpoint_s::SETPOINT_TYPE_POSITION) {
altitude = pos_sp_triplet->current.alt;
}
_mission_item.altitude = altitude;
_mission_item.altitude_is_relative = false;
_mission_item.nav_cmd = NAV_CMD_WAYPOINT;
_mission_item.autocontinue = true;
_mission_item.time_inside = 0.0f;
} else if (_mission_item.nav_cmd == NAV_CMD_LAND && _work_item_type == WORK_ITEM_TYPE_DEFAULT) {
if (_mission_item.land_precision > 0 && _mission_item.land_precision < 3) {
new_work_item_type = WORK_ITEM_TYPE_PRECISION_LAND;
if (_mission_item.land_precision == 1) {
_navigator->get_precland()->set_mode(PrecLandMode::Opportunistic);
} else { //_mission_item.land_precision == 2
_navigator->get_precland()->set_mode(PrecLandMode::Required);
}
_navigator->get_precland()->on_activation();
}
}
/* we just moved to the landing waypoint, now descend */
if (_work_item_type == WORK_ITEM_TYPE_MOVE_TO_LAND &&
new_work_item_type == WORK_ITEM_TYPE_DEFAULT) {
if (_mission_item.land_precision > 0 && _mission_item.land_precision < 3) {
new_work_item_type = WORK_ITEM_TYPE_PRECISION_LAND;
if (_mission_item.land_precision == 1) {
_navigator->get_precland()->set_mode(PrecLandMode::Opportunistic);
} else { //_mission_item.land_precision == 2
_navigator->get_precland()->set_mode(PrecLandMode::Required);
}
_navigator->get_precland()->on_activation();
}
}
/* ignore yaw for landing items */
/* XXX: if specified heading for landing is desired we could add another step before the descent
* that aligns the vehicle first */
if (_mission_item.nav_cmd == NAV_CMD_LAND || _mission_item.nav_cmd == NAV_CMD_VTOL_LAND) {
_mission_item.yaw = NAN;
}
// for fast forward convert certain types to simple waypoint
// XXX: add other types which should be ignored in fast forward
if (_mission_execution_mode == mission_result_s::MISSION_EXECUTION_MODE_FAST_FORWARD &&
((_mission_item.nav_cmd == NAV_CMD_LOITER_UNLIMITED) ||
(_mission_item.nav_cmd == NAV_CMD_LOITER_TIME_LIMIT))) {
_mission_item.nav_cmd = NAV_CMD_WAYPOINT;
_mission_item.autocontinue = true;
_mission_item.time_inside = 0.0f;
}
break;
}
case mission_result_s::MISSION_EXECUTION_MODE_REVERSE: {
if (item_contains_position(_mission_item)) {
// convert mission item to a simple waypoint
_mission_item.nav_cmd = NAV_CMD_WAYPOINT;
_mission_item.autocontinue = true;
_mission_item.time_inside = 0.0f;
} else {
mavlink_log_critical(_navigator->get_mavlink_log_pub(), "MissionReverse: Got a non-position mission item, ignoring it");
}
break;
}
}
} else {
/* handle non-position mission items such as commands */
switch (_mission_execution_mode) {
case mission_result_s::MISSION_EXECUTION_MODE_NORMAL:
case mission_result_s::MISSION_EXECUTION_MODE_FAST_FORWARD: {
position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet();
/* turn towards next waypoint before MC to FW transition */
if (_mission_item.nav_cmd == NAV_CMD_DO_VTOL_TRANSITION
&& _work_item_type == WORK_ITEM_TYPE_DEFAULT
&& new_work_item_type == WORK_ITEM_TYPE_DEFAULT
&& _navigator->get_vstatus()->is_rotary_wing
&& !_navigator->get_land_detected()->landed
&& has_next_position_item) {
new_work_item_type = WORK_ITEM_TYPE_ALIGN;
set_align_mission_item(&_mission_item, &mission_item_next_position);
/* set position setpoint to target during the transition */
mission_apply_limitation(_mission_item);
mission_item_to_position_setpoint(mission_item_next_position, &pos_sp_triplet->current);
}
/* yaw is aligned now */
if (_work_item_type == WORK_ITEM_TYPE_ALIGN &&
new_work_item_type == WORK_ITEM_TYPE_DEFAULT) {
new_work_item_type = WORK_ITEM_TYPE_DEFAULT;
/* set position setpoint to target during the transition */
pos_sp_triplet->previous = pos_sp_triplet->current;
generate_waypoint_from_heading(&pos_sp_triplet->current, pos_sp_triplet->current.yaw);
}
/* don't advance mission after FW to MC command */
if (_mission_item.nav_cmd == NAV_CMD_DO_VTOL_TRANSITION
&& _work_item_type == WORK_ITEM_TYPE_DEFAULT
&& new_work_item_type == WORK_ITEM_TYPE_DEFAULT
&& !_navigator->get_vstatus()->is_rotary_wing
&& !_navigator->get_land_detected()->landed
&& pos_sp_triplet->current.valid) {
new_work_item_type = WORK_ITEM_TYPE_CMD_BEFORE_MOVE;
}
/* after FW to MC transition finish moving to the waypoint */
if (_work_item_type == WORK_ITEM_TYPE_CMD_BEFORE_MOVE &&
new_work_item_type == WORK_ITEM_TYPE_DEFAULT
&& pos_sp_triplet->current.valid) {
new_work_item_type = WORK_ITEM_TYPE_DEFAULT;
_mission_item.nav_cmd = NAV_CMD_WAYPOINT;
copy_position_if_valid(&_mission_item, &pos_sp_triplet->current);
_mission_item.autocontinue = true;
_mission_item.time_inside = 0.0f;
}
// ignore certain commands in mission fast forward
if ((_mission_execution_mode == mission_result_s::MISSION_EXECUTION_MODE_FAST_FORWARD) &&
(_mission_item.nav_cmd == NAV_CMD_DELAY)) {
_mission_item.autocontinue = true;
_mission_item.time_inside = 0.0f;
}
break;
}
case mission_result_s::MISSION_EXECUTION_MODE_REVERSE: {
// nothing to do, all commands are ignored
break;
}
}
}
/*********************************** set setpoints and check next *********************************************/
position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet();
/* set current position setpoint from mission item (is protected against non-position items) */
if (new_work_item_type != WORK_ITEM_TYPE_PRECISION_LAND) {
mission_apply_limitation(_mission_item);
mission_item_to_position_setpoint(_mission_item, &pos_sp_triplet->current);
}