-
Notifications
You must be signed in to change notification settings - Fork 13.4k
/
mavlink_mission.cpp
1670 lines (1277 loc) · 49.4 KB
/
mavlink_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) 2012-2016 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 mavlink_mission.cpp
* MAVLink mission manager implementation.
*
* @author Lorenz Meier <lorenz@px4.io>
* @author Julian Oes <julian@px4.io>
* @author Anton Babushkin <anton@px4.io>
*/
#include "mavlink_mission.h"
#include "mavlink_main.h"
#include <lib/ecl/geo/geo.h>
#include <systemlib/err.h>
#include <drivers/drv_hrt.h>
#include <px4_defines.h>
#include <mathlib/mathlib.h>
#include <matrix/math.hpp>
#include <navigator/navigation.h>
#include <uORB/topics/mission.h>
#include <uORB/topics/mission_result.h>
using matrix::wrap_2pi;
dm_item_t MavlinkMissionManager::_dataman_id = DM_KEY_WAYPOINTS_OFFBOARD_0;
bool MavlinkMissionManager::_dataman_init = false;
uint16_t MavlinkMissionManager::_count[3] = { 0, 0, 0 };
int32_t MavlinkMissionManager::_current_seq = 0;
bool MavlinkMissionManager::_transfer_in_progress = false;
constexpr uint16_t MavlinkMissionManager::MAX_COUNT[];
uint16_t MavlinkMissionManager::_geofence_update_counter = 0;
#define CHECK_SYSID_COMPID_MISSION(_msg) (_msg.target_system == mavlink_system.sysid && \
((_msg.target_component == mavlink_system.compid) || \
(_msg.target_component == MAV_COMP_ID_MISSIONPLANNER) || \
(_msg.target_component == MAV_COMP_ID_ALL)))
MavlinkMissionManager::MavlinkMissionManager(Mavlink *mavlink) :
_mavlink(mavlink)
{
_offboard_mission_sub = orb_subscribe(ORB_ID(mission));
_mission_result_sub = orb_subscribe(ORB_ID(mission_result));
init_offboard_mission();
}
MavlinkMissionManager::~MavlinkMissionManager()
{
orb_unsubscribe(_mission_result_sub);
orb_unadvertise(_offboard_mission_pub);
}
void
MavlinkMissionManager::init_offboard_mission()
{
if (!_dataman_init) {
_dataman_init = true;
/* lock MISSION_STATE item */
int dm_lock_ret = dm_lock(DM_KEY_MISSION_STATE);
if (dm_lock_ret != 0) {
PX4_ERR("DM_KEY_MISSION_STATE lock failed");
}
mission_s mission_state;
int ret = dm_read(DM_KEY_MISSION_STATE, 0, &mission_state, sizeof(mission_s));
/* unlock MISSION_STATE item */
if (dm_lock_ret == 0) {
dm_unlock(DM_KEY_MISSION_STATE);
}
if (ret > 0) {
_dataman_id = (dm_item_t)mission_state.dataman_id;
_count[MAV_MISSION_TYPE_MISSION] = mission_state.count;
_current_seq = mission_state.current_seq;
} else if (ret < 0) {
PX4_ERR("offboard mission init failed (%i)", ret);
}
load_geofence_stats();
load_safepoint_stats();
}
_my_dataman_id = _dataman_id;
}
int
MavlinkMissionManager::load_geofence_stats()
{
mission_stats_entry_s stats;
// initialize fence points count
int ret = dm_read(DM_KEY_FENCE_POINTS, 0, &stats, sizeof(mission_stats_entry_s));
if (ret == sizeof(mission_stats_entry_s)) {
_count[MAV_MISSION_TYPE_FENCE] = stats.num_items;
_geofence_update_counter = stats.update_counter;
}
return ret;
}
int
MavlinkMissionManager::load_safepoint_stats()
{
mission_stats_entry_s stats;
// initialize safe points count
int ret = dm_read(DM_KEY_SAFE_POINTS, 0, &stats, sizeof(mission_stats_entry_s));
if (ret == sizeof(mission_stats_entry_s)) {
_count[MAV_MISSION_TYPE_RALLY] = stats.num_items;
}
return ret;
}
/**
* Publish mission topic to notify navigator about changes.
*/
int
MavlinkMissionManager::update_active_mission(dm_item_t dataman_id, uint16_t count, int32_t seq)
{
mission_s mission;
mission.timestamp = hrt_absolute_time();
mission.dataman_id = dataman_id;
mission.count = count;
mission.current_seq = seq;
/* update mission state in dataman */
/* lock MISSION_STATE item */
int dm_lock_ret = dm_lock(DM_KEY_MISSION_STATE);
if (dm_lock_ret != 0) {
PX4_ERR("DM_KEY_MISSION_STATE lock failed");
}
int res = dm_write(DM_KEY_MISSION_STATE, 0, DM_PERSIST_POWER_ON_RESET, &mission, sizeof(mission_s));
/* unlock MISSION_STATE item */
if (dm_lock_ret == 0) {
dm_unlock(DM_KEY_MISSION_STATE);
}
if (res == sizeof(mission_s)) {
/* update active mission state */
_dataman_id = dataman_id;
_count[MAV_MISSION_TYPE_MISSION] = count;
_current_seq = seq;
_my_dataman_id = _dataman_id;
/* mission state saved successfully, publish offboard_mission topic */
if (_offboard_mission_pub == nullptr) {
_offboard_mission_pub = orb_advertise(ORB_ID(mission), &mission);
} else {
orb_publish(ORB_ID(mission), _offboard_mission_pub, &mission);
}
return PX4_OK;
} else {
PX4_ERR("WPM: can't save mission state");
if (_filesystem_errcount++ < FILESYSTEM_ERRCOUNT_NOTIFY_LIMIT) {
_mavlink->send_statustext_critical("Mission storage: Unable to write to microSD");
}
return PX4_ERROR;
}
}
int
MavlinkMissionManager::update_geofence_count(unsigned count)
{
mission_stats_entry_s stats;
stats.num_items = count;
stats.update_counter = ++_geofence_update_counter; // this makes sure navigator will reload the fence data
/* update stats in dataman */
int res = dm_write(DM_KEY_FENCE_POINTS, 0, DM_PERSIST_POWER_ON_RESET, &stats, sizeof(mission_stats_entry_s));
if (res == sizeof(mission_stats_entry_s)) {
_count[MAV_MISSION_TYPE_FENCE] = count;
} else {
if (_filesystem_errcount++ < FILESYSTEM_ERRCOUNT_NOTIFY_LIMIT) {
_mavlink->send_statustext_critical("Mission storage: Unable to write to microSD");
}
return PX4_ERROR;
}
return PX4_OK;
}
int
MavlinkMissionManager::update_safepoint_count(unsigned count)
{
mission_stats_entry_s stats;
stats.num_items = count;
/* update stats in dataman */
int res = dm_write(DM_KEY_SAFE_POINTS, 0, DM_PERSIST_POWER_ON_RESET, &stats, sizeof(mission_stats_entry_s));
if (res == sizeof(mission_stats_entry_s)) {
_count[MAV_MISSION_TYPE_RALLY] = count;
} else {
if (_filesystem_errcount++ < FILESYSTEM_ERRCOUNT_NOTIFY_LIMIT) {
_mavlink->send_statustext_critical("Mission storage: Unable to write to microSD");
}
return PX4_ERROR;
}
return PX4_OK;
}
void
MavlinkMissionManager::send_mission_ack(uint8_t sysid, uint8_t compid, uint8_t type)
{
mavlink_mission_ack_t wpa;
wpa.target_system = sysid;
wpa.target_component = compid;
wpa.type = type;
wpa.mission_type = _mission_type;
mavlink_msg_mission_ack_send_struct(_mavlink->get_channel(), &wpa);
PX4_DEBUG("WPM: Send MISSION_ACK type %u to ID %u", wpa.type, wpa.target_system);
}
void
MavlinkMissionManager::send_mission_current(uint16_t seq)
{
unsigned item_count = _count[MAV_MISSION_TYPE_MISSION];
if (seq < item_count) {
mavlink_mission_current_t wpc;
wpc.seq = seq;
mavlink_msg_mission_current_send_struct(_mavlink->get_channel(), &wpc);
} else if (seq == 0 && item_count == 0) {
/* don't broadcast if no WPs */
} else {
PX4_DEBUG("WPM: Send MISSION_CURRENT ERROR: seq %u out of bounds", seq);
_mavlink->send_statustext_critical("ERROR: wp index out of bounds");
}
}
void
MavlinkMissionManager::send_mission_count(uint8_t sysid, uint8_t compid, uint16_t count, MAV_MISSION_TYPE mission_type)
{
_time_last_sent = hrt_absolute_time();
mavlink_mission_count_t wpc;
wpc.target_system = sysid;
wpc.target_component = compid;
wpc.count = count;
wpc.mission_type = mission_type;
mavlink_msg_mission_count_send_struct(_mavlink->get_channel(), &wpc);
PX4_DEBUG("WPM: Send MISSION_COUNT %u to ID %u, mission type=%i", wpc.count, wpc.target_system, mission_type);
}
void
MavlinkMissionManager::send_mission_item(uint8_t sysid, uint8_t compid, uint16_t seq)
{
mission_item_s mission_item = {};
bool read_success = false;
switch (_mission_type) {
case MAV_MISSION_TYPE_MISSION: {
read_success = dm_read(_dataman_id, seq, &mission_item, sizeof(mission_item_s)) == sizeof(mission_item_s);
}
break;
case MAV_MISSION_TYPE_FENCE: { // Read a geofence point
mission_fence_point_s mission_fence_point;
read_success = dm_read(DM_KEY_FENCE_POINTS, seq + 1, &mission_fence_point, sizeof(mission_fence_point_s)) ==
sizeof(mission_fence_point_s);
mission_item.nav_cmd = mission_fence_point.nav_cmd;
mission_item.frame = mission_fence_point.frame;
mission_item.lat = mission_fence_point.lat;
mission_item.lon = mission_fence_point.lon;
mission_item.altitude = mission_fence_point.alt;
if (mission_fence_point.nav_cmd == MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION ||
mission_fence_point.nav_cmd == MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION) {
mission_item.vertex_count = mission_fence_point.vertex_count;
} else {
mission_item.circle_radius = mission_fence_point.circle_radius;
}
}
break;
case MAV_MISSION_TYPE_RALLY: { // Read a safe point / rally point
mission_save_point_s mission_save_point;
read_success = dm_read(DM_KEY_SAFE_POINTS, seq + 1, &mission_save_point, sizeof(mission_save_point_s)) ==
sizeof(mission_save_point_s);
mission_item.nav_cmd = MAV_CMD_NAV_RALLY_POINT;
mission_item.frame = mission_save_point.frame;
mission_item.lat = mission_save_point.lat;
mission_item.lon = mission_save_point.lon;
mission_item.altitude = mission_save_point.alt;
}
break;
default:
_mavlink->send_statustext_critical("Received unknown mission type, abort.");
break;
}
if (read_success) {
_time_last_sent = hrt_absolute_time();
if (_int_mode) {
mavlink_mission_item_int_t wp = {};
format_mavlink_mission_item(&mission_item, reinterpret_cast<mavlink_mission_item_t *>(&wp));
wp.target_system = sysid;
wp.target_component = compid;
wp.seq = seq;
wp.current = (_current_seq == seq) ? 1 : 0;
mavlink_msg_mission_item_int_send_struct(_mavlink->get_channel(), &wp);
PX4_DEBUG("WPM: Send MISSION_ITEM_INT seq %u to ID %u", wp.seq, wp.target_system);
} else {
mavlink_mission_item_t wp = {};
format_mavlink_mission_item(&mission_item, &wp);
wp.target_system = sysid;
wp.target_component = compid;
wp.seq = seq;
wp.current = (_current_seq == seq) ? 1 : 0;
mavlink_msg_mission_item_send_struct(_mavlink->get_channel(), &wp);
PX4_DEBUG("WPM: Send MISSION_ITEM seq %u to ID %u", wp.seq, wp.target_system);
}
} else {
send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR);
if (_filesystem_errcount++ < FILESYSTEM_ERRCOUNT_NOTIFY_LIMIT) {
_mavlink->send_statustext_critical("Mission storage: Unable to read from microSD");
}
PX4_DEBUG("WPM: Send MISSION_ITEM ERROR: could not read seq %u from dataman ID %i", seq, _dataman_id);
}
}
uint16_t
MavlinkMissionManager::current_max_item_count()
{
if (_mission_type >= sizeof(MAX_COUNT) / sizeof(MAX_COUNT[0])) {
PX4_ERR("WPM: MAX_COUNT out of bounds (%u)", _mission_type);
return 0;
}
return MAX_COUNT[_mission_type];
}
uint16_t
MavlinkMissionManager::current_item_count()
{
if (_mission_type >= sizeof(_count) / sizeof(_count[0])) {
PX4_ERR("WPM: _count out of bounds (%u)", _mission_type);
return 0;
}
return _count[_mission_type];
}
void
MavlinkMissionManager::send_mission_request(uint8_t sysid, uint8_t compid, uint16_t seq)
{
if (seq < current_max_item_count()) {
_time_last_sent = hrt_absolute_time();
if (_int_mode) {
mavlink_mission_request_int_t wpr;
wpr.target_system = sysid;
wpr.target_component = compid;
wpr.seq = seq;
wpr.mission_type = _mission_type;
mavlink_msg_mission_request_int_send_struct(_mavlink->get_channel(), &wpr);
PX4_DEBUG("WPM: Send MISSION_REQUEST_INT seq %u to ID %u", wpr.seq, wpr.target_system);
} else {
mavlink_mission_request_t wpr;
wpr.target_system = sysid;
wpr.target_component = compid;
wpr.seq = seq;
wpr.mission_type = _mission_type;
mavlink_msg_mission_request_send_struct(_mavlink->get_channel(), &wpr);
PX4_DEBUG("WPM: Send MISSION_REQUEST seq %u to ID %u", wpr.seq, wpr.target_system);
}
} else {
_mavlink->send_statustext_critical("ERROR: Waypoint index exceeds list capacity");
PX4_DEBUG("WPM: Send MISSION_REQUEST ERROR: seq %u exceeds list capacity", seq);
}
}
void
MavlinkMissionManager::send_mission_item_reached(uint16_t seq)
{
mavlink_mission_item_reached_t wp_reached;
wp_reached.seq = seq;
mavlink_msg_mission_item_reached_send_struct(_mavlink->get_channel(), &wp_reached);
PX4_DEBUG("WPM: Send MISSION_ITEM_REACHED reached_seq %u", wp_reached.seq);
}
void
MavlinkMissionManager::send(const hrt_abstime now)
{
// do not send anything over high latency communication
if (_mavlink->get_mode() == Mavlink::MAVLINK_MODE_IRIDIUM) {
return;
}
bool updated = false;
orb_check(_mission_result_sub, &updated);
if (updated) {
mission_result_s mission_result;
orb_copy(ORB_ID(mission_result), _mission_result_sub, &mission_result);
if (_current_seq != mission_result.seq_current) {
_current_seq = mission_result.seq_current;
PX4_DEBUG("WPM: got mission result, new current_seq: %u", _current_seq);
}
if (_last_reached != mission_result.seq_reached) {
_last_reached = mission_result.seq_reached;
_reached_sent_count = 0;
if (_last_reached >= 0) {
send_mission_item_reached((uint16_t)mission_result.seq_reached);
}
PX4_DEBUG("WPM: got mission result, new seq_reached: %d", _last_reached);
}
send_mission_current(_current_seq);
if (mission_result.item_do_jump_changed) {
/* send a mission item again if the remaining DO_JUMPs has changed */
send_mission_item(_transfer_partner_sysid, _transfer_partner_compid,
(uint16_t)mission_result.item_changed_index);
}
} else {
if (_slow_rate_limiter.check(now)) {
send_mission_current(_current_seq);
// send the reached message another 10 times
if (_last_reached >= 0 && (_reached_sent_count < 10)) {
send_mission_item_reached((uint16_t)_last_reached);
_reached_sent_count++;
}
}
}
/* check for timed-out operations */
if (_state == MAVLINK_WPM_STATE_GETLIST && (_time_last_sent > 0)
&& hrt_elapsed_time(&_time_last_sent) > MAVLINK_MISSION_RETRY_TIMEOUT_DEFAULT) {
// try to request item again after timeout
send_mission_request(_transfer_partner_sysid, _transfer_partner_compid, _transfer_seq);
} else if (_state != MAVLINK_WPM_STATE_IDLE && (_time_last_recv > 0)
&& hrt_elapsed_time(&_time_last_recv) > MAVLINK_MISSION_PROTOCOL_TIMEOUT_DEFAULT) {
_mavlink->send_statustext_critical("Operation timeout");
PX4_DEBUG("WPM: Last operation (state=%u) timed out, changing state to MAVLINK_WPM_STATE_IDLE", _state);
switch_to_idle_state();
// since we are giving up, reset this state also, so another request can be started.
_transfer_in_progress = false;
} else if (_state == MAVLINK_WPM_STATE_IDLE) {
// reset flags
_time_last_sent = 0;
_time_last_recv = 0;
}
}
void
MavlinkMissionManager::handle_message(const mavlink_message_t *msg)
{
switch (msg->msgid) {
case MAVLINK_MSG_ID_MISSION_ACK:
handle_mission_ack(msg);
break;
case MAVLINK_MSG_ID_MISSION_SET_CURRENT:
handle_mission_set_current(msg);
break;
case MAVLINK_MSG_ID_MISSION_REQUEST_LIST:
handle_mission_request_list(msg);
break;
case MAVLINK_MSG_ID_MISSION_REQUEST:
handle_mission_request(msg);
break;
case MAVLINK_MSG_ID_MISSION_REQUEST_INT:
handle_mission_request_int(msg);
break;
case MAVLINK_MSG_ID_MISSION_COUNT:
handle_mission_count(msg);
break;
case MAVLINK_MSG_ID_MISSION_ITEM:
handle_mission_item(msg);
break;
case MAVLINK_MSG_ID_MISSION_ITEM_INT:
handle_mission_item_int(msg);
break;
case MAVLINK_MSG_ID_MISSION_CLEAR_ALL:
handle_mission_clear_all(msg);
break;
default:
break;
}
}
void
MavlinkMissionManager::handle_mission_ack(const mavlink_message_t *msg)
{
mavlink_mission_ack_t wpa;
mavlink_msg_mission_ack_decode(msg, &wpa);
if (CHECK_SYSID_COMPID_MISSION(wpa)) {
if ((msg->sysid == _transfer_partner_sysid && msg->compid == _transfer_partner_compid)) {
if (_state == MAVLINK_WPM_STATE_SENDLIST && _mission_type == wpa.mission_type) {
_time_last_recv = hrt_absolute_time();
if (_transfer_seq == current_item_count()) {
PX4_DEBUG("WPM: MISSION_ACK OK all items sent, switch to state IDLE");
} else {
_mavlink->send_statustext_critical("WPM: ERR: not all items sent -> IDLE");
PX4_DEBUG("WPM: MISSION_ACK ERROR: not all items sent, switch to state IDLE anyway");
}
switch_to_idle_state();
} else if (_state == MAVLINK_WPM_STATE_GETLIST) {
// INT or float mode is not supported
if (wpa.type == MAV_MISSION_UNSUPPORTED) {
if (_int_mode) {
_int_mode = false;
send_mission_request(_transfer_partner_sysid, _transfer_partner_compid, _transfer_seq);
} else {
_int_mode = true;
send_mission_request(_transfer_partner_sysid, _transfer_partner_compid, _transfer_seq);
}
} else if (wpa.type != MAV_MISSION_ACCEPTED) {
PX4_WARN("Mission ack result was %d", wpa.type);
}
}
} else {
_mavlink->send_statustext_critical("REJ. WP CMD: partner id mismatch");
PX4_DEBUG("WPM: MISSION_ACK ERR: ID mismatch");
}
}
}
void
MavlinkMissionManager::handle_mission_set_current(const mavlink_message_t *msg)
{
mavlink_mission_set_current_t wpc;
mavlink_msg_mission_set_current_decode(msg, &wpc);
if (CHECK_SYSID_COMPID_MISSION(wpc)) {
if (_state == MAVLINK_WPM_STATE_IDLE) {
_time_last_recv = hrt_absolute_time();
if (wpc.seq < _count[MAV_MISSION_TYPE_MISSION]) {
if (update_active_mission(_dataman_id, _count[MAV_MISSION_TYPE_MISSION], wpc.seq) == PX4_OK) {
PX4_DEBUG("WPM: MISSION_SET_CURRENT seq=%d OK", wpc.seq);
} else {
PX4_DEBUG("WPM: MISSION_SET_CURRENT seq=%d ERROR", wpc.seq);
_mavlink->send_statustext_critical("WPM: WP CURR CMD: Error setting ID");
}
} else {
PX4_ERR("WPM: MISSION_SET_CURRENT seq=%d ERROR: not in list", wpc.seq);
_mavlink->send_statustext_critical("WPM: WP CURR CMD: Not in list");
}
} else {
PX4_DEBUG("WPM: MISSION_SET_CURRENT ERROR: busy");
_mavlink->send_statustext_critical("WPM: IGN WP CURR CMD: Busy");
}
}
}
void
MavlinkMissionManager::handle_mission_request_list(const mavlink_message_t *msg)
{
mavlink_mission_request_list_t wprl;
mavlink_msg_mission_request_list_decode(msg, &wprl);
if (CHECK_SYSID_COMPID_MISSION(wprl)) {
if (_state == MAVLINK_WPM_STATE_IDLE || (_state == MAVLINK_WPM_STATE_SENDLIST
&& (uint8_t)_mission_type == wprl.mission_type)) {
_time_last_recv = hrt_absolute_time();
_state = MAVLINK_WPM_STATE_SENDLIST;
_mission_type = (MAV_MISSION_TYPE)wprl.mission_type;
// make sure our item counts are up-to-date
switch (_mission_type) {
case MAV_MISSION_TYPE_FENCE:
load_geofence_stats();
break;
case MAV_MISSION_TYPE_RALLY:
load_safepoint_stats();
break;
default:
break;
}
_transfer_seq = 0;
_transfer_count = current_item_count();
_transfer_partner_sysid = msg->sysid;
_transfer_partner_compid = msg->compid;
if (_transfer_count > 0) {
PX4_DEBUG("WPM: MISSION_REQUEST_LIST OK, %u mission items to send, mission type=%i", _transfer_count, _mission_type);
} else {
PX4_DEBUG("WPM: MISSION_REQUEST_LIST OK nothing to send, mission is empty, mission type=%i", _mission_type);
}
send_mission_count(msg->sysid, msg->compid, _transfer_count, _mission_type);
} else {
PX4_DEBUG("WPM: MISSION_REQUEST_LIST ERROR: busy");
_mavlink->send_statustext_critical("IGN REQUEST LIST: Busy");
}
}
}
void
MavlinkMissionManager::handle_mission_request(const mavlink_message_t *msg)
{
// The request comes in the old float mode, so we switch to it.
if (_int_mode) {
_int_mode = false;
}
handle_mission_request_both(msg);
}
void
MavlinkMissionManager::handle_mission_request_int(const mavlink_message_t *msg)
{
// The request comes in the new int mode, so we switch to it.
if (!_int_mode) {
_int_mode = true;
}
handle_mission_request_both(msg);
}
void
MavlinkMissionManager::handle_mission_request_both(const mavlink_message_t *msg)
{
/* The mavlink_message_t could also be a mavlink_mission_request_int_t, however the structs
* are basically the same, so we can ignore it. */
mavlink_mission_request_t wpr;
mavlink_msg_mission_request_decode(msg, &wpr);
if (CHECK_SYSID_COMPID_MISSION(wpr)) {
if (msg->sysid == _transfer_partner_sysid && msg->compid == _transfer_partner_compid) {
if (_state == MAVLINK_WPM_STATE_SENDLIST) {
if (_mission_type != wpr.mission_type) {
PX4_WARN("WPM: Unexpected mission type (%u %u)", wpr.mission_type, _mission_type);
return;
}
_time_last_recv = hrt_absolute_time();
/* _transfer_seq contains sequence of expected request */
if (wpr.seq == _transfer_seq && _transfer_seq < _transfer_count) {
PX4_DEBUG("WPM: MISSION_ITEM_REQUEST(_INT) seq %u from ID %u", wpr.seq, msg->sysid);
_transfer_seq++;
} else if (wpr.seq == _transfer_seq - 1) {
PX4_DEBUG("WPM: MISSION_ITEM_REQUEST(_INT) seq %u from ID %u (again)", wpr.seq, msg->sysid);
} else {
if (_transfer_seq > 0 && _transfer_seq < _transfer_count) {
PX4_DEBUG("WPM: MISSION_ITEM_REQUEST(_INT) ERROR: seq %u from ID %u unexpected, must be %i or %i", wpr.seq, msg->sysid,
_transfer_seq - 1, _transfer_seq);
} else if (_transfer_seq <= 0) {
PX4_DEBUG("WPM: MISSION_ITEM_REQUEST(_INT) ERROR: seq %u from ID %u unexpected, must be %i", wpr.seq, msg->sysid,
_transfer_seq);
} else {
PX4_DEBUG("WPM: MISSION_ITEM_REQUEST(_INT) ERROR: seq %u from ID %u unexpected, must be %i", wpr.seq, msg->sysid,
_transfer_seq - 1);
}
switch_to_idle_state();
send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR);
_mavlink->send_statustext_critical("WPM: REJ. CMD: Req. WP was unexpected");
return;
}
/* double check bounds in case of items count changed */
if (wpr.seq < current_item_count()) {
send_mission_item(_transfer_partner_sysid, _transfer_partner_compid, wpr.seq);
} else {
PX4_DEBUG("WPM: MISSION_ITEM_REQUEST(_INT) ERROR: seq %u out of bound [%u, %u]", wpr.seq, wpr.seq,
current_item_count() - 1);
switch_to_idle_state();
send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR);
_mavlink->send_statustext_critical("WPM: REJ. CMD: Req. WP was unexpected");
}
} else if (_state == MAVLINK_WPM_STATE_IDLE) {
PX4_DEBUG("WPM: MISSION_ITEM_REQUEST(_INT) ERROR: no transfer");
// Silently ignore this as some OSDs have buggy mission protocol implementations
//_mavlink->send_statustext_critical("IGN MISSION_ITEM_REQUEST(_INT): No active transfer");
} else {
PX4_DEBUG("WPM: MISSION_ITEM_REQUEST(_INT) ERROR: busy (state %d).", _state);
_mavlink->send_statustext_critical("WPM: REJ. CMD: Busy");
}
} else {
_mavlink->send_statustext_critical("WPM: REJ. CMD: partner id mismatch");
PX4_DEBUG("WPM: MISSION_ITEM_REQUEST(_INT) ERROR: rejected, partner ID mismatch");
}
}
}
void
MavlinkMissionManager::handle_mission_count(const mavlink_message_t *msg)
{
mavlink_mission_count_t wpc;
mavlink_msg_mission_count_decode(msg, &wpc);
if (CHECK_SYSID_COMPID_MISSION(wpc)) {
if (_state == MAVLINK_WPM_STATE_IDLE) {
_time_last_recv = hrt_absolute_time();
if (_transfer_in_progress) {
send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR);
return;
}
_transfer_in_progress = true;
_mission_type = (MAV_MISSION_TYPE)wpc.mission_type;
if (wpc.count > current_max_item_count()) {
PX4_DEBUG("WPM: MISSION_COUNT ERROR: too many waypoints (%d), supported: %d", wpc.count, current_max_item_count());
send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_NO_SPACE);
_transfer_in_progress = false;
return;
}
if (wpc.count == 0) {
PX4_DEBUG("WPM: MISSION_COUNT 0, clearing waypoints list and staying in state MAVLINK_WPM_STATE_IDLE");
switch (_mission_type) {
case MAV_MISSION_TYPE_MISSION:
/* alternate dataman ID anyway to let navigator know about changes */
if (_dataman_id == DM_KEY_WAYPOINTS_OFFBOARD_0) {
update_active_mission(DM_KEY_WAYPOINTS_OFFBOARD_1, 0, 0);
} else {
update_active_mission(DM_KEY_WAYPOINTS_OFFBOARD_0, 0, 0);
}
break;
case MAV_MISSION_TYPE_FENCE:
update_geofence_count(0);
break;
case MAV_MISSION_TYPE_RALLY:
update_safepoint_count(0);
break;
default:
PX4_ERR("mission type %u not handled", _mission_type);
break;
}
send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ACCEPTED);
_transfer_in_progress = false;
return;
}
PX4_DEBUG("WPM: MISSION_COUNT %u from ID %u, changing state to MAVLINK_WPM_STATE_GETLIST", wpc.count, msg->sysid);
_state = MAVLINK_WPM_STATE_GETLIST;
_transfer_seq = 0;
_transfer_partner_sysid = msg->sysid;
_transfer_partner_compid = msg->compid;
_transfer_count = wpc.count;
_transfer_dataman_id = (_dataman_id == DM_KEY_WAYPOINTS_OFFBOARD_0 ? DM_KEY_WAYPOINTS_OFFBOARD_1 :
DM_KEY_WAYPOINTS_OFFBOARD_0); // use inactive storage for transmission
_transfer_current_seq = -1;
if (_mission_type == MAV_MISSION_TYPE_FENCE) {
// We're about to write new geofence items, so take the lock. It will be released when
// switching back to idle
PX4_DEBUG("locking fence dataman items");
int ret = dm_lock(DM_KEY_FENCE_POINTS);
if (ret == 0) {
_geofence_locked = true;
} else {
PX4_ERR("locking failed (%i)", errno);
}
}
} else if (_state == MAVLINK_WPM_STATE_GETLIST) {
_time_last_recv = hrt_absolute_time();
if (_transfer_seq == 0) {
/* looks like our MISSION_REQUEST was lost, try again */
PX4_DEBUG("WPM: MISSION_COUNT %u from ID %u (again)", wpc.count, msg->sysid);
} else {
PX4_DEBUG("WPM: MISSION_COUNT ERROR: busy, already receiving seq %u", _transfer_seq);
_mavlink->send_statustext_critical("WPM: REJ. CMD: Busy");
send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR);
return;
}
} else {
PX4_DEBUG("WPM: MISSION_COUNT ERROR: busy, state %i", _state);
_mavlink->send_statustext_critical("WPM: IGN MISSION_COUNT: Busy");
send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR);
return;
}
send_mission_request(_transfer_partner_sysid, _transfer_partner_compid, _transfer_seq);
}
}
void
MavlinkMissionManager::switch_to_idle_state()
{
// when switching to idle, we *always* check if the lock was held and release it.
// This is to ensure we don't end up in a state where we forget to release it.
if (_geofence_locked) {
dm_unlock(DM_KEY_FENCE_POINTS);
_geofence_locked = false;
PX4_DEBUG("unlocking geofence");
}
_state = MAVLINK_WPM_STATE_IDLE;
}
void
MavlinkMissionManager::handle_mission_item(const mavlink_message_t *msg)
{
if (_int_mode) {
// It seems that we should be using the float mode, let's switch out of int mode.
_int_mode = false;
}
handle_mission_item_both(msg);
}
void
MavlinkMissionManager::handle_mission_item_int(const mavlink_message_t *msg)
{
if (!_int_mode) {
// It seems that we should be using the int mode, let's switch to it.
_int_mode = true;
}
handle_mission_item_both(msg);
}
void