49 #include <nuttx/fs/fs.h> 51 #include <arpa/inet.h> 52 #include <drivers/device/device.h> 53 #include <sys/socket.h> 56 #if defined(CONFIG_NET) || !defined(__PX4_NUTTX) 58 #include <netinet/in.h> 73 #include <systemlib/uthash/utlist.h> 74 #include <uORB/topics/mavlink_log.h> 75 #include <uORB/topics/mission_result.h> 76 #include <uORB/topics/radio_status.h> 77 #include <uORB/topics/telemetry_status.h> 86 #define DEFAULT_REMOTE_PORT_UDP 14550 87 #define DEFAULT_DEVICE_NAME "/dev/ttyS1" 88 #define HASH_PARAM "_HASH_CHECK" 117 static int start(
int argc,
char *argv[]);
122 void display_status();
127 void display_status_streams();
129 static int stream_command(
int argc,
char *argv[]);
131 static int instance_count();
133 static Mavlink *new_instance();
135 static Mavlink *get_instance(
int instance);
137 static Mavlink *get_instance_for_device(
const char *device_name);
139 static Mavlink *get_instance_for_network_port(
unsigned long port);
141 mavlink_message_t *get_buffer() {
return &_mavlink_buffer; }
143 mavlink_status_t *get_status() {
return &_mavlink_status; }
152 void set_proto_version(
unsigned version);
154 static int destroy_all_instances();
156 static int get_status_all_instances(
bool show_streams_status);
158 static bool instance_exists(
const char *device_name, Mavlink *
self);
160 static void forward_message(
const mavlink_message_t *msg, Mavlink *
self);
162 static int get_uart_fd(
unsigned index);
164 int get_uart_fd()
const {
return _uart_fd; }
180 const char *_device_name{DEFAULT_DEVICE_NAME};
183 MAVLINK_MODE_NORMAL = 0,
185 MAVLINK_MODE_ONBOARD,
189 MAVLINK_MODE_IRIDIUM,
190 MAVLINK_MODE_MINIMAL,
191 MAVLINK_MODE_EXTVISION,
196 enum BROADCAST_MODE {
197 BROADCAST_MODE_OFF = 0,
199 BROADCAST_MODE_MULTICAST
202 enum FLOW_CONTROL_MODE {
203 FLOW_CONTROL_OFF = 0,
208 static const char *mavlink_mode_str(
enum MAVLINK_MODE mode)
211 case MAVLINK_MODE_NORMAL:
214 case MAVLINK_MODE_CUSTOM:
217 case MAVLINK_MODE_ONBOARD:
220 case MAVLINK_MODE_OSD:
223 case MAVLINK_MODE_MAGIC:
226 case MAVLINK_MODE_CONFIG:
229 case MAVLINK_MODE_IRIDIUM:
232 case MAVLINK_MODE_MINIMAL:
235 case MAVLINK_MODE_EXTVISION:
243 enum MAVLINK_MODE get_mode() {
return _mode; }
245 bool get_hil_enabled() {
return _hil_enabled; }
247 bool get_use_hil_gps() {
return _param_mav_usehilgps.get(); }
249 bool get_forward_externalsp() {
return _param_mav_fwdextsp.get(); }
251 bool get_flow_control_enabled() {
return _flow_control_mode; }
253 bool get_forwarding_on() {
return _forwarding_on; }
255 bool is_connected() {
return (hrt_elapsed_time(&_tstatus.heartbeat_time) < 3_s); }
257 bool broadcast_enabled() {
return _param_mav_broadcast.get() == BROADCAST_MODE_ON; }
265 static void set_boot_complete();
272 unsigned get_free_tx_buf();
274 static int start_helper(
int argc,
char *argv[]);
284 int set_hil_enabled(
bool hil_enabled);
318 void send_bytes(
const uint8_t *buf,
unsigned packet_len);
330 void resend_message(mavlink_message_t *msg) { _mavlink_resend_uart(_channel, msg); }
332 void handle_message(
const mavlink_message_t *msg);
343 int get_instance_id()
const {
return _instance_id; }
350 int enable_flow_control(
enum FLOW_CONTROL_MODE enabled);
352 mavlink_channel_t get_channel()
const {
return _channel; }
354 void configure_stream_threadsafe(
const char *stream_name,
float rate = -1.0f);
356 orb_advert_t *get_mavlink_log_pub() {
return &_mavlink_log_pub; }
363 void send_statustext_info(
const char *
string);
370 void send_statustext_critical(
const char *
string);
377 void send_statustext_emergency(
const char *
string);
388 void send_statustext(
unsigned char severity,
const char *
string);
393 void send_autopilot_capabilites();
398 void send_protocol_version();
400 List<MavlinkStream *> &get_streams() {
return _streams; }
402 float get_rate_mult()
const {
return _rate_mult; }
404 float get_baudrate() {
return _baudrate; }
407 void set_has_received_messages(
bool received_messages) { _received_messages = received_messages; }
408 bool get_has_received_messages() {
return _received_messages; }
409 void set_wait_to_transmit(
bool wait) { _wait_to_transmit = wait; }
410 bool get_wait_to_transmit() {
return _wait_to_transmit; }
411 bool should_transmit() {
return (_transmitting_enabled && _boot_complete && (!_wait_to_transmit || (_wait_to_transmit && _received_messages))); }
413 bool message_buffer_write(
const void *ptr,
int size);
415 void lockMessageBufferMutex(
void) { pthread_mutex_lock(&_message_buffer_mutex); }
416 void unlockMessageBufferMutex(
void) { pthread_mutex_unlock(&_message_buffer_mutex); }
438 void set_telemetry_status_type(uint8_t type) { _tstatus.type = type; }
440 void update_radio_status(
const radio_status_s &radio_status);
442 ringbuffer::RingBuffer *get_logbuffer() {
return &_logbuffer; }
444 unsigned get_system_type() {
return _param_mav_type.get(); }
446 Protocol get_protocol() {
return _protocol; }
448 unsigned short get_network_port() {
return _network_port; }
450 unsigned short get_remote_port() {
return _remote_port; }
452 int get_socket_fd() {
return _socket_fd; };
454 bool _task_should_exit{
false};
457 const in_addr query_netmask_addr(
const int socket_fd,
const ifreq &ifreq);
459 const in_addr compute_broadcast_addr(
const in_addr &host_addr,
const in_addr &netmask_addr);
462 #if defined(CONFIG_NET) || defined(__PX4_POSIX) 463 struct sockaddr_in &get_client_source_address() {
return _src_addr; }
465 void set_client_source_initialized() { _src_addr_initialized =
true; }
467 bool get_client_source_initialized() {
return _src_addr_initialized; }
469 bool get_client_source_initialized() {
return true; }
472 uint64_t get_start_time() {
return _mavlink_start_time; }
474 static bool boot_complete() {
return _boot_complete; }
476 bool is_usb_uart() {
return _is_usb_uart; }
478 int get_data_rate() {
return _datarate; }
479 void set_data_rate(
int rate) {
if (rate > 0) { _datarate = rate; } }
481 unsigned get_main_loop_delay()
const {
return _main_loop_delay; }
491 void try_start_ulog_streaming(uint8_t target_system, uint8_t target_component)
493 if (_mavlink_ulog) {
return; }
497 void request_stop_ulog_streaming()
499 if (_mavlink_ulog) { _mavlink_ulog_stop_requested =
true; }
503 void set_uorb_main_fd(
int fd,
unsigned int interval);
505 bool ftp_enabled()
const {
return _ftp_on; }
507 bool hash_check_enabled()
const {
return _param_mav_hash_chk_en.get(); }
508 bool forward_heartbeats_enabled()
const {
return _param_mav_hb_forw_en.get(); }
509 bool odometry_loopback_enabled()
const {
return _param_mav_odom_lp.get(); }
512 uint64_t last_ping_time;
513 uint32_t last_ping_seq;
514 uint32_t dropped_packets;
527 Mavlink *next{
nullptr};
532 bool _transmitting_enabled{
true};
533 bool _transmitting_enabled_commanded{
false};
534 bool _first_heartbeat_sent{
false};
539 bool _task_running{
false};
540 static bool _boot_complete;
541 static constexpr
int MAVLINK_MAX_INSTANCES{4};
542 static constexpr
int MAVLINK_MIN_INTERVAL{1500};
543 static constexpr
int MAVLINK_MAX_INTERVAL{10000};
544 static constexpr
float MAVLINK_MIN_MULTIPLIER{0.0005f};
546 mavlink_message_t _mavlink_buffer {};
547 mavlink_status_t _mavlink_status {};
550 bool _hil_enabled{
false};
551 bool _generate_rc{
false};
552 bool _is_usb_uart{
false};
553 bool _wait_to_transmit{
false};
554 bool _received_messages{
false};
556 unsigned _main_loop_delay{1000};
558 List<MavlinkOrbSubscription *> _subscriptions;
559 List<MavlinkStream *> _streams;
564 volatile bool _mavlink_ulog_stop_requested{
false};
566 MAVLINK_MODE _mode{MAVLINK_MODE_NORMAL};
568 mavlink_channel_t _channel{MAVLINK_COMM_0};
570 ringbuffer::RingBuffer _logbuffer{5,
sizeof(mavlink_log_s)};
572 pthread_t _receive_thread {};
574 bool _forwarding_on{
false};
579 int _baudrate{57600};
581 float _rate_mult{1.0f};
583 bool _radio_status_available{
false};
584 bool _radio_status_critical{
false};
585 float _radio_status_mult{1.0f};
592 unsigned int _mavlink_param_queue_index{0};
594 bool _mavlink_link_termination_allowed{
false};
596 char *_subscribe_to_stream{
nullptr};
597 float _subscribe_to_stream_rate{0.0f};
598 bool _udp_initialised{
false};
600 FLOW_CONTROL_MODE _flow_control_mode{Mavlink::FLOW_CONTROL_OFF};
602 uint64_t _last_write_success_time;
603 uint64_t _last_write_try_time;
604 uint64_t _mavlink_start_time;
605 int32_t _protocol_version_switch;
606 int32_t _protocol_version;
609 unsigned _bytes_txerr;
611 uint64_t _bytes_timestamp;
613 #if defined(CONFIG_NET) || defined(__PX4_POSIX) 615 sockaddr_in _src_addr;
616 sockaddr_in _bcast_addr;
618 bool _src_addr_initialized;
619 bool _broadcast_address_found;
620 bool _broadcast_address_not_found_warned;
621 bool _broadcast_failed_warned;
622 uint8_t _network_buf[MAVLINK_MAX_PACKET_LEN];
623 unsigned _network_buf_len;
626 const char *_interface_name;
630 unsigned short _network_port;
631 unsigned short _remote_port;
633 radio_status_s _rstatus{};
634 telemetry_status_s _tstatus{};
638 struct mavlink_message_buffer {
645 mavlink_message_buffer _message_buffer {};
647 pthread_mutex_t _message_buffer_mutex {};
648 pthread_mutex_t _send_mutex {};
656 (ParamBool<px4::params::MAV_USEHILGPS>) _param_mav_usehilgps,
657 (ParamBool<px4::params::MAV_FWDEXTSP>) _param_mav_fwdextsp,
659 (ParamBool<px4::params::MAV_HASH_CHK_EN>) _param_mav_hash_chk_en,
660 (ParamBool<px4::params::MAV_HB_FORW_EN>) _param_mav_hb_forw_en,
661 (ParamBool<px4::params::MAV_ODOM_LP>) _param_mav_odom_lp,
668 void mavlink_update_parameters();
670 int mavlink_open_uart(
int baudrate,
const char *uart_name,
bool force_flow_control);
672 static constexpr
unsigned RADIO_BUFFER_CRITICAL_LOW_PERCENTAGE = 25;
673 static constexpr
unsigned RADIO_BUFFER_LOW_PERCENTAGE = 35;
674 static constexpr
unsigned RADIO_BUFFER_HALF_PERCENTAGE = 50;
682 int configure_stream(
const char *stream_name,
const float rate = -1.0f);
690 int configure_streams_to_default(
const char *configure_single_stream =
nullptr);
692 int message_buffer_init(
int size);
694 void message_buffer_destroy();
696 int message_buffer_count();
698 int message_buffer_is_empty()
const {
return (_message_buffer.read_ptr == _message_buffer.write_ptr); }
700 int message_buffer_get_ptr(
void **ptr,
bool *is_part);
702 void message_buffer_mark_read(
int n) { _message_buffer.read_ptr = (_message_buffer.read_ptr + n) % _message_buffer.size; }
704 void pass_message(
const mavlink_message_t *msg);
706 void publish_telemetry_status();
714 void check_radio_config();
719 void update_rate_mult();
721 void find_broadcast_address();
728 int task_main(
int argc,
char *argv[]);
731 Mavlink(
const Mavlink &) =
delete;
732 Mavlink operator=(
const Mavlink &) =
delete;
An intrusive linked list.
Helper methods for command-line parameters.
A flexible ringbuffer class.
Definition: px4_param.h:313
static MavlinkULog * try_start(int datarate, float max_rate_factor, uint8_t target_system, uint8_t target_component)
try to start a new stream.
Definition: mavlink_ulog.cpp:219
MAVLink 1.0 message formatters definition.
telemetry_status_s & get_telemetry_status()
Get the receive status of this MAVLink link.
Definition: mavlink_main.h:436
Configuration flags used in code.
Includes POSIX-like functions for virtual character devices.
struct ping_statistics_s & get_ping_statistics()
Get the ping statistics of this MAVLink link.
Definition: mavlink_main.h:524
MavlinkULog * get_ulog_streaming()
get ulog streaming if active, nullptr otherwise
Definition: mavlink_main.h:490
__BEGIN_DECLS typedef void * orb_advert_t
ORB topic advertiser handle.
Definition: uORB.h:134
void count_rxbytes(unsigned n)
Count received bytes.
Definition: mavlink_main.h:431
int get_system_id() const
Get the MAVLink system id.
Definition: mavlink_main.h:171
Generally used magic defines.
Global flash based parameter store.
void set_protocol(Protocol p)
Set communication protocol for this mavlink instance.
Definition: mavlink_main.h:299
void resend_message(mavlink_message_t *msg)
Resend message as is, don't change sequence number and CRC.
Definition: mavlink_main.h:330
API for the uORB lightweight object broker.
ULog streaming class.
Definition: mavlink_ulog.h:58
C++ base class for modules/classes using configuration parameters.
Definition: px4_module_params.h:46
Mavlink commands sender with support for retransmission.
bool get_manual_input_mode_generation()
Get the manual input generation mode.
Definition: mavlink_main.h:306
uORB subscription definition.
Thread safe version of getopt.
A shell to be used via MAVLink.
Definition: mavlink_orb_subscription.h:48
ULog data streaming via MAVLink.
void count_txbytes(unsigned n)
Count transmitted bytes.
Definition: mavlink_main.h:421
void set_manual_input_mode_generation(bool generation_enabled)
Set manual input generation mode.
Definition: mavlink_main.h:294
Definition: mavlink_shell.h:48
int get_component_id() const
Get the MAVLink component id.
Definition: mavlink_main.h:178
void begin_send()
This is the beginning of a MAVLINK_START_UART_SEND/MAVLINK_END_UART_SEND transaction.
Definition: mavlink_main.h:311
Definition: mavlink_main.h:511
Performance measuring tools.
Mavlink()
Constructor.
Definition: mavlink_main.cpp:163
void count_txerrbytes(unsigned n)
Count bytes not transmitted because of errors.
Definition: mavlink_main.h:426