Firmware
mavlink_main.h
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2012-2018 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
43 #pragma once
44 
45 #include <pthread.h>
46 #include <stdbool.h>
47 
48 #ifdef __PX4_NUTTX
49 #include <nuttx/fs/fs.h>
50 #else
51 #include <arpa/inet.h>
52 #include <drivers/device/device.h>
53 #include <sys/socket.h>
54 #endif
55 
56 #if defined(CONFIG_NET) || !defined(__PX4_NUTTX)
57 #include <net/if.h>
58 #include <netinet/in.h>
59 #endif
60 
61 #include <containers/List.hpp>
63 #include <parameters/param.h>
64 #include <perf/perf_counter.h>
65 #include <px4_cli.h>
66 #include <px4_config.h>
67 #include <px4_defines.h>
68 #include <px4_getopt.h>
69 #include <px4_module.h>
70 #include <px4_module_params.h>
71 #include <px4_posix.h>
72 #include <systemlib/mavlink_log.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>
78 #include <uORB/uORB.h>
79 
80 #include "mavlink_command_sender.h"
81 #include "mavlink_messages.h"
83 #include "mavlink_shell.h"
84 #include "mavlink_ulog.h"
85 
86 #define DEFAULT_REMOTE_PORT_UDP 14550
87 #define DEFAULT_DEVICE_NAME "/dev/ttyS1"
88 #define HASH_PARAM "_HASH_CHECK"
89 
90 enum Protocol {
91  SERIAL = 0,
92  UDP,
93  TCP,
94 };
95 
96 using namespace time_literals;
97 
98 class Mavlink : public ModuleParams
99 {
100 
101 public:
105  Mavlink();
106 
110  ~Mavlink();
111 
117  static int start(int argc, char *argv[]);
118 
122  void display_status();
123 
127  void display_status_streams();
128 
129  static int stream_command(int argc, char *argv[]);
130 
131  static int instance_count();
132 
133  static Mavlink *new_instance();
134 
135  static Mavlink *get_instance(int instance);
136 
137  static Mavlink *get_instance_for_device(const char *device_name);
138 
139  static Mavlink *get_instance_for_network_port(unsigned long port);
140 
141  mavlink_message_t *get_buffer() { return &_mavlink_buffer; }
142 
143  mavlink_status_t *get_status() { return &_mavlink_status; }
144 
152  void set_proto_version(unsigned version);
153 
154  static int destroy_all_instances();
155 
156  static int get_status_all_instances(bool show_streams_status);
157 
158  static bool instance_exists(const char *device_name, Mavlink *self);
159 
160  static void forward_message(const mavlink_message_t *msg, Mavlink *self);
161 
162  static int get_uart_fd(unsigned index);
163 
164  int get_uart_fd() const { return _uart_fd; }
165 
171  int get_system_id() const { return mavlink_system.sysid; }
172 
178  int get_component_id() const { return mavlink_system.compid; }
179 
180  const char *_device_name{DEFAULT_DEVICE_NAME};
181 
182  enum MAVLINK_MODE {
183  MAVLINK_MODE_NORMAL = 0,
184  MAVLINK_MODE_CUSTOM,
185  MAVLINK_MODE_ONBOARD,
186  MAVLINK_MODE_OSD,
187  MAVLINK_MODE_MAGIC,
188  MAVLINK_MODE_CONFIG,
189  MAVLINK_MODE_IRIDIUM,
190  MAVLINK_MODE_MINIMAL,
191  MAVLINK_MODE_EXTVISION,
192 
193  MAVLINK_MODE_COUNT
194  };
195 
196  enum BROADCAST_MODE {
197  BROADCAST_MODE_OFF = 0,
198  BROADCAST_MODE_ON,
199  BROADCAST_MODE_MULTICAST
200  };
201 
202  enum FLOW_CONTROL_MODE {
203  FLOW_CONTROL_OFF = 0,
204  FLOW_CONTROL_AUTO,
205  FLOW_CONTROL_ON
206  };
207 
208  static const char *mavlink_mode_str(enum MAVLINK_MODE mode)
209  {
210  switch (mode) {
211  case MAVLINK_MODE_NORMAL:
212  return "Normal";
213 
214  case MAVLINK_MODE_CUSTOM:
215  return "Custom";
216 
217  case MAVLINK_MODE_ONBOARD:
218  return "Onboard";
219 
220  case MAVLINK_MODE_OSD:
221  return "OSD";
222 
223  case MAVLINK_MODE_MAGIC:
224  return "Magic";
225 
226  case MAVLINK_MODE_CONFIG:
227  return "Config";
228 
229  case MAVLINK_MODE_IRIDIUM:
230  return "Iridium";
231 
232  case MAVLINK_MODE_MINIMAL:
233  return "Minimal";
234 
235  case MAVLINK_MODE_EXTVISION:
236  return "ExtVision";
237 
238  default:
239  return "Unknown";
240  }
241  }
242 
243  enum MAVLINK_MODE get_mode() { return _mode; }
244 
245  bool get_hil_enabled() { return _hil_enabled; }
246 
247  bool get_use_hil_gps() { return _param_mav_usehilgps.get(); }
248 
249  bool get_forward_externalsp() { return _param_mav_fwdextsp.get(); }
250 
251  bool get_flow_control_enabled() { return _flow_control_mode; }
252 
253  bool get_forwarding_on() { return _forwarding_on; }
254 
255  bool is_connected() { return (hrt_elapsed_time(&_tstatus.heartbeat_time) < 3_s); }
256 
257  bool broadcast_enabled() { return _param_mav_broadcast.get() == BROADCAST_MODE_ON; }
258 
265  static void set_boot_complete();
266 
272  unsigned get_free_tx_buf();
273 
274  static int start_helper(int argc, char *argv[]);
275 
284  int set_hil_enabled(bool hil_enabled);
285 
294  void set_manual_input_mode_generation(bool generation_enabled) { _generate_rc = generation_enabled; }
295 
299  void set_protocol(Protocol p) { _protocol = p; }
300 
306  bool get_manual_input_mode_generation() { return _generate_rc; }
307 
311  void begin_send() { pthread_mutex_lock(&_send_mutex); }
312 
318  void send_bytes(const uint8_t *buf, unsigned packet_len);
319 
325  int send_packet();
326 
330  void resend_message(mavlink_message_t *msg) { _mavlink_resend_uart(_channel, msg); }
331 
332  void handle_message(const mavlink_message_t *msg);
333 
341  MavlinkOrbSubscription *add_orb_subscription(const orb_id_t topic, int instance = 0, bool disable_sharing = false);
342 
343  int get_instance_id() const { return _instance_id; }
344 
350  int enable_flow_control(enum FLOW_CONTROL_MODE enabled);
351 
352  mavlink_channel_t get_channel() const { return _channel; }
353 
354  void configure_stream_threadsafe(const char *stream_name, float rate = -1.0f);
355 
356  orb_advert_t *get_mavlink_log_pub() { return &_mavlink_log_pub; }
357 
363  void send_statustext_info(const char *string);
364 
370  void send_statustext_critical(const char *string);
371 
377  void send_statustext_emergency(const char *string);
378 
388  void send_statustext(unsigned char severity, const char *string);
389 
393  void send_autopilot_capabilites();
394 
398  void send_protocol_version();
399 
400  List<MavlinkStream *> &get_streams() { return _streams; }
401 
402  float get_rate_mult() const { return _rate_mult; }
403 
404  float get_baudrate() { return _baudrate; }
405 
406  /* Functions for waiting to start transmission until message received. */
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))); }
412 
413  bool message_buffer_write(const void *ptr, int size);
414 
415  void lockMessageBufferMutex(void) { pthread_mutex_lock(&_message_buffer_mutex); }
416  void unlockMessageBufferMutex(void) { pthread_mutex_unlock(&_message_buffer_mutex); }
417 
421  void count_txbytes(unsigned n) { _bytes_tx += n; };
422 
426  void count_txerrbytes(unsigned n) { _bytes_txerr += n; };
427 
431  void count_rxbytes(unsigned n) { _bytes_rx += n; };
432 
436  telemetry_status_s &get_telemetry_status() { return _tstatus; }
437 
438  void set_telemetry_status_type(uint8_t type) { _tstatus.type = type; }
439 
440  void update_radio_status(const radio_status_s &radio_status);
441 
442  ringbuffer::RingBuffer *get_logbuffer() { return &_logbuffer; }
443 
444  unsigned get_system_type() { return _param_mav_type.get(); }
445 
446  Protocol get_protocol() { return _protocol; }
447 
448  unsigned short get_network_port() { return _network_port; }
449 
450  unsigned short get_remote_port() { return _remote_port; }
451 
452  int get_socket_fd() { return _socket_fd; };
453 
454  bool _task_should_exit{false};
456 #ifdef __PX4_POSIX
457  const in_addr query_netmask_addr(const int socket_fd, const ifreq &ifreq);
458 
459  const in_addr compute_broadcast_addr(const in_addr &host_addr, const in_addr &netmask_addr);
460 #endif
461 
462 #if defined(CONFIG_NET) || defined(__PX4_POSIX)
463  struct sockaddr_in &get_client_source_address() { return _src_addr; }
464 
465  void set_client_source_initialized() { _src_addr_initialized = true; }
466 
467  bool get_client_source_initialized() { return _src_addr_initialized; }
468 #else
469  bool get_client_source_initialized() { return true; }
470 #endif
471 
472  uint64_t get_start_time() { return _mavlink_start_time; }
473 
474  static bool boot_complete() { return _boot_complete; }
475 
476  bool is_usb_uart() { return _is_usb_uart; }
477 
478  int get_data_rate() { return _datarate; }
479  void set_data_rate(int rate) { if (rate > 0) { _datarate = rate; } }
480 
481  unsigned get_main_loop_delay() const { return _main_loop_delay; }
482 
485  MavlinkShell *get_shell();
487  void close_shell();
488 
490  MavlinkULog *get_ulog_streaming() { return _mavlink_ulog; }
491  void try_start_ulog_streaming(uint8_t target_system, uint8_t target_component)
492  {
493  if (_mavlink_ulog) { return; }
494 
495  _mavlink_ulog = MavlinkULog::try_start(_datarate, 0.7f, target_system, target_component);
496  }
497  void request_stop_ulog_streaming()
498  {
499  if (_mavlink_ulog) { _mavlink_ulog_stop_requested = true; }
500  }
501 
502 
503  void set_uorb_main_fd(int fd, unsigned int interval);
504 
505  bool ftp_enabled() const { return _ftp_on; }
506 
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(); }
510 
512  uint64_t last_ping_time;
513  uint32_t last_ping_seq;
514  uint32_t dropped_packets;
515  float last_rtt;
516  float mean_rtt;
517  float max_rtt;
518  float min_rtt;
519  };
520 
524  struct ping_statistics_s &get_ping_statistics() { return _ping_stats; }
525 
526 protected:
527  Mavlink *next{nullptr};
528 
529 private:
530  int _instance_id{0};
531 
532  bool _transmitting_enabled{true};
533  bool _transmitting_enabled_commanded{false};
534  bool _first_heartbeat_sent{false};
535 
536  orb_advert_t _mavlink_log_pub{nullptr};
537  orb_advert_t _telem_status_pub{nullptr};
538 
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};
545 
546  mavlink_message_t _mavlink_buffer {};
547  mavlink_status_t _mavlink_status {};
548 
549  /* states */
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;
560 
561  MavlinkShell *_mavlink_shell{nullptr};
562  MavlinkULog *_mavlink_ulog{nullptr};
563 
564  volatile bool _mavlink_ulog_stop_requested{false};
565 
566  MAVLINK_MODE _mode{MAVLINK_MODE_NORMAL};
567 
568  mavlink_channel_t _channel{MAVLINK_COMM_0};
569 
570  ringbuffer::RingBuffer _logbuffer{5, sizeof(mavlink_log_s)};
571 
572  pthread_t _receive_thread {};
573 
574  bool _forwarding_on{false};
575  bool _ftp_on{false};
576 
577  int _uart_fd{-1};
578 
579  int _baudrate{57600};
580  int _datarate{1000};
581  float _rate_mult{1.0f};
582 
583  bool _radio_status_available{false};
584  bool _radio_status_critical{false};
585  float _radio_status_mult{1.0f};
586 
592  unsigned int _mavlink_param_queue_index{0};
593 
594  bool _mavlink_link_termination_allowed{false};
595 
596  char *_subscribe_to_stream{nullptr};
597  float _subscribe_to_stream_rate{0.0f};
598  bool _udp_initialised{false};
599 
600  FLOW_CONTROL_MODE _flow_control_mode{Mavlink::FLOW_CONTROL_OFF};
601 
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;
607 
608  unsigned _bytes_tx;
609  unsigned _bytes_txerr;
610  unsigned _bytes_rx;
611  uint64_t _bytes_timestamp;
612 
613 #if defined(CONFIG_NET) || defined(__PX4_POSIX)
614  sockaddr_in _myaddr;
615  sockaddr_in _src_addr;
616  sockaddr_in _bcast_addr;
617 
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;
624 #endif
625 
626  const char *_interface_name;
627 
628  int _socket_fd;
629  Protocol _protocol;
630  unsigned short _network_port;
631  unsigned short _remote_port;
632 
633  radio_status_s _rstatus{};
634  telemetry_status_s _tstatus{};
635 
636  ping_statistics_s _ping_stats{};
637 
638  struct mavlink_message_buffer {
639  int write_ptr;
640  int read_ptr;
641  int size;
642  char *data;
643  };
644 
645  mavlink_message_buffer _message_buffer {};
646 
647  pthread_mutex_t _message_buffer_mutex {};
648  pthread_mutex_t _send_mutex {};
649 
650  DEFINE_PARAMETERS(
651  (ParamInt<px4::params::MAV_SYS_ID>) _param_mav_sys_id,
652  (ParamInt<px4::params::MAV_COMP_ID>) _param_mav_comp_id,
653  (ParamInt<px4::params::MAV_PROTO_VER>) _param_mav_proto_ver,
654  (ParamInt<px4::params::MAV_RADIO_ID>) _param_mav_radio_id,
655  (ParamInt<px4::params::MAV_TYPE>) _param_mav_type,
656  (ParamBool<px4::params::MAV_USEHILGPS>) _param_mav_usehilgps,
657  (ParamBool<px4::params::MAV_FWDEXTSP>) _param_mav_fwdextsp,
658  (ParamInt<px4::params::MAV_BROADCAST>) _param_mav_broadcast,
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,
662  (ParamInt<px4::params::SYS_HITL>) _param_sys_hitl
663  )
664 
665  perf_counter_t _loop_perf;
666  perf_counter_t _loop_interval_perf;
668  void mavlink_update_parameters();
669 
670  int mavlink_open_uart(int baudrate, const char *uart_name, bool force_flow_control);
671 
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;
675 
682  int configure_stream(const char *stream_name, const float rate = -1.0f);
683 
690  int configure_streams_to_default(const char *configure_single_stream = nullptr);
691 
692  int message_buffer_init(int size);
693 
694  void message_buffer_destroy();
695 
696  int message_buffer_count();
697 
698  int message_buffer_is_empty() const { return (_message_buffer.read_ptr == _message_buffer.write_ptr); }
699 
700  int message_buffer_get_ptr(void **ptr, bool *is_part);
701 
702  void message_buffer_mark_read(int n) { _message_buffer.read_ptr = (_message_buffer.read_ptr + n) % _message_buffer.size; }
703 
704  void pass_message(const mavlink_message_t *msg);
705 
706  void publish_telemetry_status();
707 
714  void check_radio_config();
715 
719  void update_rate_mult();
720 
721  void find_broadcast_address();
722 
723  void init_udp();
724 
728  int task_main(int argc, char *argv[]);
729 
730  // Disallow copy construction and move assignment.
731  Mavlink(const Mavlink &) = delete;
732  Mavlink operator=(const Mavlink &) = delete;
733 };
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
Configuration flags used in code.
Includes POSIX-like functions for virtual character devices.
__BEGIN_DECLS typedef void * orb_advert_t
ORB topic advertiser handle.
Definition: uORB.h:134
Generally used magic defines.
Global flash based parameter store.
Header common to all counters.
Definition: perf_counter.cpp:65
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
Object metadata.
Definition: uORB.h:50
Thread safe version of getopt.
Definition: mavlink_orb_subscription.h:48
Definition: mavlink_shell.h:48
Performance measuring tools.