-
Notifications
You must be signed in to change notification settings - Fork 18.2k
/
Copy pathGCS_Common.cpp
7241 lines (6380 loc) · 224 KB
/
GCS_Common.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
/*
Common GCS MAVLink functions for all vehicle types
This program 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.
This program 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 this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include "GCS_config.h"
#if HAL_GCS_ENABLED
#include "GCS.h"
#include <AC_Fence/AC_Fence.h>
#include <AP_Compass/AP_Compass.h>
#include <AP_ADSB/AP_ADSB.h>
#include <AP_AdvancedFailsafe/AP_AdvancedFailsafe.h>
#include <AP_AHRS/AP_AHRS.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Arming/AP_Arming.h>
#include <AP_InternalError/AP_InternalError.h>
#include <AP_Logger/AP_Logger.h>
#include <AP_OpticalFlow/AP_OpticalFlow.h>
#include <AP_Vehicle/AP_Vehicle.h>
#include <AP_RangeFinder/AP_RangeFinder.h>
#include <AP_RangeFinder/AP_RangeFinder_Backend.h>
#include <AP_Airspeed/AP_Airspeed.h>
#include <AP_Camera/AP_Camera.h>
#include <AP_Gripper/AP_Gripper.h>
#include <AC_Sprayer/AC_Sprayer.h>
#include <AP_BLHeli/AP_BLHeli.h>
#include <AP_Relay/AP_Relay.h>
#include <AP_RSSI/AP_RSSI.h>
#include <AP_RTC/AP_RTC.h>
#include <AP_Scheduler/AP_Scheduler.h>
#include <AP_SerialManager/AP_SerialManager.h>
#include <AP_RCTelemetry/AP_Spektrum_Telem.h>
#include <AP_Mount/AP_Mount.h>
#include <AP_Common/AP_FWVersion.h>
#include <AP_VisualOdom/AP_VisualOdom.h>
#include <AP_Baro/AP_Baro.h>
#include <AP_EFI/AP_EFI.h>
#include <AP_Proximity/AP_Proximity.h>
#include <AP_Scripting/AP_Scripting.h>
#include <SRV_Channel/SRV_Channel.h>
#include <AP_Winch/AP_Winch.h>
#include <AP_Mission/AP_Mission.h>
#include <AP_OpenDroneID/AP_OpenDroneID.h>
#include <AP_OSD/AP_OSD.h>
#include <AP_RCTelemetry/AP_CRSF_Telem.h>
#include <AP_RPM/AP_RPM.h>
#include <AP_AIS/AP_AIS.h>
#include <AP_Filesystem/AP_Filesystem.h>
#include <AP_Frsky_Telem/AP_Frsky_Telem.h>
#include <RC_Channel/RC_Channel.h>
#include <AP_VisualOdom/AP_VisualOdom.h>
#include <AP_KDECAN/AP_KDECAN.h>
#include <AP_LandingGear/AP_LandingGear.h>
#include <AP_Landing/AP_Landing_config.h>
#include "MissionItemProtocol_Waypoints.h"
#include "MissionItemProtocol_Rally.h"
#include "MissionItemProtocol_Fence.h"
#include <AP_Notify/AP_Notify.h>
#include <AP_Vehicle/AP_Vehicle_config.h>
#include <stdio.h>
#if AP_RADIO_ENABLED
#include <AP_Radio/AP_Radio.h>
#include <AP_BoardConfig/AP_BoardConfig.h>
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include <SITL/SITL.h>
#endif
#if HAL_MAX_CAN_PROTOCOL_DRIVERS
#include <AP_CANManager/AP_CANManager.h>
#include <AP_Common/AP_Common.h>
#include <AP_PiccoloCAN/AP_PiccoloCAN.h>
#include <AP_DroneCAN/AP_DroneCAN.h>
#endif
#include <AP_BattMonitor/AP_BattMonitor_config.h>
#if AP_BATTERY_ENABLED
#include <AP_BattMonitor/AP_BattMonitor.h>
#endif
#include <AP_GPS/AP_GPS.h>
#include <AP_RCProtocol/AP_RCProtocol_config.h>
#if AP_RCPROTOCOL_ENABLED
#include <AP_RCProtocol/AP_RCProtocol.h>
#endif
#if HAL_WITH_IO_MCU
#include <AP_IOMCU/AP_IOMCU.h>
extern AP_IOMCU iomcu;
#endif
#include <ctype.h>
extern const AP_HAL::HAL& hal;
struct GCS_MAVLINK::LastRadioStatus GCS_MAVLINK::last_radio_status;
uint8_t GCS_MAVLINK::mavlink_active = 0;
uint8_t GCS_MAVLINK::chan_is_streaming = 0;
uint32_t GCS_MAVLINK::reserve_param_space_start_ms;
// private channels are ones used for point-to-point protocols, and
// don't get broadcasts or fwded packets
uint8_t GCS_MAVLINK::mavlink_private = 0;
GCS *GCS::_singleton = nullptr;
GCS_MAVLINK_InProgress GCS_MAVLINK_InProgress::in_progress_tasks[1];
uint32_t GCS_MAVLINK_InProgress::last_check_ms;
GCS_MAVLINK::GCS_MAVLINK(GCS_MAVLINK_Parameters ¶meters,
AP_HAL::UARTDriver &uart)
{
_port = &uart;
streamRates = parameters.streamRates;
}
bool GCS_MAVLINK::init(uint8_t instance)
{
// get associated mavlink channel
chan = (mavlink_channel_t)(MAVLINK_COMM_0 + instance);
if (!valid_channel(chan)) {
return false;
}
// find instance of MAVLink protocol; the protocol_match method in
// AP_SerialManager means this will match MAVLink2 and MAVLinkHL,
// too:
uartstate = AP::serialmanager().find_protocol_instance(AP_SerialManager::SerialProtocol_MAVLink, instance);
if (uartstate == nullptr) {
return false;
}
// and init the gcs instance
// whether this port is considered "private" is stored on the uart
// rather than in our own parameters:
if (uartstate->option_enabled(AP_HAL::UARTDriver::OPTION_MAVLINK_NO_FORWARD)) {
set_channel_private(chan);
}
/*
Now try to cope with SiK radios that may be stuck in bootloader
mode because CTS was held while powering on. This tells the
bootloader to wait for a firmware. It affects any SiK radio with
CTS connected that is externally powered. To cope we send 0x30
0x20 at 115200 on startup, which tells the bootloader to reset
and boot normally
*/
_port->begin(115200);
AP_HAL::UARTDriver::flow_control old_flow_control = _port->get_flow_control();
_port->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);
for (uint8_t i=0; i<3; i++) {
hal.scheduler->delay(1);
_port->write(0x30);
_port->write(0x20);
}
// since tcdrain() and TCSADRAIN may not be implemented...
hal.scheduler->delay(1);
_port->set_flow_control(old_flow_control);
// now change back to desired baudrate
_port->begin(uartstate->baudrate());
mavlink_comm_port[chan] = _port;
const auto mavlink_protocol = uartstate->get_protocol();
if (mavlink_protocol == AP_SerialManager::SerialProtocol_MAVLink2 ||
mavlink_protocol == AP_SerialManager::SerialProtocol_MAVLinkHL) {
// load signing key
load_signing_key();
} else {
// user has asked to only send MAVLink1
_channel_status.flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
}
#if HAL_HIGH_LATENCY2_ENABLED
if (mavlink_protocol == AP_SerialManager::SerialProtocol_MAVLinkHL) {
is_high_latency_link = true;
}
#endif
return true;
}
void GCS_MAVLINK::send_meminfo(void)
{
unsigned __brkval = 0;
uint32_t memory = hal.util->available_memory();
mavlink_msg_meminfo_send(chan, __brkval, MIN(memory, 0xFFFFU), memory);
}
// report power supply status
void GCS_MAVLINK::send_power_status(void)
{
if (!gcs().vehicle_initialised()) {
// avoid unnecessary errors being reported to user
return;
}
mavlink_msg_power_status_send(chan,
hal.analogin->board_voltage() * 1000,
hal.analogin->servorail_voltage() * 1000,
hal.analogin->power_status_flags());
}
#if AP_SCHEDULER_ENABLED
// cap the MAVLink message rate. It can't be greater than 0.8 * SCHED_LOOP_RATE
uint16_t GCS_MAVLINK::cap_message_interval(uint16_t interval_ms) const
{
if (interval_ms == 0) {
return 0;
}
if (interval_ms*800 < AP::scheduler().get_loop_period_us()) {
return AP::scheduler().get_loop_period_us()/800.0f;
}
return interval_ms;
}
#endif
#if HAL_WITH_MCU_MONITORING
// report MCU voltage/temperature status
void GCS_MAVLINK::send_mcu_status(void)
{
if (!gcs().vehicle_initialised()) {
// avoid unnecessary errors being reported to user
return;
}
mavlink_msg_mcu_status_send(chan,
0, // only one MCU
hal.analogin->mcu_temperature() * 100,
hal.analogin->mcu_voltage() * 1000,
hal.analogin->mcu_voltage_min() * 1000,
hal.analogin->mcu_voltage_max() * 1000);
}
#endif
#if AP_BATTERY_ENABLED
// returns the battery remaining percentage if valid, -1 otherwise
int8_t GCS_MAVLINK::battery_remaining_pct(const uint8_t instance) const {
uint8_t percentage;
return AP::battery().capacity_remaining_pct(percentage, instance) ? MIN(percentage, INT8_MAX) : -1;
}
void GCS_MAVLINK::send_battery_status(const uint8_t instance) const
{
// catch the battery backend not supporting the required number of cells
static_assert(sizeof(AP_BattMonitor::cells) >= (sizeof(uint16_t) * MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN),
"Not enough battery cells for the MAVLink message");
const AP_BattMonitor &battery = AP::battery();
float temp;
bool got_temperature = battery.get_temperature(temp, instance);
// prepare arrays of individual cell voltages
uint16_t cell_mvolts[MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN];
uint16_t cell_mvolts_ext[MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_EXT_LEN];
const uint16_t max_cell_mV = 0xFFFEU;
const uint16_t invalid_cell_mV = 0xFFFFU;
if (battery.has_cell_voltages(instance)) {
const AP_BattMonitor::cells& batt_cells = battery.get_cell_voltages(instance);
static_assert(sizeof(cell_mvolts) <= sizeof(batt_cells.cells), "cell array length not large enough");
// copy the first 10 cells
memcpy(cell_mvolts, batt_cells.cells, sizeof(cell_mvolts));
// 11 ... 14 use a second cell_volts_ext array
for (uint8_t i = 0; i < MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_EXT_LEN; i++) {
if (MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN+i < uint8_t(ARRAY_SIZE(batt_cells.cells))) {
cell_mvolts_ext[i] = batt_cells.cells[MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN+i];
} else {
cell_mvolts_ext[i] = 0;
}
}
/*
now adjust voltages to cope with two things:
1) we may be reporting sag corrected voltage
2) the battery may have more cells than can be reported by the backend, so the actual voltage may be higher than the sum
*/
const float voltage_mV = battery.gcs_voltage(instance) * 1e3f;
float voltage_mV_sum = 0;
uint8_t non_zero_cell_count = 0;
for (uint8_t i=0; i<MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN; i++) {
if (cell_mvolts[i] > 0 && cell_mvolts[i] != invalid_cell_mV) {
non_zero_cell_count++;
voltage_mV_sum += cell_mvolts[i];
}
}
for (uint8_t i=0; i<MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_EXT_LEN; i++) {
if (cell_mvolts_ext[i] > 0 && cell_mvolts_ext[i] != invalid_cell_mV) {
non_zero_cell_count++;
voltage_mV_sum += cell_mvolts_ext[i];
}
}
if (voltage_mV > voltage_mV_sum && non_zero_cell_count > 0) {
// distribute the extra voltage over the non-zero cells
uint32_t extra_mV = (voltage_mV - voltage_mV_sum) / non_zero_cell_count;
for (uint8_t i=0; i<MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN; i++) {
if (cell_mvolts[i] > 0 && cell_mvolts[i] != invalid_cell_mV) {
cell_mvolts[i] = MIN(cell_mvolts[i] + extra_mV, max_cell_mV);
}
}
for (uint8_t i=0; i<MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_EXT_LEN; i++) {
if (cell_mvolts_ext[i] > 0 && cell_mvolts_ext[i] != invalid_cell_mV) {
cell_mvolts_ext[i] = MIN(cell_mvolts_ext[i] + extra_mV, max_cell_mV);
}
}
}
} else {
// for battery monitors that cannot provide voltages for individual cells the battery's total voltage is put into the first cell
// if the total voltage cannot fit into a single field, the remainder into subsequent fields.
// the GCS can then recover the pack voltage by summing all non ignored cell values an we can report a pack up to 655.34 V
float voltage_mV = battery.gcs_voltage(instance) * 1e3f;
for (uint8_t i = 0; i < MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN; i++) {
if (voltage_mV < 0.001f) {
// too small to send to the GCS, set it to the no cell value
cell_mvolts[i] = UINT16_MAX;
} else {
cell_mvolts[i] = MIN(voltage_mV, max_cell_mV); // Can't send more then UINT16_MAX - 1 in a cell
voltage_mV -= max_cell_mV;
}
}
for (uint8_t i = 0; i < MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_EXT_LEN; i++) {
cell_mvolts_ext[i] = 0;
}
}
float current, consumed_mah, consumed_wh;
const int8_t percentage = battery_remaining_pct(instance);
if (battery.current_amps(current, instance)) {
current = constrain_float(current * 100,-INT16_MAX,INT16_MAX);
} else {
current = -1;
}
if (!battery.consumed_mah(consumed_mah, instance)) {
consumed_mah = -1;
}
if (battery.consumed_wh(consumed_wh, instance)) {
consumed_wh *= 36;
} else {
consumed_wh = -1;
}
uint32_t time_remaining;
if (!battery.time_remaining(time_remaining, instance)) {
time_remaining = 0;
}
mavlink_msg_battery_status_send(chan,
instance, // id
MAV_BATTERY_FUNCTION_UNKNOWN, // function
MAV_BATTERY_TYPE_UNKNOWN, // type
got_temperature ? ((int16_t) (temp * 100)) : INT16_MAX, // temperature. INT16_MAX if unknown
cell_mvolts, // cell voltages
current, // current in centiampere
consumed_mah, // total consumed current in milliampere.hour
consumed_wh, // consumed energy in hJ (hecto-Joules)
constrain_int16(percentage, -1, 100),
time_remaining, // time remaining, seconds
battery.get_mavlink_charge_state(instance), // battery charge state
cell_mvolts_ext, // Cell 11..14 voltages
0, // battery mode
battery.get_mavlink_fault_bitmask(instance)); // fault_bitmask
}
// returns true if all battery instances were reported
bool GCS_MAVLINK::send_battery_status()
{
const AP_BattMonitor &battery = AP::battery();
for(uint8_t i = 0; i < AP_BATT_MONITOR_MAX_INSTANCES; i++) {
const uint8_t battery_id = (last_battery_status_idx + 1) % AP_BATT_MONITOR_MAX_INSTANCES;
const auto configured_type = battery.configured_type(battery_id);
if (configured_type != AP_BattMonitor::Type::NONE &&
configured_type == battery.allocated_type(battery_id) &&
!battery.option_is_set(battery_id, AP_BattMonitor_Params::Options::InternalUseOnly)) {
CHECK_PAYLOAD_SIZE(BATTERY_STATUS);
send_battery_status(battery_id);
last_battery_status_idx = battery_id;
return true;
} else {
last_battery_status_idx = battery_id;
}
}
return true;
}
#endif // AP_BATTERY_ENABLED
#if AP_RANGEFINDER_ENABLED
void GCS_MAVLINK::send_distance_sensor(const AP_RangeFinder_Backend *sensor, const uint8_t instance) const
{
if (!sensor->has_data()) {
return;
}
int8_t quality_pct = sensor->signal_quality_pct();
// ardupilot defines this field as -1 is unknown, 0 is poor, 100 is excellent
// mavlink defines this field as 0 is unknown, 1 is invalid, 100 is perfect
uint8_t quality;
if (quality_pct == RangeFinder::SIGNAL_QUALITY_UNKNOWN) {
quality = 0;
} else if (quality_pct > 1 && quality_pct <= RangeFinder::SIGNAL_QUALITY_MAX) {
quality = quality_pct;
} else {
quality = 1;
}
mavlink_msg_distance_sensor_send(
chan,
AP_HAL::millis(), // time since system boot TODO: take time of measurement
MIN(sensor->min_distance() * 100, 65535),// minimum distance the sensor can measure in centimeters
MIN(sensor->max_distance() * 100, 65535),// maximum distance the sensor can measure in centimeters
MIN(sensor->distance() * 100, 65535), // current distance reading
sensor->get_mav_distance_sensor_type(), // type from MAV_DISTANCE_SENSOR enum
instance, // onboard ID of the sensor == instance
sensor->orientation(), // direction the sensor faces from MAV_SENSOR_ORIENTATION enum
0, // Measurement covariance in centimeters, 0 for unknown / invalid readings
0, // horizontal FOV
0, // vertical FOV
(const float *)nullptr, // quaternion of sensor orientation for MAV_SENSOR_ROTATION_CUSTOM
quality); // Signal quality of the sensor. 0 = unknown/unset signal quality, 1 = invalid signal, 100 = perfect signal.
}
#endif // AP_RANGEFINDER_ENABLED
// send any and all distance_sensor messages. This starts by sending
// any distance sensors not used by a Proximity sensor, then sends the
// proximity sensor ones.
void GCS_MAVLINK::send_distance_sensor()
{
#if AP_RANGEFINDER_ENABLED
RangeFinder *rangefinder = RangeFinder::get_singleton();
if (rangefinder == nullptr) {
return;
}
// if we have a proximity backend that utilizes rangefinders cull
// sending them here, and allow the later proximity code to manage
// them
bool filter_possible_proximity_sensors = false;
#if HAL_PROXIMITY_ENABLED
AP_Proximity *proximity = AP_Proximity::get_singleton();
if (proximity != nullptr) {
for (uint8_t i = 0; i < proximity->num_sensors(); i++) {
#if AP_PROXIMITY_RANGEFINDER_ENABLED
if (proximity->get_type(i) == AP_Proximity::Type::RangeFinder) {
filter_possible_proximity_sensors = true;
}
#endif
}
}
#endif
for (uint8_t i = 0; i < RANGEFINDER_MAX_INSTANCES; i++) {
if (!HAVE_PAYLOAD_SPACE(chan, DISTANCE_SENSOR)) {
return;
}
AP_RangeFinder_Backend *sensor = rangefinder->get_backend(i);
if (sensor == nullptr) {
continue;
}
enum Rotation orient = sensor->orientation();
if (!filter_possible_proximity_sensors ||
(orient > ROTATION_YAW_315 && orient != ROTATION_PITCH_90)) {
send_distance_sensor(sensor, i);
}
}
#endif // AP_RANGEFINDER_ENABLED
#if HAL_PROXIMITY_ENABLED
send_proximity();
#endif
}
#if AP_RANGEFINDER_ENABLED
void GCS_MAVLINK::send_rangefinder() const
{
RangeFinder *rangefinder = RangeFinder::get_singleton();
if (rangefinder == nullptr) {
return;
}
AP_RangeFinder_Backend *s = rangefinder->find_instance(ROTATION_PITCH_270);
if (s == nullptr) {
return;
}
mavlink_msg_rangefinder_send(
chan,
s->distance(),
s->voltage_mv() * 0.001f);
}
#endif
#if HAL_PROXIMITY_ENABLED
void GCS_MAVLINK::send_proximity()
{
AP_Proximity *proximity = AP_Proximity::get_singleton();
if (proximity == nullptr) {
return; // this is wrong, but pretend we sent data and don't requeue
}
// get min/max distances
const uint16_t dist_min = (uint16_t)(proximity->distance_min() * 100.0f); // minimum distance the sensor can measure in centimeters
const uint16_t dist_max = (uint16_t)(proximity->distance_max() * 100.0f); // maximum distance the sensor can measure in centimeters
// send horizontal distances
if (proximity->get_status() == AP_Proximity::Status::Good) {
Proximity_Distance_Array dist_array;
if (proximity->get_horizontal_distances(dist_array)) {
for (uint8_t i = 0; i < PROXIMITY_MAX_DIRECTION; i++) {
if (!HAVE_PAYLOAD_SPACE(chan, DISTANCE_SENSOR)) {
return;
}
if (dist_array.valid(i)) {
proximity_ever_valid_bitmask |= (1U << i);
} else if (!(proximity_ever_valid_bitmask & (1U << i))) {
// we've never sent this distance out, so we don't
// need to send an invalid one.
continue;
}
mavlink_msg_distance_sensor_send(
chan,
AP_HAL::millis(), // time since system boot
dist_min, // minimum distance the sensor can measure in centimeters
dist_max, // maximum distance the sensor can measure in centimeters
(uint16_t)(dist_array.distance[i] * 100.0f), // current distance reading
MAV_DISTANCE_SENSOR_LASER, // type from MAV_DISTANCE_SENSOR enum
PROXIMITY_SENSOR_ID_START + i, // onboard ID of the sensor
dist_array.orientation[i], // direction the sensor faces from MAV_SENSOR_ORIENTATION enum
0, // Measurement covariance in centimeters, 0 for unknown / invalid readings
0, 0, nullptr, 0);
}
}
}
// send upward distance
float dist_up;
if (proximity->get_upward_distance(dist_up)) {
if (!HAVE_PAYLOAD_SPACE(chan, DISTANCE_SENSOR)) {
return;
}
mavlink_msg_distance_sensor_send(
chan,
AP_HAL::millis(), // time since system boot
dist_min, // minimum distance the sensor can measure in centimeters
dist_max, // maximum distance the sensor can measure in centimeters
(uint16_t)(dist_up * 100.0f), // current distance reading
MAV_DISTANCE_SENSOR_LASER, // type from MAV_DISTANCE_SENSOR enum
PROXIMITY_SENSOR_ID_START + PROXIMITY_MAX_DIRECTION + 1, // onboard ID of the sensor
MAV_SENSOR_ROTATION_PITCH_90, // direction upwards
0, // Measurement covariance in centimeters, 0 for unknown / invalid readings
0, 0, nullptr, 0);
}
}
#endif // HAL_PROXIMITY_ENABLED
#if AP_AHRS_ENABLED
// report AHRS2 state
void GCS_MAVLINK::send_ahrs2()
{
const AP_AHRS &ahrs = AP::ahrs();
Vector3f euler;
Location loc {};
// we want one or both of these, use | to avoid short-circuiting:
if (uint8_t(ahrs.get_secondary_attitude(euler)) |
uint8_t(ahrs.get_secondary_position(loc))) {
mavlink_msg_ahrs2_send(chan,
euler.x,
euler.y,
euler.z,
loc.alt*1.0e-2f,
loc.lat,
loc.lng);
}
}
#endif // AP_AHRS_ENABLED
MissionItemProtocol *GCS::get_prot_for_mission_type(const MAV_MISSION_TYPE mission_type) const
{
if (mission_type >= ARRAY_SIZE(missionitemprotocols)) {
return nullptr;
}
return missionitemprotocols[mission_type];
}
// handle a request for the number of items we have stored for a mission type:
void GCS_MAVLINK::handle_mission_request_list(const mavlink_message_t &msg)
{
// decode
mavlink_mission_request_list_t packet;
mavlink_msg_mission_request_list_decode(&msg, &packet);
MissionItemProtocol *prot = gcs().get_prot_for_mission_type((MAV_MISSION_TYPE)packet.mission_type);
if (prot == nullptr) {
mavlink_msg_mission_ack_send(chan,
msg.sysid,
msg.compid,
MAV_MISSION_UNSUPPORTED,
packet.mission_type);
return;
}
prot->handle_mission_request_list(*this, packet, msg);
}
/*
handle a MISSION_REQUEST mavlink packet
*/
void GCS_MAVLINK::handle_mission_request_int(const mavlink_message_t &msg)
{
// decode
mavlink_mission_request_int_t packet;
mavlink_msg_mission_request_int_decode(&msg, &packet);
MissionItemProtocol *prot = gcs().get_prot_for_mission_type((MAV_MISSION_TYPE)packet.mission_type);
if (prot == nullptr) {
return;
}
prot->handle_mission_request_int(*this, packet, msg);
}
#if AP_MAVLINK_MSG_MISSION_REQUEST_ENABLED
void GCS_MAVLINK::handle_mission_request(const mavlink_message_t &msg)
{
// decode
mavlink_mission_request_t packet;
mavlink_msg_mission_request_decode(&msg, &packet);
MissionItemProtocol *prot = gcs().get_prot_for_mission_type((MAV_MISSION_TYPE)packet.mission_type);
if (prot == nullptr) {
return;
}
prot->handle_mission_request(*this, packet, msg);
}
#endif
// returns a MISSION_STATE numeration value best describing out
// current mission state.
MISSION_STATE GCS_MAVLINK::mission_state(const AP_Mission &mission) const
{
if (!mission.present()) {
return MISSION_STATE_NO_MISSION;
}
switch (mission.state()) {
case AP_Mission::mission_state::MISSION_STOPPED:
return MISSION_STATE_NOT_STARTED;
case AP_Mission::mission_state::MISSION_RUNNING:
return MISSION_STATE_ACTIVE;
case AP_Mission::mission_state::MISSION_COMPLETE:
return MISSION_STATE_COMPLETE;
}
// compiler ensures we can't get here as no default case in above enumeration
return MISSION_STATE_UNKNOWN;
}
void GCS_MAVLINK::send_mission_current(const class AP_Mission &mission, uint16_t seq)
{
auto num_commands = mission.num_commands();
if (num_commands > 0) {
// exclude home location from the count; see message definition.
num_commands -= 1;
}
#if AP_VEHICLE_ENABLED
const uint8_t mission_mode = AP::vehicle()->current_mode_requires_mission() ? 1 : 0;
#else
const uint8_t mission_mode = 0;
#endif
mavlink_msg_mission_current_send(
chan,
seq,
num_commands, // total
mission_state(mission), // mission_state
mission_mode); // mission_mode
}
#if AP_MAVLINK_MISSION_SET_CURRENT_ENABLED
/*
handle a MISSION_SET_CURRENT mavlink packet
Note that there exists a relatively new mavlink DO command,
MAV_CMD_DO_SET_MISSION_CURRENT which provides an acknowledgement
that the command has been received, rather than the GCS having to
rely on getting back an identical sequence number as some currently
do.
*/
void GCS_MAVLINK::handle_mission_set_current(AP_Mission &mission, const mavlink_message_t &msg)
{
// send_received_message_deprecation_warning("MISSION_SET_CURRENT");
// decode
mavlink_mission_set_current_t packet;
mavlink_msg_mission_set_current_decode(&msg, &packet);
// set current command
if (mission.set_current_cmd(packet.seq)) {
// because MISSION_SET_CURRENT is a message not a command,
// there is not ACK associated with us successfully changing
// our waypoint. Some GCSs use the fact we return exactly the
// same mission sequence number in this packet as an ACK - so
// if they send a MISSION_SET_CURRENT with seq number of 4
// then they expect to receive a MISSION_CURRENT message with
// exactly that sequence number in it, even if ArduPilot never
// actually holds that as a sequence number (e.g. packet.seq==0).
if (HAVE_PAYLOAD_SPACE(chan, MISSION_CURRENT)) {
send_mission_current(mission, packet.seq);
} else {
// schedule it for later:
send_message(MSG_CURRENT_WAYPOINT);
}
}
}
#endif // AP_MAVLINK_MISSION_SET_CURRENT_ENABLED
/*
handle a MISSION_COUNT mavlink packet
*/
void GCS_MAVLINK::handle_mission_count(const mavlink_message_t &msg)
{
// decode
mavlink_mission_count_t packet;
mavlink_msg_mission_count_decode(&msg, &packet);
MissionItemProtocol *prot = gcs().get_prot_for_mission_type((MAV_MISSION_TYPE)packet.mission_type);
if (prot == nullptr) {
mavlink_msg_mission_ack_send(chan,
msg.sysid,
msg.compid,
MAV_MISSION_UNSUPPORTED,
packet.mission_type);
return;
}
prot->handle_mission_count(*this, packet, msg);
}
/*
handle a MISSION_CLEAR_ALL mavlink packet
*/
void GCS_MAVLINK::handle_mission_clear_all(const mavlink_message_t &msg)
{
// decode
mavlink_mission_clear_all_t packet;
mavlink_msg_mission_clear_all_decode(&msg, &packet);
const MAV_MISSION_TYPE mission_type = (MAV_MISSION_TYPE)packet.mission_type;
MissionItemProtocol *prot = gcs().get_prot_for_mission_type(mission_type);
if (prot == nullptr) {
send_mission_ack(msg, mission_type, MAV_MISSION_UNSUPPORTED);
return;
}
prot->handle_mission_clear_all(*this, msg);
}
bool GCS_MAVLINK::requesting_mission_items() const
{
for (const auto *prot : gcs().missionitemprotocols) {
if (prot && prot->receiving && prot->active_link_is(this)) {
return true;
}
}
return false;
}
void GCS_MAVLINK::handle_mission_write_partial_list(const mavlink_message_t &msg)
{
// decode
mavlink_mission_write_partial_list_t packet;
mavlink_msg_mission_write_partial_list_decode(&msg, &packet);
MissionItemProtocol *use_prot = gcs().get_prot_for_mission_type((MAV_MISSION_TYPE)packet.mission_type);
if (use_prot == nullptr) {
send_mission_ack(msg, (MAV_MISSION_TYPE)packet.mission_type, MAV_MISSION_UNSUPPORTED);
return;
}
use_prot->handle_mission_write_partial_list(*this, msg, packet);
}
#if HAL_MOUNT_ENABLED
/*
pass mavlink messages to the AP_Mount singleton
*/
void GCS_MAVLINK::handle_mount_message(const mavlink_message_t &msg)
{
AP_Mount *mount = AP::mount();
if (mount == nullptr) {
return;
}
mount->handle_message(chan, msg);
}
#endif
/*
pass parameter value messages through to mount library
*/
void GCS_MAVLINK::handle_param_value(const mavlink_message_t &msg)
{
#if HAL_MOUNT_ENABLED
AP_Mount *mount = AP::mount();
if (mount == nullptr) {
return;
}
mount->handle_param_value(msg);
#endif
}
void GCS_MAVLINK::send_text(MAV_SEVERITY severity, const char *fmt, ...) const
{
va_list arg_list;
va_start(arg_list, fmt);
gcs().send_textv(severity, fmt, arg_list, (1<<chan));
va_end(arg_list);
}
float GCS_MAVLINK::telemetry_radio_rssi()
{
if (AP_HAL::millis() - last_radio_status.received_ms > 5000) {
// telemetry radio has disappeared?!
return 0;
}
if (last_radio_status.rssi == 255) {
// see RADIO_STATUS packet definition
return 0;
}
return last_radio_status.rssi/254.0f;
}
bool GCS_MAVLINK::last_txbuf_is_greater(uint8_t txbuf_limit)
{
if (AP_HAL::millis() - last_radio_status.received_ms > 5000) {
// stale report
return true;
}
return last_radio_status.txbuf > txbuf_limit;
}
void GCS_MAVLINK::handle_radio_status(const mavlink_message_t &msg)
{
mavlink_radio_t packet;
mavlink_msg_radio_decode(&msg, &packet);
const uint32_t now = AP_HAL::millis();
last_radio_status.received_ms = now;
last_radio_status.rssi = packet.rssi;
// record if the GCS has been receiving radio messages from
// the aircraft
if (packet.remrssi != 0) {
last_radio_status.remrssi_ms = now;
}
last_radio_status.txbuf = packet.txbuf;
// use the state of the transmit buffer in the radio to
// control the stream rate, giving us adaptive software
// flow control
if (packet.txbuf < 20 && stream_slowdown_ms < 2000) {
// we are very low on space - slow down a lot
stream_slowdown_ms += 60;
} else if (packet.txbuf < 50 && stream_slowdown_ms < 2000) {
// we are a bit low on space, slow down slightly
stream_slowdown_ms += 20;
} else if (packet.txbuf > 95 && stream_slowdown_ms > 200) {
// the buffer has plenty of space, speed up a lot
stream_slowdown_ms -= 40;
} else if (packet.txbuf > 90 && stream_slowdown_ms != 0) {
// the buffer has enough space, speed up a bit
if (stream_slowdown_ms > 20) {
stream_slowdown_ms -= 20;
} else {
stream_slowdown_ms = 0;
}
}
#if GCS_DEBUG_SEND_MESSAGE_TIMINGS
if (stream_slowdown_ms > max_slowdown_ms) {
max_slowdown_ms = stream_slowdown_ms;
}
#endif
#if HAL_LOGGING_ENABLED
//log rssi, noise, etc if logging Performance monitoring data
if (AP::logger().should_log(log_radio_bit())) {
AP::logger().Write_Radio(packet);
}
#endif
}
void GCS_MAVLINK::handle_mission_item(const mavlink_message_t &msg)
{
mavlink_mission_item_int_t mission_item_int;
bool send_mission_item_warning = false;
if (msg.msgid == MAVLINK_MSG_ID_MISSION_ITEM) {
mavlink_mission_item_t mission_item;
mavlink_msg_mission_item_decode(&msg, &mission_item);
#if AP_MISSION_ENABLED
MAV_MISSION_RESULT ret = AP_Mission::convert_MISSION_ITEM_to_MISSION_ITEM_INT(mission_item, mission_item_int);
if (ret != MAV_MISSION_ACCEPTED) {
const MAV_MISSION_TYPE type = (MAV_MISSION_TYPE)mission_item_int.mission_type;
send_mission_ack(msg, type, ret);
return;
}
#else
// No mission library, so we can't convert from MISSION_ITEM
// to MISSION_ITEM_INT. Since we shouldn't be receiving fence
// or rally items via MISSION_ITEM, we don't need to work hard
// here, just fail:
const MAV_MISSION_TYPE type = (MAV_MISSION_TYPE)mission_item.mission_type;
send_mission_ack(msg, type, MAV_MISSION_UNSUPPORTED);
return;
#endif
send_mission_item_warning = true;
} else {
mavlink_msg_mission_item_int_decode(&msg, &mission_item_int);
}
const MAV_MISSION_TYPE type = (MAV_MISSION_TYPE)mission_item_int.mission_type;
#if AP_MISSION_ENABLED
const uint8_t current = mission_item_int.current;
if (type == MAV_MISSION_TYPE_MISSION && (current == 2 || current == 3)) {
struct AP_Mission::Mission_Command cmd = {};
MAV_MISSION_RESULT result = AP_Mission::mavlink_int_to_mission_cmd(mission_item_int, cmd);
if (result != MAV_MISSION_ACCEPTED) {
//decode failed
send_mission_ack(msg, MAV_MISSION_TYPE_MISSION, result);
return;
}
// guided or change-alt
if (current == 2) {
// current = 2 is a flag to tell us this is a "guided mode"
// waypoint and not for the mission
result = (handle_guided_request(cmd) ? MAV_MISSION_ACCEPTED
: MAV_MISSION_ERROR) ;
} else if (current == 3) {
//current = 3 is a flag to tell us this is a alt change only
// add home alt if needed
handle_change_alt_request(cmd);
// verify we received the command
result = MAV_MISSION_ACCEPTED;
}
send_mission_ack(msg, MAV_MISSION_TYPE_MISSION, result);
return;
}
#endif
// not a guided-mode reqest
MissionItemProtocol *prot = gcs().get_prot_for_mission_type(type);
if (prot == nullptr) {
send_mission_ack(msg, type, MAV_MISSION_UNSUPPORTED);
return;
}
if (send_mission_item_warning) {
prot->send_mission_item_warning();
}
if (!prot->receiving) {
send_mission_ack(msg, type, MAV_MISSION_ERROR);
return;
}
prot->handle_mission_item(msg, mission_item_int);
}
ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) const
{
// MSG_NEXT_MISSION_REQUEST doesn't correspond to a mavlink message directly.
// It is used to request the next waypoint after receiving one.
// MSG_NEXT_PARAM doesn't correspond to a mavlink message directly.
// It is used to send the next parameter in a stream after sending one