Link Search Menu Expand Document

Mavlink Routing on VOXL

Mavlink routing on VOXL is handled by voxl-mavlink-server which routes mavlink messages between the autopilot, MPA services, and ground control stations.

Up to 16 simultaneous external UDP connections can be established with voxl-mavlink-server. These can be connections to qGroundControl, MAVROS, MAVSDK, or any custom software on the same network as VOXL. voxl-mavlink-server listens for mavlink heartbeats on the standard mavlink port 14550 and opens a new link when it receives a heartbeat from a new IP. Each link receives all mavlink data coming from the autopilot and any messages received on the UDP port will be forwarded to the autopilot.

Prerequisites

This page assumes you have followed the VOXL Developer Bootcamp Connecting VOXL to QGroundControl page.

Routing Paths (QRB5165 SDSP Mode)

QRB5165 based systems (VOXL2 and VOXL2-mini) running voxl-px4 on the SDSP have two parallel mavlink streams running between the autopilot and voxl-mavlink-server. This allows very high datarate messages (aka ‘Onboard Mode’) to be sent from the autopilot to local services running on VOXL through MPA.

A second low datarate stream (aka ‘Normal Mode’) is then transmitted to ground control stations over UDP. This data stream is still available for MPA services to inspect via the mavlink_to_gcs pipe. MPA services can also communicate directly with the GCS though the mavlink_from_gcs pipe.

Mavlink Server Diagram SDSP

Routing Paths (External Autopilot Mode)

On both QRB5165 and APQ8096 based systems where the user has connected an external Autopilot Via a UART port, the single mavlink stream is shared for both onboard and GCS communication. Note it is up to the user to configure the desired datarate on their own external Autopilot.

For information on how to connect an external flight controller to VOXL2, go here.

Mavlink Server Diagram External Autopilot

voxl-inspect-mavlink will show the mavlink message types and rates being published on any of the 8 pipes described in the Routing Paths section.

For example, to see the full datarate ‘onboard mode’ messages being published by the Autopilot for use by onboard services, run the following:

voxl2:/$ voxl-inspect-mavlink mavlink_onboard

|   ID  |      Mavlink MSG Name       |Counter|  Hz  |
|-------|-----------------------------|-------|------|
|     0 | heartbeat                   |     4 |  1.1 |
|     1 | sys_status                  |    18 |  5.0 |
|     2 | system_time                 |     4 |  1.1 |
|     4 | ping                        |     4 |  1.1 |
|     8 | link_node_status            |     4 |  1.1 |
|    24 | gps_raw_int                 |    29 |  8.0 |
|    29 | scaled_pressure             |     4 |  1.1 |
|    30 | attitude                    |    36 | 10.0 |
|    31 | attitude_quaternion         |    36 | 10.0 |
|    32 | local_position_ned          |   109 | 30.2 |
|    36 | servo_output_raw            |    36 | 10.0 |
|    65 | rc_channels                 |    72 | 20.0 |
|    74 | vfr_hud                     |    36 | 10.0 |
|    83 | attitude_target             |    36 | 10.0 |
|    85 | position_target_local_ned   |    36 | 10.0 |
|   105 | highres_imu                 |    36 | 10.0 |
|   141 | altitude                    |    36 | 10.0 |
|   147 | battery_status              |     2 |  0.6 |
|   230 | estimator_status            |     4 |  1.1 |
|   241 | vibration                   |     2 |  0.6 |
|   245 | extended_sys_state          |    18 |  5.0 |
|   290 | esc_info                    |    36 | 10.0 |
|   291 | esc_status                  |    36 | 10.0 |
|   331 | odometry                    |   108 | 29.9 |
|   380 | time_estimate_to_target     |     3 |  0.8 |
|   411 | current_event_sequence      |     1 |  0.3 |
| 12901 | open_drone_id_location      |     4 |  1.1 |

Or to simply show that heartbeats are being broadcast by the autopilot:

voxl2:/$ voxl-inspect-mavlink mavlink_ap_heartbeat

|   ID  |      Mavlink MSG Name       |Counter|  Hz  |
|-------|-----------------------------|-------|------|
|     0 | heartbeat                   |     8 |  1.1 |

You can also see the much lower datarate packets going from the autopilot to the GCS. Note that this will show data even without a GCS connected since the autopilot broadcasts this data at all times.

voxl2:/$ voxl-inspect-mavlink mavlink_to_gcs

|   ID  |      Mavlink MSG Name       |Counter|  Hz  |
|-------|-----------------------------|-------|------|
|     0 | heartbeat                   |     8 |  1.1 |
|     1 | sys_status                  |     8 |  1.1 |
|     4 | ping                        |     1 |  0.1 |
|     8 | link_node_status            |     7 |  0.9 |
|    24 | gps_raw_int                 |     7 |  0.9 |
|    29 | scaled_pressure             |     8 |  1.1 |
|    30 | attitude                    |   111 | 14.9 |
|    31 | attitude_quaternion         |    75 | 10.1 |
|    32 | local_position_ned          |     8 |  1.1 |
|    36 | servo_output_raw            |     8 |  1.1 |
|    65 | rc_channels                 |    38 |  5.1 |
|    74 | vfr_hud                     |    30 |  4.0 |
|    83 | attitude_target             |    15 |  2.0 |
|    85 | position_target_local_ned   |    11 |  1.5 |
|   141 | altitude                    |     8 |  1.1 |
|   147 | battery_status              |     4 |  0.5 |
|   230 | estimator_status            |     4 |  0.5 |
|   241 | vibration                   |     1 |  0.1 |
|   245 | extended_sys_state          |     8 |  1.1 |
|   290 | esc_info                    |     8 |  1.1 |
|   291 | esc_status                  |     8 |  1.1 |
|   380 | time_estimate_to_target     |     7 |  0.9 |
|   411 | current_event_sequence      |     3 |  0.4 |
| 12901 | open_drone_id_location      |     8 |  1.1 |

You will, however, only see data coming from the GCS on the mavlink_from_gcs pipe once a GCS connects. Usually the GCS just sends a heartbeat once per second and a ping every 10 seconds. However, if you open voxl-inspect-mavlink BEFORE opening the GCS, you can see the variety of messages the GCS sends over during initial connection.

Of note is the param_request_list message which triggers the param dump from the autopilot to the GCS on initial connection. Also the initial several command_long messages are mavlink commands requesting information about the camera capabilities and requesting the RTSP video stream URL.

You can have two windows open at once inspecting both mavlink_from_gcs and mavlink_to_gcs to help debug if custom commands and command ACKs are being send back and forth.

voxl2:/$ voxl-inspect-mavlink mavlink_from_gcs

|   ID  |      Mavlink MSG Name       |Counter|  Hz  |
|-------|-----------------------------|-------|------|
|     0 | heartbeat                   |    26 |  1.1 |
|     2 | system_time                 |     2 |  0.1 |
|     4 | ping                        |     1 |  0.0 |
|    21 | param_request_list          |     1 |  0.0 |
|    23 | param_set                   |     1 |  0.0 |
|    43 | mission_request_list        |     3 |  0.1 |
|    47 | mission_ack                 |     3 |  0.1 |
|    76 | command_long                |     9 |  0.4 |
/**
 * voxl-mavlink-server Configuration File
 *
 * primary_static_gcs_ip & secondary_static_gcs_ip
 *    These configure voxl-mavlink-server to automatically try to connect to
 *    up to two known static GCS units. Set to empty or NULL if you don't want
 *    to use this and you want the GCS to initialize the connection instead.
 *    Note the default IP for the primary link is 192.168.8.10 which is the
 *    first IP that VOXL DHCP serves when connecting in wifi softap mode.
 *
 *
 * Settings for running voxl-px4 on SLPI:
 * onboard_port_to_autopilot   - UDP port to send high-rate onboard data to SLPI
 * onboard_port_from_autopilot - UDP port to receive high-rate onboard data from SLPI
 * gcs_port_to_autopilot       - UDP port to send normal-rate gcs data to SLPI
 * gcs_port_from_autopilot     - UDP port to receive normal-rate gcs data from SLPI
 *
 * Settings for running an external autopilot connected via UART:
 * en_external_uart_ap       - set to true to enable an external flight controller
 * autopilot_uart_bus        - uart bus, default 1 for VOXL2
 * autopilot_uart_baudrate   - default 921600
 * en_external_fc_timesync   - enable responding to timesync messages
 *                                   (enabled by default)
 * en_external_ap_heartbeat  - enable automatic sending of heartbeat
 * gcs_timeout_s - time without heartbeat to consider GCS disconnected
 *
 * udp_mtu - maximum transfer unit for UDP packets back to GCS. voxl-mavlink-server
 *           will bundle up backets for the GCS into a single UDP packet with
 *           a maximum size of this. This saves network traffic drastically.
 *           Set to 0 to disable this feature and send one UDP packet per msg.
 *
 *
 * External FC field is for QRB5165 only. Set to true to enable UART
 * communication to an external flight controller, otherwise a UDP interface
 * will be started to talk to voxl-autopilot on localhost which is the default behavior.
 *
 */
{
	"primary_static_gcs_ip":	"192.168.8.10",
	"secondary_static_gcs_ip":	"192.168.8.11",
	"onboard_port_to_autopilot":	14556,
	"onboard_port_from_autopilot":	14557,
	"gcs_port_to_autopilot":	14558,
	"gcs_port_from_autopilot":	14559,
	"en_external_uart_ap":	false,
	"autopilot_uart_bus":	1,
	"autopilot_uart_baudrate":	921600,
	"en_external_ap_timesync":	1,
	"en_external_ap_heartbeat":	1,
	"udp_mtu":	0,
	"gcs_timeout_s":	4.5
}
voxl2:/$ voxl-mavlink-server --help

voxl-mavlink-server usually runs as a systemd background service. However, for debug
purposes it can be started from the command line manually with any of the following
debug options. When started from the command line, voxl-mavlink-server will automatically
stop the background service so you don't have to stop it manually

-c, --load_config_only    Load the config file and then exit right away.
                            This also adds new defaults if necessary. This is used
                            by voxl-configure-voxl-px4 to make sure the config file
                            is up to date without actually starting this service.
-h, --help                Print this help text
-i, --debug_pipe_recv     show debug info on messages coming from MPA
-j, --debug_pipe_send     show debug info on messages sending to MPA
-k, --debug_ap_recv       show debug info on messages coming from autopilot
-l, --debug_ap_send       show debug info on messages sending to autopilot
-m, --debug_gcs_recv      show debug info on messages coming from GCS
-n, --debug_gcs_send      show debug info on messages sending to GCS
-t, --debug_timesync      show debug info on the timesync protocol handling
-z, --debug_send_recv     show debug info on all sent and received messages

ModalAI bundles up the official MAVlink headers into a deb (and ipk) package called voxl-mavlink for distribution in voxl-suite for easy distribution and building projects in the VOXL ecosystem. The source code for the voxl-mavlink package can be found here.

Next: Streaming Video to QGroundControl