-
Notifications
You must be signed in to change notification settings - Fork 13.7k
/
Copy pathmavlink_main.cpp
3408 lines (2701 loc) · 95.8 KB
/
mavlink_main.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-2023 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_main.cpp
* MAVLink 1.0 protocol implementation.
*
* @author Lorenz Meier <[email protected]>
* @author Julian Oes <[email protected]>
* @author Anton Babushkin <[email protected]>
*/
#include <termios.h>
#ifdef CONFIG_NET
#include <arpa/inet.h>
#include <netinet/in.h>
#include <netutils/netlib.h>
#endif
#include <containers/LockGuard.hpp>
#include <lib/geo/geo.h>
#include <lib/mathlib/mathlib.h>
#include <lib/systemlib/mavlink_log.h>
#include <lib/version/version.h>
#include <px4_platform_common/events.h>
#include <uORB/topics/event.h>
#include "mavlink_receiver.h"
#include "mavlink_main.h"
// Guard against MAVLink misconfiguration
#ifndef MAVLINK_CRC_EXTRA
#error MAVLINK_CRC_EXTRA has to be defined on PX4 systems
#endif
// Guard against flow control misconfiguration
#if defined (CRTSCTS) && defined (__PX4_NUTTX) && (CRTSCTS != (CRTS_IFLOW | CCTS_OFLOW))
#error The non-standard CRTSCTS define is incorrect. Fix this in the OS or replace with (CRTS_IFLOW | CCTS_OFLOW)
#endif
#ifdef CONFIG_NET
#define MAVLINK_NET_ADDED_STACK PX4_STACK_ADJUSTED(350)
#else
#define MAVLINK_NET_ADDED_STACK 0
#endif
#define FLOW_CONTROL_DISABLE_THRESHOLD 40 ///< picked so that some messages still would fit it.
#define MAX_DATA_RATE 10000000 ///< max data rate in bytes/s
#define MAIN_LOOP_DELAY 10000 ///< 100 Hz @ 1000 bytes/s data rate
static pthread_mutex_t mavlink_module_mutex = PTHREAD_MUTEX_INITIALIZER;
static pthread_mutex_t mavlink_event_buffer_mutex = PTHREAD_MUTEX_INITIALIZER;
events::EventBuffer *Mavlink::_event_buffer = nullptr;
Mavlink *mavlink_module_instances[MAVLINK_COMM_NUM_BUFFERS] {};
void mavlink_send_uart_bytes(mavlink_channel_t chan, const uint8_t *ch, int length) { mavlink_module_instances[chan]->send_bytes(ch, length); }
void mavlink_start_uart_send(mavlink_channel_t chan, int length) { mavlink_module_instances[chan]->send_start(length); }
void mavlink_end_uart_send(mavlink_channel_t chan, int length) { mavlink_module_instances[chan]->send_finish(); }
mavlink_status_t *mavlink_get_channel_status(uint8_t channel) { return mavlink_module_instances[channel]->get_status(); }
mavlink_message_t *mavlink_get_channel_buffer(uint8_t channel) { return mavlink_module_instances[channel]->get_buffer(); }
static void usage();
hrt_abstime Mavlink::_first_start_time = {0};
bool Mavlink::_boot_complete = false;
Mavlink::Mavlink() :
ModuleParams(nullptr),
_receiver(*this)
{
// initialise parameter cache
mavlink_update_parameters();
// save the current system- and component ID because we don't allow them to change during operation
int sys_id = _param_mav_sys_id.get();
if (sys_id > 0 && sys_id < 255) {
mavlink_system.sysid = sys_id;
}
int comp_id = _param_mav_comp_id.get();
if (comp_id > 0 && comp_id < 255) {
mavlink_system.compid = comp_id;
}
if (_first_start_time == 0) {
_first_start_time = hrt_absolute_time();
}
// ensure topic exists, otherwise we might lose first queued commands
if (orb_exists(ORB_ID(vehicle_command), 0) == PX4_ERROR) {
orb_advertise(ORB_ID(vehicle_command), nullptr);
}
_vehicle_command_sub.subscribe();
if (orb_exists(ORB_ID(event), 0) == PX4_ERROR) {
orb_advertise(ORB_ID(event), nullptr);
}
_event_sub.subscribe();
_telemetry_status_pub.advertise();
}
Mavlink::~Mavlink()
{
if (running()) {
/* task wakes up every 10ms or so at the longest */
request_stop();
/* wait for a second for the task to quit at our request */
unsigned i = 0;
do {
/* wait at least 1 second (10ms * 10) */
px4_usleep(10000);
/* if we have given up, kill it */
if (++i > 100) {
PX4_ERR("mavlink didn't stop, killing task %d", _task_id);
px4_task_delete(_task_id);
break;
}
} while (running());
}
if (_instance_id >= 0) {
mavlink_module_instances[_instance_id] = nullptr;
}
// if this instance was responsible for checking events then select a new mavlink instance
if (check_events()) {
check_events_disable();
// select next available instance
for (Mavlink *inst : mavlink_module_instances) {
if (inst) {
inst->check_events_enable();
break;
}
}
}
perf_free(_loop_perf);
perf_free(_loop_interval_perf);
perf_free(_send_byte_error_perf);
perf_free(_forwarding_error_perf);
}
void
Mavlink::mavlink_update_parameters()
{
updateParams();
int32_t proto = _param_mav_proto_ver.get();
if (_protocol_version_switch != proto) {
_protocol_version_switch = proto;
set_proto_version(proto);
}
if (_param_mav_type.get() < 0 || _param_mav_type.get() >= MAV_TYPE_ENUM_END) {
_param_mav_type.set(0);
_param_mav_type.commit_no_notification();
PX4_ERR("MAV_TYPE parameter invalid, resetting to 0.");
}
}
bool Mavlink::set_channel()
{
/* set channel according to instance id */
switch (_instance_id) {
case 0:
_channel = MAVLINK_COMM_0;
return true;
case 1:
_channel = MAVLINK_COMM_1;
return true;
case 2:
_channel = MAVLINK_COMM_2;
return true;
case 3:
_channel = MAVLINK_COMM_3;
return true;
#ifdef MAVLINK_COMM_4
case 4:
_channel = MAVLINK_COMM_4;
return true;
#endif
#ifdef MAVLINK_COMM_5
case 5:
_channel = MAVLINK_COMM_5;
return true;
#endif
#ifdef MAVLINK_COMM_6
case 6:
_channel = MAVLINK_COMM_6;
return true;
#endif
default:
PX4_ERR("instance ID %d is out of range", _instance_id);
break;
}
return false;
}
bool
Mavlink::set_instance_id()
{
LockGuard lg{mavlink_module_mutex};
// instance count
size_t inst_count = 0;
for (Mavlink *inst : mavlink_module_instances) {
if (inst != nullptr) {
inst_count++;
}
}
// if this is the first instance use it to check events
if (inst_count == 0) {
check_events_enable();
}
for (int instance_id = 0; instance_id < MAVLINK_COMM_NUM_BUFFERS; instance_id++) {
if (mavlink_module_instances[instance_id] == nullptr) {
mavlink_module_instances[instance_id] = this;
_instance_id = instance_id;
return true;
}
}
return false;
}
void
Mavlink::set_proto_version(unsigned version)
{
if ((version == 1 || version == 0) &&
((_protocol_version_switch == 0) || (_protocol_version_switch == 1))) {
get_status()->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
_protocol_version = 1;
} else if (version == 2 &&
((_protocol_version_switch == 0) || (_protocol_version_switch == 2))) {
get_status()->flags &= ~(MAVLINK_STATUS_FLAG_OUT_MAVLINK1);
_protocol_version = 2;
}
}
int
Mavlink::instance_count()
{
LockGuard lg{mavlink_module_mutex};
size_t inst_index = 0;
for (Mavlink *inst : mavlink_module_instances) {
if (inst != nullptr) {
inst_index++;
}
}
return inst_index;
}
Mavlink *
Mavlink::get_instance_for_device(const char *device_name)
{
LockGuard lg{mavlink_module_mutex};
for (Mavlink *inst : mavlink_module_instances) {
if (inst && (inst->_protocol == Protocol::SERIAL) && (strcmp(inst->_device_name, device_name) == 0)) {
return inst;
}
}
return nullptr;
}
#ifdef MAVLINK_UDP
Mavlink *
Mavlink::get_instance_for_network_port(unsigned long port)
{
LockGuard lg{mavlink_module_mutex};
for (Mavlink *inst : mavlink_module_instances) {
if (inst && (inst->_protocol == Protocol::UDP) && (inst->_network_port == port)) {
return inst;
}
}
return nullptr;
}
#endif // MAVLINK_UDP
int
Mavlink::destroy_all_instances()
{
PX4_INFO("waiting for instances to stop");
unsigned iterations = 0;
while (iterations < 1000) {
int running = 0;
pthread_mutex_lock(&mavlink_module_mutex);
for (Mavlink *inst_to_del : mavlink_module_instances) {
if (inst_to_del != nullptr) {
if (inst_to_del->running()) {
running++;
// set flag to stop thread and wait for all threads to finish
inst_to_del->request_stop();
}
}
}
pthread_mutex_unlock(&mavlink_module_mutex);
if (running == 0) {
break;
} else if (iterations > 1000) {
PX4_ERR("Couldn't stop all mavlink instances.");
return PX4_ERROR;
} else {
iterations++;
printf(".");
fflush(stdout);
px4_usleep(10000);
}
}
{
LockGuard lg{mavlink_module_mutex};
// we know all threads have exited, so it's safe to delete objects.
for (Mavlink *inst_to_del : mavlink_module_instances) {
delete inst_to_del;
}
}
{
LockGuard lg{mavlink_event_buffer_mutex};
delete _event_buffer;
_event_buffer = nullptr;
}
PX4_INFO("all instances stopped");
return OK;
}
int
Mavlink::get_status_all_instances(bool show_streams_status)
{
LockGuard lg{mavlink_module_mutex};
unsigned iterations = 0;
for (Mavlink *inst : mavlink_module_instances) {
if (inst != nullptr) {
printf("\ninstance #%u:\n", iterations);
if (show_streams_status) {
inst->display_status_streams();
} else {
inst->display_status();
}
iterations++;
}
}
/* return an error if there are no instances */
return (iterations == 0);
}
bool
Mavlink::serial_instance_exists(const char *device_name, Mavlink *self)
{
LockGuard lg{mavlink_module_mutex};
for (Mavlink *inst : mavlink_module_instances) {
/* don't compare with itself and with non serial instances*/
if (inst && (inst != self) && (inst->get_protocol() == Protocol::SERIAL) && !strcmp(device_name, inst->_device_name)) {
return true;
}
}
return false;
}
bool
Mavlink::component_was_seen(int system_id, int component_id, Mavlink &self)
{
LockGuard lg{mavlink_module_mutex};
for (Mavlink *inst : mavlink_module_instances) {
if (inst && (inst != &self) && (inst->_receiver.component_was_seen(system_id, component_id))) {
return true;
}
}
return false;
}
void
Mavlink::forward_message(const mavlink_message_t *msg, Mavlink *self)
{
const mavlink_msg_entry_t *meta = mavlink_get_msg_entry(msg->msgid);
int target_system_id = 0;
int target_component_id = 0;
// might be nullptr if message is unknown
if (meta) {
// Extract target system and target component if set
if (meta->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_SYSTEM) {
target_system_id = static_cast<uint8_t>((_MAV_PAYLOAD(msg))[meta->target_system_ofs]);
}
if (meta->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_COMPONENT) {
target_component_id = static_cast<uint8_t>((_MAV_PAYLOAD(msg))[meta->target_component_ofs]);
}
}
// If it's a message only for us, we keep it
if (target_system_id == self->get_system_id() && target_component_id == self->get_component_id()) {
return;
}
// We don't forward heartbeats unless it's specifically enabled.
if (msg->msgid == MAVLINK_MSG_ID_HEARTBEAT && !self->forward_heartbeats_enabled()) {
return;
}
LockGuard lg{mavlink_module_mutex};
for (Mavlink *inst : mavlink_module_instances) {
if (inst && (inst != self) && (inst->get_forwarding_on())) {
// Pass message only if target component was seen before
if (inst->_receiver.component_was_seen(target_system_id, target_component_id)) {
inst->pass_message(msg);
}
}
}
}
int
Mavlink::mavlink_open_uart(const int baud, const char *uart_name, const FLOW_CONTROL_MODE flow_control)
{
#ifndef B460800
#define B460800 460800
#endif
#ifndef B500000
#define B500000 500000
#endif
#ifndef B921600
#define B921600 921600
#endif
#ifndef B1000000
#define B1000000 1000000
#endif
/* process baud rate */
int speed;
switch (baud) {
case 0: speed = B0; break;
case 50: speed = B50; break;
case 75: speed = B75; break;
case 110: speed = B110; break;
case 134: speed = B134; break;
case 150: speed = B150; break;
case 200: speed = B200; break;
case 300: speed = B300; break;
case 600: speed = B600; break;
case 1200: speed = B1200; break;
case 1800: speed = B1800; break;
case 2400: speed = B2400; break;
case 4800: speed = B4800; break;
case 9600: speed = B9600; break;
case 19200: speed = B19200; break;
case 38400: speed = B38400; break;
case 57600: speed = B57600; break;
case 115200: speed = B115200; break;
case 230400: speed = B230400; break;
case 460800: speed = B460800; break;
case 500000: speed = B500000; break;
case 921600: speed = B921600; break;
case 1000000: speed = B1000000; break;
#ifdef B1500000
case 1500000: speed = B1500000; break;
#endif
#ifdef B2000000
case 2000000: speed = B2000000; break;
#endif
#ifdef B3000000
case 3000000: speed = B3000000; break;
#endif
default:
PX4_ERR("Unsupported baudrate: %d\n\tsupported examples:\n\t9600, 19200, 38400, 57600\t\n115200\n230400\n460800\n500000\n921600\n1000000\n",
baud);
return -EINVAL;
}
/* open uart */
_uart_fd = ::open(uart_name, O_RDWR | O_NOCTTY);
/*
* Return here in the iridium mode since the iridium driver does not
* support the subsequent function calls.
*/
if (_uart_fd < 0 || _mode == MAVLINK_MODE_IRIDIUM) {
return _uart_fd;
}
/* Try to set baud rate */
struct termios uart_config;
int termios_state;
/* Initialize the uart config */
if ((termios_state = tcgetattr(_uart_fd, &uart_config)) < 0) {
PX4_ERR("ERR GET CONF %s: %d\n", uart_name, termios_state);
::close(_uart_fd);
return -1;
}
/* Clear ONLCR flag (which appends a CR for every LF) */
uart_config.c_oflag &= ~ONLCR;
/* Set baud rate */
if (cfsetispeed(&uart_config, speed) < 0 || cfsetospeed(&uart_config, speed) < 0) {
PX4_ERR("ERR SET BAUD %s: %d\n", uart_name, termios_state);
::close(_uart_fd);
return -1;
}
#if defined(__PX4_LINUX) || defined(__PX4_DARWIN) || defined(__PX4_CYGWIN)
/* Put in raw mode */
cfmakeraw(&uart_config);
#endif
if ((termios_state = tcsetattr(_uart_fd, TCSANOW, &uart_config)) < 0) {
PX4_WARN("ERR SET CONF %s\n", uart_name);
::close(_uart_fd);
return -1;
}
/* setup hardware flow control */
if (setup_flow_control(flow_control) && (flow_control != FLOW_CONTROL_AUTO)) {
PX4_WARN("hardware flow control not supported");
}
return _uart_fd;
}
int
Mavlink::setup_flow_control(enum FLOW_CONTROL_MODE mode)
{
struct termios uart_config;
int ret = tcgetattr(_uart_fd, &uart_config);
if (mode != FLOW_CONTROL_OFF) {
uart_config.c_cflag |= CRTSCTS;
} else {
uart_config.c_cflag &= ~CRTSCTS;
}
ret = tcsetattr(_uart_fd, TCSANOW, &uart_config);
if (!ret) {
_flow_control_mode = mode;
}
return ret;
}
int
Mavlink::set_hil_enabled(bool hil_enabled)
{
int ret = OK;
/* enable HIL (only on links with sufficient bandwidth) */
if (hil_enabled && !_hil_enabled && _datarate > 5000) {
_hil_enabled = true;
ret = configure_stream("HIL_ACTUATOR_CONTROLS", 200.0f);
if (_param_sys_hitl.get() == 2) { // Simulation in Hardware enabled ?
configure_stream("HIL_STATE_QUATERNION", 25.0f); // ground truth to display the SIH
} else {
configure_stream("HIL_STATE_QUATERNION", 0.0f);
}
}
/* disable HIL */
if (!hil_enabled && _hil_enabled) {
_hil_enabled = false;
ret = configure_stream("HIL_ACTUATOR_CONTROLS", 0.0f);
configure_stream("HIL_STATE_QUATERNION", 0.0f);
}
return ret;
}
unsigned
Mavlink::get_free_tx_buf()
{
/*
* Check if the OS buffer is full and disable HW
* flow control if it continues to be full
*/
int buf_free = 0;
#if defined(MAVLINK_UDP)
// if we are using network sockets, return max length of one packet
if (get_protocol() == Protocol::UDP) {
# if defined(__PX4_POSIX)
return 1500 * 10; // Speed up FTP transfers
# else
return 1500;
# endif /* defined(__PX4_POSIX) */
} else
#endif // MAVLINK_UDP
{
#if defined(__PX4_NUTTX)
(void) ioctl(_uart_fd, FIONSPACE, (unsigned long)&buf_free);
#else
// No FIONSPACE on Linux todo:use SIOCOUTQ and queue size to emulate FIONSPACE
//Linux cp210x does not support TIOCOUTQ
buf_free = MAVLINK_MAX_PACKET_LEN;
#endif
if (_flow_control_mode == FLOW_CONTROL_AUTO && buf_free < FLOW_CONTROL_DISABLE_THRESHOLD) {
/* Disable hardware flow control in FLOW_CONTROL_AUTO mode:
* if no successful write since a defined time
* and if the last try was not the last successful write
*/
if (_last_write_try_time != 0 &&
hrt_elapsed_time(&_last_write_success_time) > 500_ms &&
_last_write_success_time != _last_write_try_time) {
setup_flow_control(FLOW_CONTROL_OFF);
}
}
}
return buf_free;
}
void Mavlink::send_start(int length)
{
pthread_mutex_lock(&_send_mutex);
_last_write_try_time = hrt_absolute_time();
// check if there is space in the buffer
if (length > (int)get_free_tx_buf()) {
// not enough space in buffer to send
count_txerrbytes(length);
_tstatus.tx_buffer_overruns++;
// prevent writes
_tx_buffer_low = true;
} else {
_tx_buffer_low = false;
}
}
void Mavlink::send_finish()
{
if (_tx_buffer_low || (_buf_fill == 0)) {
pthread_mutex_unlock(&_send_mutex);
return;
}
int ret = -1;
// send message to UART
if (get_protocol() == Protocol::SERIAL) {
ret = ::write(_uart_fd, _buf, _buf_fill);
}
#if defined(MAVLINK_UDP)
else if (get_protocol() == Protocol::UDP) {
# if defined(CONFIG_NET)
if (_src_addr_initialized) {
# endif // CONFIG_NET
ret = sendto(_socket_fd, _buf, _buf_fill, 0, (struct sockaddr *)&_src_addr, sizeof(_src_addr));
# if defined(CONFIG_NET)
}
# endif // CONFIG_NET
if ((_mode != MAVLINK_MODE_ONBOARD) && broadcast_enabled() &&
(!get_client_source_initialized() || !is_gcs_connected())) {
if (!_broadcast_address_found) {
find_broadcast_address();
}
if (_broadcast_address_found && _buf_fill > 0) {
int bret = sendto(_socket_fd, _buf, _buf_fill, 0, (struct sockaddr *)&_bcast_addr, sizeof(_bcast_addr));
if (bret <= 0) {
if (!_broadcast_failed_warned) {
PX4_ERR("sending broadcast failed, errno: %d: %s", errno, strerror(errno));
_broadcast_failed_warned = true;
}
} else {
_broadcast_failed_warned = false;
}
}
}
}
#endif // MAVLINK_UDP
if (ret == (int)_buf_fill) {
_tstatus.tx_message_count++;
count_txbytes(_buf_fill);
_last_write_success_time = _last_write_try_time;
} else {
count_txerrbytes(_buf_fill);
}
_buf_fill = 0;
pthread_mutex_unlock(&_send_mutex);
}
void Mavlink::send_bytes(const uint8_t *buf, unsigned packet_len)
{
if (!_tx_buffer_low) {
if (_buf_fill + packet_len < sizeof(_buf)) {
memcpy(&_buf[_buf_fill], buf, packet_len);
_buf_fill += packet_len;
} else {
perf_count(_send_byte_error_perf);
}
}
}
#ifdef MAVLINK_UDP
void Mavlink::find_broadcast_address()
{
struct ifconf ifconf;
int ret;
#if defined(__APPLE__) && defined(__MACH__) || defined(__CYGWIN__)
// On Mac, we can't determine the required buffer
// size in advance, so we just use what tends to work.
ifconf.ifc_len = 1024;
#else
// On Linux, we can determine the required size of the
// buffer first by providing NULL to ifc_req.
ifconf.ifc_req = nullptr;
ifconf.ifc_len = 0;
ret = ioctl(_socket_fd, SIOCGIFCONF, &ifconf);
if (ret != 0) {
PX4_WARN("getting required buffer size failed");
return;
}
#endif
PX4_DEBUG("need to allocate %d bytes", ifconf.ifc_len);
// Allocate buffer.
ifconf.ifc_req = (struct ifreq *)(new uint8_t[ifconf.ifc_len]);
if (ifconf.ifc_req == nullptr) {
PX4_ERR("Could not allocate ifconf buffer");
return;
}
memset(ifconf.ifc_req, 0, ifconf.ifc_len);
ret = ioctl(_socket_fd, SIOCGIFCONF, &ifconf);
if (ret != 0) {
PX4_ERR("getting network config failed");
delete[] ifconf.ifc_req;
return;
}
int offset = 0;
// Later used to point to next network interface in buffer.
struct ifreq *cur_ifreq = (struct ifreq *) & (((uint8_t *)ifconf.ifc_req)[offset]);
// The ugly `for` construct is used because it allows to use
// `continue` and `break`.
for (;
offset < (int)ifconf.ifc_len;
#if defined(__APPLE__) && defined(__MACH__)
// On Mac, to get to next entry in buffer, jump by the size of
// the interface name size plus whatever is greater, either the
// sizeof sockaddr or ifr_addr.sa_len.
offset += IF_NAMESIZE
+ (sizeof(struct sockaddr) > cur_ifreq->ifr_addr.sa_len ?
sizeof(struct sockaddr) : cur_ifreq->ifr_addr.sa_len)
#else
// On Linux, it's much easier to traverse the buffer, every entry
// has the constant length.
offset += sizeof(struct ifreq)
#endif
) {
// Point to next network interface in buffer.
cur_ifreq = (struct ifreq *) & (((uint8_t *)ifconf.ifc_req)[offset]);
PX4_DEBUG("looking at %s", cur_ifreq->ifr_name);
// ignore loopback network
if (strcmp(cur_ifreq->ifr_name, "lo") == 0 ||
strcmp(cur_ifreq->ifr_name, "lo0") == 0 ||
strcmp(cur_ifreq->ifr_name, "lo1") == 0 ||
strcmp(cur_ifreq->ifr_name, "lo2") == 0) {
PX4_DEBUG("skipping loopback");
continue;
}
struct in_addr &sin_addr = ((struct sockaddr_in *)&cur_ifreq->ifr_addr)->sin_addr;
// Accept network interfaces to local network only. This means it's an IP starting with:
// 192./172./10.
// Also see https://tools.ietf.org/html/rfc1918#section-3
uint8_t first_byte = sin_addr.s_addr & 0xFF;
if (first_byte != 192 && first_byte != 172 && first_byte != 10) {
continue;
}
if (!_broadcast_address_found) {
const struct in_addr netmask_addr = query_netmask_addr(_socket_fd, *cur_ifreq);
const struct in_addr broadcast_addr = compute_broadcast_addr(sin_addr, netmask_addr);
if (_interface_name && strstr(cur_ifreq->ifr_name, _interface_name) == nullptr) { continue; }
PX4_INFO("using network interface %s, IP: %s", cur_ifreq->ifr_name, inet_ntoa(sin_addr));
PX4_INFO("with netmask: %s", inet_ntoa(netmask_addr));
PX4_INFO("and broadcast IP: %s", inet_ntoa(broadcast_addr));
_bcast_addr.sin_family = AF_INET;
_bcast_addr.sin_addr = broadcast_addr;
_broadcast_address_found = true;
} else {
PX4_DEBUG("ignoring additional network interface %s, IP: %s",
cur_ifreq->ifr_name, inet_ntoa(sin_addr));
}
}
if (_broadcast_address_found) {
_bcast_addr.sin_port = htons(_remote_port);
int broadcast_opt = 1;
if (setsockopt(_socket_fd, SOL_SOCKET, SO_BROADCAST, &broadcast_opt, sizeof(broadcast_opt)) < 0) {
PX4_WARN("setting broadcast permission failed");
}
_broadcast_address_not_found_warned = false;
} else {
if (!_broadcast_address_not_found_warned) {
PX4_WARN("no broadcasting address found");
_broadcast_address_not_found_warned = true;
}
}
delete[] ifconf.ifc_req;
}
const in_addr Mavlink::query_netmask_addr(const int socket_fd, const ifreq &ifreq)
{
struct ifreq netmask_ifreq {};
strncpy(netmask_ifreq.ifr_name, ifreq.ifr_name, IF_NAMESIZE);
ioctl(socket_fd, SIOCGIFNETMASK, &netmask_ifreq);
return ((struct sockaddr_in *)&netmask_ifreq.ifr_addr)->sin_addr;
}
const in_addr Mavlink::compute_broadcast_addr(const in_addr &host_addr, const in_addr &netmask_addr)
{
struct in_addr broadcast_addr;
broadcast_addr.s_addr = ~netmask_addr.s_addr | host_addr.s_addr;
return broadcast_addr;
}
void Mavlink::init_udp()
{
PX4_DEBUG("Setting up UDP with port %hu", _network_port);
_myaddr.sin_family = AF_INET;
_myaddr.sin_addr.s_addr = htonl(INADDR_ANY);
_myaddr.sin_port = htons(_network_port);
if ((_socket_fd = socket(AF_INET, SOCK_DGRAM, 0)) < 0) {
PX4_WARN("create socket failed: %s", strerror(errno));
return;