-
Notifications
You must be signed in to change notification settings - Fork 1.5k
/
mavlink.c
1304 lines (1143 loc) · 49 KB
/
mavlink.c
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
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
/*
* telemetry_mavlink.c
*
* Author: Konstantin Sharlaimov
*/
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include <math.h>
#include "platform.h"
#if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_MAVLINK)
#include "build/build_config.h"
#include "build/debug.h"
#include "common/axis.h"
#include "common/color.h"
#include "common/maths.h"
#include "common/utils.h"
#include "common/string_light.h"
#include "config/feature.h"
#include "drivers/serial.h"
#include "drivers/time.h"
#include "drivers/display.h"
#include "drivers/osd_symbols.h"
#include "fc/config.h"
#include "fc/fc_core.h"
#include "fc/rc_controls.h"
#include "fc/rc_modes.h"
#include "fc/runtime_config.h"
#include "fc/settings.h"
#include "flight/failsafe.h"
#include "flight/imu.h"
#include "flight/mixer_profile.h"
#include "flight/pid.h"
#include "flight/servos.h"
#include "io/adsb.h"
#include "io/gps.h"
#include "io/ledstrip.h"
#include "io/serial.h"
#include "io/osd.h"
#include "navigation/navigation.h"
#include "navigation/navigation_private.h"
#include "rx/rx.h"
#include "rx/mavlink.h"
#include "sensors/acceleration.h"
#include "sensors/barometer.h"
#include "sensors/battery.h"
#include "sensors/boardalignment.h"
#include "sensors/gyro.h"
#include "sensors/pitotmeter.h"
#include "sensors/diagnostics.h"
#include "sensors/sensors.h"
#include "sensors/temperature.h"
#include "sensors/esc_sensor.h"
#include "telemetry/mavlink.h"
#include "telemetry/telemetry.h"
#include "blackbox/blackbox_io.h"
#include "scheduler/scheduler.h"
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunused-function"
#define MAVLINK_COMM_NUM_BUFFERS 1
#include "common/mavlink.h"
#pragma GCC diagnostic pop
#define TELEMETRY_MAVLINK_PORT_MODE MODE_RXTX
#define TELEMETRY_MAVLINK_MAXRATE 50
#define TELEMETRY_MAVLINK_DELAY ((1000 * 1000) / TELEMETRY_MAVLINK_MAXRATE)
/**
* MAVLink requires angles to be in the range -Pi..Pi.
* This converts angles from a range of 0..Pi to -Pi..Pi
*/
#define RADIANS_TO_MAVLINK_RANGE(angle) (angle > M_PIf) ? angle - (2 * M_PIf) : angle
/** @brief A mapping of plane flight modes for custom_mode field of heartbeat. */
typedef enum APM_PLANE_MODE
{
PLANE_MODE_MANUAL=0,
PLANE_MODE_CIRCLE=1,
PLANE_MODE_STABILIZE=2,
PLANE_MODE_TRAINING=3,
PLANE_MODE_ACRO=4,
PLANE_MODE_FLY_BY_WIRE_A=5,
PLANE_MODE_FLY_BY_WIRE_B=6,
PLANE_MODE_CRUISE=7,
PLANE_MODE_AUTOTUNE=8,
PLANE_MODE_AUTO=10,
PLANE_MODE_RTL=11,
PLANE_MODE_LOITER=12,
PLANE_MODE_TAKEOFF=13,
PLANE_MODE_AVOID_ADSB=14,
PLANE_MODE_GUIDED=15,
PLANE_MODE_INITIALIZING=16,
PLANE_MODE_QSTABILIZE=17,
PLANE_MODE_QHOVER=18,
PLANE_MODE_QLOITER=19,
PLANE_MODE_QLAND=20,
PLANE_MODE_QRTL=21,
PLANE_MODE_QAUTOTUNE=22,
PLANE_MODE_ENUM_END=23,
} APM_PLANE_MODE;
/** @brief A mapping of copter flight modes for custom_mode field of heartbeat. */
typedef enum APM_COPTER_MODE
{
COPTER_MODE_STABILIZE=0,
COPTER_MODE_ACRO=1,
COPTER_MODE_ALT_HOLD=2,
COPTER_MODE_AUTO=3,
COPTER_MODE_GUIDED=4,
COPTER_MODE_LOITER=5,
COPTER_MODE_RTL=6,
COPTER_MODE_CIRCLE=7,
COPTER_MODE_LAND=9,
COPTER_MODE_DRIFT=11,
COPTER_MODE_SPORT=13,
COPTER_MODE_FLIP=14,
COPTER_MODE_AUTOTUNE=15,
COPTER_MODE_POSHOLD=16,
COPTER_MODE_BRAKE=17,
COPTER_MODE_THROW=18,
COPTER_MODE_AVOID_ADSB=19,
COPTER_MODE_GUIDED_NOGPS=20,
COPTER_MODE_SMART_RTL=21,
COPTER_MODE_ENUM_END=22,
} APM_COPTER_MODE;
static serialPort_t *mavlinkPort = NULL;
static serialPortConfig_t *portConfig;
static bool mavlinkTelemetryEnabled = false;
static portSharing_e mavlinkPortSharing;
static uint8_t txbuff_free = 100;
static bool txbuff_valid = false;
/* MAVLink datastream rates in Hz */
static uint8_t mavRates[] = {
[MAV_DATA_STREAM_EXTENDED_STATUS] = 2, // 2Hz
[MAV_DATA_STREAM_RC_CHANNELS] = 1, // 1Hz
[MAV_DATA_STREAM_POSITION] = 2, // 2Hz
[MAV_DATA_STREAM_EXTRA1] = 3, // 3Hz
[MAV_DATA_STREAM_EXTRA2] = 2, // 2Hz, HEARTBEATs are important
[MAV_DATA_STREAM_EXTRA3] = 1 // 1Hz
};
#define MAXSTREAMS (sizeof(mavRates) / sizeof(mavRates[0]))
static timeUs_t lastMavlinkMessage = 0;
static uint8_t mavTicks[MAXSTREAMS];
static mavlink_message_t mavSendMsg;
static mavlink_message_t mavRecvMsg;
static mavlink_status_t mavRecvStatus;
static uint8_t mavSystemId = 1;
static uint8_t mavComponentId = MAV_COMP_ID_AUTOPILOT1;
static APM_COPTER_MODE inavToArduCopterMap(flightModeForTelemetry_e flightMode)
{
switch (flightMode)
{
case FLM_ACRO: return COPTER_MODE_ACRO;
case FLM_ACRO_AIR: return COPTER_MODE_ACRO;
case FLM_ANGLE: return COPTER_MODE_STABILIZE;
case FLM_HORIZON: return COPTER_MODE_STABILIZE;
case FLM_ANGLEHOLD: return COPTER_MODE_STABILIZE;
case FLM_ALTITUDE_HOLD: return COPTER_MODE_ALT_HOLD;
case FLM_POSITION_HOLD: return COPTER_MODE_POSHOLD;
case FLM_RTH: return COPTER_MODE_RTL;
case FLM_MISSION: return COPTER_MODE_AUTO;
case FLM_LAUNCH: return COPTER_MODE_THROW;
case FLM_FAILSAFE:
{
if (failsafePhase() == FAILSAFE_RETURN_TO_HOME) {
return COPTER_MODE_RTL;
} else if (failsafePhase() == FAILSAFE_LANDING) {
return COPTER_MODE_LAND;
} else {
// There is no valid mapping to ArduCopter
return COPTER_MODE_ENUM_END;
}
}
default: return COPTER_MODE_ENUM_END;
}
}
static APM_PLANE_MODE inavToArduPlaneMap(flightModeForTelemetry_e flightMode)
{
switch (flightMode)
{
case FLM_MANUAL: return PLANE_MODE_MANUAL;
case FLM_ACRO: return PLANE_MODE_ACRO;
case FLM_ACRO_AIR: return PLANE_MODE_ACRO;
case FLM_ANGLE: return PLANE_MODE_FLY_BY_WIRE_A;
case FLM_HORIZON: return PLANE_MODE_STABILIZE;
case FLM_ANGLEHOLD: return PLANE_MODE_STABILIZE;
case FLM_ALTITUDE_HOLD: return PLANE_MODE_FLY_BY_WIRE_B;
case FLM_POSITION_HOLD: return PLANE_MODE_LOITER;
case FLM_RTH: return PLANE_MODE_RTL;
case FLM_MISSION: return PLANE_MODE_AUTO;
case FLM_CRUISE: return PLANE_MODE_CRUISE;
case FLM_LAUNCH: return PLANE_MODE_TAKEOFF;
case FLM_FAILSAFE:
{
if (failsafePhase() == FAILSAFE_RETURN_TO_HOME) {
return PLANE_MODE_RTL;
}
else if (failsafePhase() == FAILSAFE_LANDING) {
return PLANE_MODE_AUTO;
}
else {
// There is no valid mapping to ArduPlane
return PLANE_MODE_ENUM_END;
}
}
default: return PLANE_MODE_ENUM_END;
}
}
static int mavlinkStreamTrigger(enum MAV_DATA_STREAM streamNum)
{
uint8_t rate = (uint8_t) mavRates[streamNum];
if (rate == 0) {
return 0;
}
if (mavTicks[streamNum] == 0) {
// we're triggering now, setup the next trigger point
if (rate > TELEMETRY_MAVLINK_MAXRATE) {
rate = TELEMETRY_MAVLINK_MAXRATE;
}
mavTicks[streamNum] = (TELEMETRY_MAVLINK_MAXRATE / rate);
return 1;
}
// count down at TASK_RATE_HZ
mavTicks[streamNum]--;
return 0;
}
void freeMAVLinkTelemetryPort(void)
{
closeSerialPort(mavlinkPort);
mavlinkPort = NULL;
mavlinkTelemetryEnabled = false;
}
void initMAVLinkTelemetry(void)
{
portConfig = findSerialPortConfig(FUNCTION_TELEMETRY_MAVLINK);
mavlinkPortSharing = determinePortSharing(portConfig, FUNCTION_TELEMETRY_MAVLINK);
}
void configureMAVLinkTelemetryPort(void)
{
if (!portConfig) {
return;
}
baudRate_e baudRateIndex = portConfig->telemetry_baudrateIndex;
if (baudRateIndex == BAUD_AUTO) {
// default rate for minimOSD
baudRateIndex = BAUD_57600;
}
mavlinkPort = openSerialPort(portConfig->identifier, FUNCTION_TELEMETRY_MAVLINK, NULL, NULL, baudRates[baudRateIndex], TELEMETRY_MAVLINK_PORT_MODE, SERIAL_NOT_INVERTED);
if (!mavlinkPort) {
return;
}
mavlinkTelemetryEnabled = true;
}
static void configureMAVLinkStreamRates(void)
{
mavRates[MAV_DATA_STREAM_EXTENDED_STATUS] = telemetryConfig()->mavlink.extended_status_rate;
mavRates[MAV_DATA_STREAM_RC_CHANNELS] = telemetryConfig()->mavlink.rc_channels_rate;
mavRates[MAV_DATA_STREAM_POSITION] = telemetryConfig()->mavlink.position_rate;
mavRates[MAV_DATA_STREAM_EXTRA1] = telemetryConfig()->mavlink.extra1_rate;
mavRates[MAV_DATA_STREAM_EXTRA2] = telemetryConfig()->mavlink.extra2_rate;
mavRates[MAV_DATA_STREAM_EXTRA3] = telemetryConfig()->mavlink.extra3_rate;
}
void checkMAVLinkTelemetryState(void)
{
bool newTelemetryEnabledValue = telemetryDetermineEnabledState(mavlinkPortSharing);
if (newTelemetryEnabledValue == mavlinkTelemetryEnabled) {
return;
}
if (newTelemetryEnabledValue) {
configureMAVLinkTelemetryPort();
configureMAVLinkStreamRates();
} else
freeMAVLinkTelemetryPort();
}
static void mavlinkSendMessage(void)
{
uint8_t mavBuffer[MAVLINK_MAX_PACKET_LEN];
mavlink_status_t* chan_state = mavlink_get_channel_status(MAVLINK_COMM_0);
if (telemetryConfig()->mavlink.version == 1) {
chan_state->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
} else {
chan_state->flags &= ~MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
}
int msgLength = mavlink_msg_to_send_buffer(mavBuffer, &mavSendMsg);
for (int i = 0; i < msgLength; i++) {
serialWrite(mavlinkPort, mavBuffer[i]);
}
}
void mavlinkSendSystemStatus(void)
{
// Receiver is assumed to be always present
uint32_t onboard_control_sensors_present = (MAV_SYS_STATUS_SENSOR_RC_RECEIVER);
// GYRO and RC are assumed as minimum requirements
uint32_t onboard_control_sensors_enabled = (MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_RC_RECEIVER);
uint32_t onboard_control_sensors_health = 0;
if (getHwGyroStatus() == HW_SENSOR_OK) {
onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_GYRO;
// Missing presence will report as sensor unhealthy
onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_GYRO;
}
hardwareSensorStatus_e accStatus = getHwAccelerometerStatus();
if (accStatus == HW_SENSOR_OK) {
onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_ACCEL;
onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_3D_ACCEL;
onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_ACCEL;
} else if (accStatus == HW_SENSOR_UNHEALTHY) {
onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_ACCEL;
onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_3D_ACCEL;
} else if (accStatus == HW_SENSOR_UNAVAILABLE) {
onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_3D_ACCEL;
}
hardwareSensorStatus_e compassStatus = getHwCompassStatus();
if (compassStatus == HW_SENSOR_OK) {
onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_MAG;
onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_3D_MAG;
onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_MAG;
} else if (compassStatus == HW_SENSOR_UNHEALTHY) {
onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_MAG;
onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_3D_MAG;
} else if (compassStatus == HW_SENSOR_UNAVAILABLE) {
onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_3D_MAG;
}
hardwareSensorStatus_e baroStatus = getHwBarometerStatus();
if (baroStatus == HW_SENSOR_OK) {
onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
} else if (baroStatus == HW_SENSOR_UNHEALTHY) {
onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
} else if (baroStatus == HW_SENSOR_UNAVAILABLE) {
onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
}
hardwareSensorStatus_e pitotStatus = getHwPitotmeterStatus();
if (pitotStatus == HW_SENSOR_OK) {
onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
} else if (pitotStatus == HW_SENSOR_UNHEALTHY) {
onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
} else if (pitotStatus == HW_SENSOR_UNAVAILABLE) {
onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
}
hardwareSensorStatus_e gpsStatus = getHwGPSStatus();
if (gpsStatus == HW_SENSOR_OK) {
onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_GPS;
onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_GPS;
onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_GPS;
} else if (gpsStatus == HW_SENSOR_UNHEALTHY) {
onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_GPS;
onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_GPS;
} else if (gpsStatus == HW_SENSOR_UNAVAILABLE) {
onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_GPS;
}
hardwareSensorStatus_e opFlowStatus = getHwOpticalFlowStatus();
if (opFlowStatus == HW_SENSOR_OK) {
onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
} else if (opFlowStatus == HW_SENSOR_UNHEALTHY) {
onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
} else if (opFlowStatus == HW_SENSOR_UNAVAILABLE) {
onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
}
hardwareSensorStatus_e rangefinderStatus = getHwRangefinderStatus();
if (rangefinderStatus == HW_SENSOR_OK) {
onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
} else if (rangefinderStatus == HW_SENSOR_UNHEALTHY) {
onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
} else if (rangefinderStatus == HW_SENSOR_UNAVAILABLE) {
onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
}
if (rxIsReceivingSignal() && rxAreFlightChannelsValid()) {
onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
}
#ifdef USE_BLACKBOX
// BLACKBOX is assumed enabled and present for boards with capability
onboard_control_sensors_present |= MAV_SYS_STATUS_LOGGING;
onboard_control_sensors_enabled |= MAV_SYS_STATUS_LOGGING;
// Unhealthy only for cases with not enough space to record
if (!isBlackboxDeviceFull()) {
onboard_control_sensors_health |= MAV_SYS_STATUS_LOGGING;
}
#endif
mavlink_msg_sys_status_pack(mavSystemId, mavComponentId, &mavSendMsg,
// onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present.
//Value of 0: not present. Value of 1: present. Indices according MAV_SYS_STATUS_SENSOR
onboard_control_sensors_present,
// onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled
onboard_control_sensors_enabled,
// onboard_control_sensors_health Bitmask showing which onboard controllers and sensors are operational or have an error.
onboard_control_sensors_health,
// load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
constrain(averageSystemLoadPercent*10, 0, 1000),
// voltage_battery Battery voltage, in millivolts (1 = 1 millivolt)
feature(FEATURE_VBAT) ? getBatteryVoltage() * 10 : 0,
// current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
isAmperageConfigured() ? getAmperage() : -1,
// battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery
feature(FEATURE_VBAT) ? calculateBatteryPercentage() : 100,
// drop_rate_comm Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
0,
// errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
0,
// errors_count1 Autopilot-specific errors
0,
// errors_count2 Autopilot-specific errors
0,
// errors_count3 Autopilot-specific errors
0,
// errors_count4 Autopilot-specific errors
0);
mavlinkSendMessage();
}
void mavlinkSendRCChannelsAndRSSI(void)
{
#define GET_CHANNEL_VALUE(x) ((rxRuntimeConfig.channelCount >= (x + 1)) ? rxGetChannelValue(x) : 0)
if (telemetryConfig()->mavlink.version == 1) {
mavlink_msg_rc_channels_raw_pack(mavSystemId, mavComponentId, &mavSendMsg,
// time_boot_ms Timestamp (milliseconds since system boot)
millis(),
// port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.
0,
// chan1_raw RC channel 1 value, in microseconds
GET_CHANNEL_VALUE(0),
// chan2_raw RC channel 2 value, in microseconds
GET_CHANNEL_VALUE(1),
// chan3_raw RC channel 3 value, in microseconds
GET_CHANNEL_VALUE(2),
// chan4_raw RC channel 4 value, in microseconds
GET_CHANNEL_VALUE(3),
// chan5_raw RC channel 5 value, in microseconds
GET_CHANNEL_VALUE(4),
// chan6_raw RC channel 6 value, in microseconds
GET_CHANNEL_VALUE(5),
// chan7_raw RC channel 7 value, in microseconds
GET_CHANNEL_VALUE(6),
// chan8_raw RC channel 8 value, in microseconds
GET_CHANNEL_VALUE(7),
// rssi Receive signal strength indicator, 0: 0%, 254: 100%
//https://github.com/mavlink/mavlink/issues/1027
scaleRange(getRSSI(), 0, 1023, 0, 254));
}
else {
mavlink_msg_rc_channels_pack(mavSystemId, mavComponentId, &mavSendMsg,
// time_boot_ms Timestamp (milliseconds since system boot)
millis(),
// Total number of RC channels being received.
rxRuntimeConfig.channelCount,
// chan1_raw RC channel 1 value, in microseconds
GET_CHANNEL_VALUE(0),
// chan2_raw RC channel 2 value, in microseconds
GET_CHANNEL_VALUE(1),
// chan3_raw RC channel 3 value, in microseconds
GET_CHANNEL_VALUE(2),
// chan4_raw RC channel 4 value, in microseconds
GET_CHANNEL_VALUE(3),
// chan5_raw RC channel 5 value, in microseconds
GET_CHANNEL_VALUE(4),
// chan6_raw RC channel 6 value, in microseconds
GET_CHANNEL_VALUE(5),
// chan7_raw RC channel 7 value, in microseconds
GET_CHANNEL_VALUE(6),
// chan8_raw RC channel 8 value, in microseconds
GET_CHANNEL_VALUE(7),
// chan9_raw RC channel 9 value, in microseconds
GET_CHANNEL_VALUE(8),
// chan10_raw RC channel 10 value, in microseconds
GET_CHANNEL_VALUE(9),
// chan11_raw RC channel 11 value, in microseconds
GET_CHANNEL_VALUE(10),
// chan12_raw RC channel 12 value, in microseconds
GET_CHANNEL_VALUE(11),
// chan13_raw RC channel 13 value, in microseconds
GET_CHANNEL_VALUE(12),
// chan14_raw RC channel 14 value, in microseconds
GET_CHANNEL_VALUE(13),
// chan15_raw RC channel 15 value, in microseconds
GET_CHANNEL_VALUE(14),
// chan16_raw RC channel 16 value, in microseconds
GET_CHANNEL_VALUE(15),
// chan17_raw RC channel 17 value, in microseconds
GET_CHANNEL_VALUE(16),
// chan18_raw RC channel 18 value, in microseconds
GET_CHANNEL_VALUE(17),
// rssi Receive signal strength indicator, 0: 0%, 254: 100%
//https://github.com/mavlink/mavlink/issues/1027
scaleRange(getRSSI(), 0, 1023, 0, 254));
}
#undef GET_CHANNEL_VALUE
mavlinkSendMessage();
}
#if defined(USE_GPS)
void mavlinkSendPosition(timeUs_t currentTimeUs)
{
uint8_t gpsFixType = 0;
if (!(sensors(SENSOR_GPS)
#ifdef USE_GPS_FIX_ESTIMATION
|| STATE(GPS_ESTIMATED_FIX)
#endif
))
return;
if (gpsSol.fixType == GPS_NO_FIX)
gpsFixType = 1;
else if (gpsSol.fixType == GPS_FIX_2D)
gpsFixType = 2;
else if (gpsSol.fixType == GPS_FIX_3D)
gpsFixType = 3;
mavlink_msg_gps_raw_int_pack(mavSystemId, mavComponentId, &mavSendMsg,
// time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
currentTimeUs,
// fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
gpsFixType,
// lat Latitude in 1E7 degrees
gpsSol.llh.lat,
// lon Longitude in 1E7 degrees
gpsSol.llh.lon,
// alt Altitude in 1E3 meters (millimeters) above MSL
gpsSol.llh.alt * 10,
// eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
gpsSol.eph,
// epv GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
gpsSol.epv,
// vel GPS ground speed (m/s * 100). If unknown, set to: 65535
gpsSol.groundSpeed,
// cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
gpsSol.groundCourse * 10,
// satellites_visible Number of satellites visible. If unknown, set to 255
gpsSol.numSat,
// alt_ellipsoid Altitude (above WGS84, EGM96 ellipsoid). Positive for up
0,
// h_acc Position uncertainty in mm,
gpsSol.eph * 10,
// v_acc Altitude uncertainty in mm,
gpsSol.epv * 10,
// vel_acc Speed uncertainty in mm (??)
0,
// hdg_acc Heading uncertainty in degE5
0,
// yaw Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use 65535 if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.
0);
mavlinkSendMessage();
// Global position
mavlink_msg_global_position_int_pack(mavSystemId, mavComponentId, &mavSendMsg,
// time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
currentTimeUs,
// lat Latitude in 1E7 degrees
gpsSol.llh.lat,
// lon Longitude in 1E7 degrees
gpsSol.llh.lon,
// alt Altitude in 1E3 meters (millimeters) above MSL
gpsSol.llh.alt * 10,
// relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters)
getEstimatedActualPosition(Z) * 10,
// [cm/s] Ground X Speed (Latitude, positive north)
getEstimatedActualVelocity(X),
// [cm/s] Ground Y Speed (Longitude, positive east)
getEstimatedActualVelocity(Y),
// [cm/s] Ground Z Speed (Altitude, positive down)
getEstimatedActualVelocity(Z),
// [cdeg] Vehicle heading (yaw angle) (0.0..359.99 degrees, 0=north)
DECIDEGREES_TO_CENTIDEGREES(attitude.values.yaw)
);
mavlinkSendMessage();
mavlink_msg_gps_global_origin_pack(mavSystemId, mavComponentId, &mavSendMsg,
// latitude Latitude (WGS84), expressed as * 1E7
GPS_home.lat,
// longitude Longitude (WGS84), expressed as * 1E7
GPS_home.lon,
// altitude Altitude(WGS84), expressed as * 1000
GPS_home.alt * 10, // FIXME
// time_usec Timestamp (microseconds since system boot)
// Use millis() * 1000 as micros() will overflow after 1.19 hours.
((uint64_t) millis()) * 1000);
mavlinkSendMessage();
}
#endif
void mavlinkSendAttitude(void)
{
mavlink_msg_attitude_pack(mavSystemId, mavComponentId, &mavSendMsg,
// time_boot_ms Timestamp (milliseconds since system boot)
millis(),
// roll Roll angle (rad)
RADIANS_TO_MAVLINK_RANGE(DECIDEGREES_TO_RADIANS(attitude.values.roll)),
// pitch Pitch angle (rad)
RADIANS_TO_MAVLINK_RANGE(DECIDEGREES_TO_RADIANS(-attitude.values.pitch)),
// yaw Yaw angle (rad)
RADIANS_TO_MAVLINK_RANGE(DECIDEGREES_TO_RADIANS(attitude.values.yaw)),
// rollspeed Roll angular speed (rad/s)
gyro.gyroADCf[FD_ROLL],
// pitchspeed Pitch angular speed (rad/s)
gyro.gyroADCf[FD_PITCH],
// yawspeed Yaw angular speed (rad/s)
gyro.gyroADCf[FD_YAW]);
mavlinkSendMessage();
}
void mavlinkSendHUDAndHeartbeat(void)
{
float mavAltitude = 0;
float mavGroundSpeed = 0;
float mavAirSpeed = 0;
float mavClimbRate = 0;
#if defined(USE_GPS)
// use ground speed if source available
if (sensors(SENSOR_GPS)
#ifdef USE_GPS_FIX_ESTIMATION
|| STATE(GPS_ESTIMATED_FIX)
#endif
) {
mavGroundSpeed = gpsSol.groundSpeed / 100.0f;
}
#endif
#if defined(USE_PITOT)
if (sensors(SENSOR_PITOT) && pitotIsHealthy()) {
mavAirSpeed = getAirspeedEstimate() / 100.0f;
}
#endif
// select best source for altitude
mavAltitude = getEstimatedActualPosition(Z) / 100.0f;
mavClimbRate = getEstimatedActualVelocity(Z) / 100.0f;
int16_t thr = getThrottlePercent(osdUsingScaledThrottle());
mavlink_msg_vfr_hud_pack(mavSystemId, mavComponentId, &mavSendMsg,
// airspeed Current airspeed in m/s
mavAirSpeed,
// groundspeed Current ground speed in m/s
mavGroundSpeed,
// heading Current heading in degrees, in compass units (0..360, 0=north)
DECIDEGREES_TO_DEGREES(attitude.values.yaw),
// throttle Current throttle setting in integer percent, 0 to 100
thr,
// alt Current altitude (MSL), in meters, if we have surface or baro use them, otherwise use GPS (less accurate)
mavAltitude,
// climb Current climb rate in meters/second
mavClimbRate);
mavlinkSendMessage();
uint8_t mavModes = MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
if (ARMING_FLAG(ARMED))
mavModes |= MAV_MODE_FLAG_SAFETY_ARMED;
uint8_t mavSystemType;
switch (mixerConfig()->platformType)
{
case PLATFORM_MULTIROTOR:
mavSystemType = MAV_TYPE_QUADROTOR;
break;
case PLATFORM_TRICOPTER:
mavSystemType = MAV_TYPE_TRICOPTER;
break;
case PLATFORM_AIRPLANE:
mavSystemType = MAV_TYPE_FIXED_WING;
break;
case PLATFORM_ROVER:
mavSystemType = MAV_TYPE_GROUND_ROVER;
break;
case PLATFORM_BOAT:
mavSystemType = MAV_TYPE_SURFACE_BOAT;
break;
case PLATFORM_HELICOPTER:
mavSystemType = MAV_TYPE_HELICOPTER;
break;
default:
mavSystemType = MAV_TYPE_GENERIC;
break;
}
flightModeForTelemetry_e flm = getFlightModeForTelemetry();
uint8_t mavCustomMode;
if (STATE(FIXED_WING_LEGACY)) {
mavCustomMode = (uint8_t)inavToArduPlaneMap(flm);
}
else {
mavCustomMode = (uint8_t)inavToArduCopterMap(flm);
}
if (flm != FLM_MANUAL) {
mavModes |= MAV_MODE_FLAG_STABILIZE_ENABLED;
}
if (flm == FLM_POSITION_HOLD || flm == FLM_RTH || flm == FLM_MISSION) {
mavModes |= MAV_MODE_FLAG_GUIDED_ENABLED;
}
uint8_t mavSystemState = 0;
if (ARMING_FLAG(ARMED)) {
if (failsafeIsActive()) {
mavSystemState = MAV_STATE_CRITICAL;
}
else {
mavSystemState = MAV_STATE_ACTIVE;
}
}
else if (areSensorsCalibrating()) {
mavSystemState = MAV_STATE_CALIBRATING;
}
else {
mavSystemState = MAV_STATE_STANDBY;
}
mavlink_msg_heartbeat_pack(mavSystemId, mavComponentId, &mavSendMsg,
// type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
mavSystemType,
// autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM
MAV_AUTOPILOT_GENERIC,
// base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h
mavModes,
// custom_mode A bitfield for use for autopilot-specific flags.
mavCustomMode,
// system_status System status flag, see MAV_STATE ENUM
mavSystemState);
mavlinkSendMessage();
}
void mavlinkSendBatteryTemperatureStatusText(void)
{
uint16_t batteryVoltages[MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN];
uint16_t batteryVoltagesExt[MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_EXT_LEN];
memset(batteryVoltages, UINT16_MAX, sizeof(batteryVoltages));
memset(batteryVoltagesExt, 0, sizeof(batteryVoltagesExt));
if (feature(FEATURE_VBAT)) {
uint8_t batteryCellCount = getBatteryCellCount();
if (batteryCellCount > 0) {
for (int cell=0; cell < batteryCellCount && cell < MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN + MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_EXT_LEN; cell++) {
if (cell < MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN) {
batteryVoltages[cell] = getBatteryAverageCellVoltage() * 10;
} else {
batteryVoltagesExt[cell-MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN] = getBatteryAverageCellVoltage() * 10;
}
}
}
else {
batteryVoltages[0] = getBatteryVoltage() * 10;
}
}
else {
batteryVoltages[0] = 0;
}
mavlink_msg_battery_status_pack(mavSystemId, mavComponentId, &mavSendMsg,
// id Battery ID
0,
// battery_function Function of the battery
MAV_BATTERY_FUNCTION_UNKNOWN,
// type Type (chemistry) of the battery
MAV_BATTERY_TYPE_UNKNOWN,
// temperature Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature
INT16_MAX,
// voltages Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value.
batteryVoltages,
// current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
isAmperageConfigured() ? getAmperage() : -1,
// current_consumed Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate
isAmperageConfigured() ? getMAhDrawn() : -1,
// energy_consumed Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate
isAmperageConfigured() ? getMWhDrawn()*36 : -1,
// battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery);
feature(FEATURE_VBAT) ? calculateBatteryPercentage() : -1,
// time_remaining Remaining battery time, 0: autopilot does not provide remaining battery time estimate
0, // TODO this could easily be implemented
// charge_state State for extent of discharge, provided by autopilot for warning or external reactions
0,
// voltages_ext Battery voltages for cells 11 to 14. Cells above the valid cell count for this battery should have a value of 0, where zero indicates not supported (note, this is different than for the voltages field and allows empty byte truncation). If the measured value is 0 then 1 should be sent instead.
batteryVoltagesExt,
// mode Battery mode. Default (0) is that battery mode reporting is not supported or battery is in normal-use mode.
0,
// fault_bitmask Fault/health indications. These should be set when charge_state is MAV_BATTERY_CHARGE_STATE_FAILED or MAV_BATTERY_CHARGE_STATE_UNHEALTHY (if not, fault reporting is not supported).
0);
mavlinkSendMessage();
int16_t temperature;
sensors(SENSOR_BARO) ? getBaroTemperature(&temperature) : getIMUTemperature(&temperature);
mavlink_msg_scaled_pressure_pack(mavSystemId, mavComponentId, &mavSendMsg,
millis(),
0,
0,
temperature * 10,
0);
mavlinkSendMessage();
// FIXME - Status text is limited to boards with USE_OSD
#ifdef USE_OSD
char buff[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN] = {" "};
textAttributes_t elemAttr = osdGetSystemMessage(buff, sizeof(buff), false);
if (buff[0] != SYM_BLANK) {
MAV_SEVERITY severity = MAV_SEVERITY_NOTICE;
if (TEXT_ATTRIBUTES_HAVE_BLINK(elemAttr)) {
severity = MAV_SEVERITY_CRITICAL;
} else if TEXT_ATTRIBUTES_HAVE_INVERTED(elemAttr) {
severity = MAV_SEVERITY_WARNING;
}
mavlink_msg_statustext_pack(mavSystemId, mavComponentId, &mavSendMsg,
(uint8_t)severity,
buff,
0,
0);
mavlinkSendMessage();
}
#endif
}
void processMAVLinkTelemetry(timeUs_t currentTimeUs)
{
// is executed @ TELEMETRY_MAVLINK_MAXRATE rate
if (mavlinkStreamTrigger(MAV_DATA_STREAM_EXTENDED_STATUS)) {
mavlinkSendSystemStatus();
}
if (mavlinkStreamTrigger(MAV_DATA_STREAM_RC_CHANNELS)) {
mavlinkSendRCChannelsAndRSSI();
}
#ifdef USE_GPS
if (mavlinkStreamTrigger(MAV_DATA_STREAM_POSITION)) {
mavlinkSendPosition(currentTimeUs);
}
#endif
if (mavlinkStreamTrigger(MAV_DATA_STREAM_EXTRA1)) {
mavlinkSendAttitude();
}
if (mavlinkStreamTrigger(MAV_DATA_STREAM_EXTRA2)) {
mavlinkSendHUDAndHeartbeat();
}
if (mavlinkStreamTrigger(MAV_DATA_STREAM_EXTRA3)) {
mavlinkSendBatteryTemperatureStatusText();
}
}
static bool handleIncoming_MISSION_CLEAR_ALL(void)
{
mavlink_mission_clear_all_t msg;
mavlink_msg_mission_clear_all_decode(&mavRecvMsg, &msg);
// Check if this message is for us
if (msg.target_system == mavSystemId) {
resetWaypointList();
mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_ACCEPTED, MAV_MISSION_TYPE_MISSION);
mavlinkSendMessage();
return true;
}
return false;
}
// Static state for MISSION UPLOAD transaction (starting with MISSION_COUNT)
static int incomingMissionWpCount = 0;
static int incomingMissionWpSequence = 0;
static bool handleIncoming_MISSION_COUNT(void)
{
mavlink_mission_count_t msg;
mavlink_msg_mission_count_decode(&mavRecvMsg, &msg);
// Check if this message is for us
if (msg.target_system == mavSystemId) {
if (msg.count <= NAV_MAX_WAYPOINTS) {
incomingMissionWpCount = msg.count; // We need to know how many items to request
incomingMissionWpSequence = 0;
mavlink_msg_mission_request_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, incomingMissionWpSequence, MAV_MISSION_TYPE_MISSION);
mavlinkSendMessage();
return true;
}
else if (ARMING_FLAG(ARMED)) {
mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION);
mavlinkSendMessage();
return true;
}
else {
mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_NO_SPACE, MAV_MISSION_TYPE_MISSION);
mavlinkSendMessage();
return true;
}
}
return false;
}
static bool handleIncoming_MISSION_ITEM(void)
{
mavlink_mission_item_t msg;
mavlink_msg_mission_item_decode(&mavRecvMsg, &msg);
// Check if this message is for us
if (msg.target_system == mavSystemId) {
// Check supported values first
if (ARMING_FLAG(ARMED)) {
mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION);
mavlinkSendMessage();
return true;
}