Requesting Data From The Autopilot¶
The ground station or companion computer can request the data it wants (and the rate) using one of the following methods:
Set the
SRx_
parameters to cause the autopilot to pro-actively send groups of messages on start-up. This method is easy to set-up for a small number of drones but is not recommended for most applicationsSend REQUEST_DATA_STREAM messages to set the rate for groups of messages
Send a SET_MESSAGE_INTERVAL command (within a COMMAND_LONG message) to precisely control the rate of an individual message. Note this is only supported on ArduPilot 4.0 and higher
Send a REQUEST_MESSAGE command (within a COMMAND_LONG message) to request a single instance of a message. Note this is only supported on ArduPilot 4.0 and higher
create configuration files stored on SD card or in ROMFS specifying message stream rates on a per-channel basis
Note that the stream rates will temporarily be 4 or more times slower than requested while parameters and waypoints are being sent.
More details on the above methods can be found below.
Note
If you find your message rates are reverting to some fixed value after you set them, it is probably a Ground Control station adjusting the stream rates to suit itself. Most Ground Control Stations will have a control to stop the GCS doing this - for example in MAVProxy use set streamrate -1
. If adjusting the configuration of the GCS is infeasible, you can set bit 12 in the SERIALn_OPTIONS
parameter corresponding to the serial port on which the mavlink traffic is being transfered to force ArduPilot to ignore attempts by the GCS to set message rates via streamrate commands.
Using SRx Parameters¶
Setting the SRx_
parameters (and then rebooting the autopilot) will cause the autopilot to pro-actively send groups of messages to the ground station. This is not the recommended method because the ground station has no way to determine what “x” should be.
Connect to the autopilot with a ground station
Determine which telemetry connection is being used. For example if the ground station is connected to the autopilot’s “Telem1” port (perhaps using a wifi or telemetry radio) then the
SR1_
parameters should be modifiedSet the
SRx_
parameter to the rate (in Hz) you wish the group of messages to be sent. The exact messages contained in each group can be determined by inspecting the STREAM_xxx arrays in each vehicle’s GCS_Mavlink.cpp file (see here for Copter, Plane, Rover, Sub and AntennaTracker). Below is the list of messages by group for Copter-4.0:SRx_ADSB
SRx_EXT_STAT
SRx_EXTRA1
SRx_EXTRA2
SRx_EXTRA3
SRx_PARAMS - should not be changed
SRx_POSITION
SRx_RAW_CTRL (Not Used)
SRx_RAW_SENS
SRx_RC_CHAN
RC_CHANNELS_RAW (only sent on mavlink1 links)
Using REQUEST_DATA_STREAM¶
Most ground stations including the Mission Planner use this method. See Setting the Datarate in the Mission Planner wiki.
Send a REQUEST_DATA_STREAM message with the following fields
target_system : the MAVLink system id of the vehicle (normally “1”)
target_components : normally “0”
req_stream_id : 0 to 12 corresponding to the group of messages (see MAV_DATA_STREAM). See the “Using SRx Parameters” section above to determine exactly which messages are in each group
req_message_rate : the rate (in hz) of the message
start_stop : “1” to start sending, “0” to stop
Examples
Here are some example commands that can be copy-pasted into MAVProxy (aka SITL) to test this command. Before running these commands enter the following
module load message
Example MAVProxy/SITL Command |
Description |
---|---|
|
Request sysid:1, compid:0 send sensor data at 5hz |
|
Request sysid:1, compid:0 stop sending sensor data |
|
Request sysid:1, compid:0 send position data at 5hz |
|
Request sysid:1, compid:0 stop sending position data |
Using SET_MESSAGE_INTERVAL¶
This method provides the most precise control and reduces bandwidth requirements (because unnecessary messages are not sent) but requires knowing exactly which messages you require
Send a COMMAND_LONG with the following fields
target_system : the MAVLink system id of the vehicle (normally “1”)
target_components : normally “0”
command: 511 (for MAV_CMD_SET_MESSAGE_INTERVAL)
confirmation: 0
param1: desired MAVLink message’s id (i.e. 33 for GLOBAL_POSITION_INT)
param2: time interval between messages in microseconds (i.e. 100000 for 10hz, 1000000 for 1hz)
param3 to param7: 0 (not used)
Examples
Here are some example commands that can be copy-pasted into MAVProxy (aka SITL) to test this command. Before running these commands enter the following
module load message
Example MAVProxy/SITL Command |
Description |
---|---|
|
Request GLOBAL_POSITION_INT at 10hz |
|
Request GLOBAL_POSITION_INT at 1hz |
|
Request GLOBAL_POSITION_INT at default rate |
|
Request GLOBAL_POSITION_INT not be sent |
Warning
If the telemetry link is shared (i.e. multiple GCSs or a GCS and a companion computer) there can be conflicting requests. The most common example is the Mission Planner using the REQUEST_DATA_STREAM method while a companion copmuter uses SET_MESSAGE_INTERVAL method. Mission Planner at least allows turning off the REQUEST_DATA_STREAM requests by setting the rates to “-1” (see Setting the Datarate). MAVProxy users can set streamrate -1
.
Using REQUEST_MESSAGE¶
A GCS can poll for a single instance of a message from the autopilot.
Send a COMMAND_LONG with the following fields
target_system : the MAVLink system id of the vehicle (normally “1”)
target_components : normally “0”
command: 512 (for MAV_CMD_REQUEST_MESSAGE)
confirmation: 0
param1: desired MAVLink message’s id (i.e. 33 for GLOBAL_POSITION_INT)
param2: depends on message requested; see that message’s definition for details.
param3 to param7: 0 (not used)
Examples
Here are some example commands that can be copy-pasted into MAVProxy (aka SITL) to test this command. Before running these commands enter the following
module load message
Example MAVProxy/SITL Command |
Description |
---|---|
|
Request GLOBAL_POSITION_INT be sent once |
Specifying Message Rates in a File¶
At boot ArduPilot will populate the initial message intervals from files found in either ROMFS or in the filesystem.
On ChibiOS-based boards (with more than 1MB of flash) the SD card will be searched for specially-named files in the root directory.
Each mavlink channel is configured in a separate configuration file. The first serial port configured as mavlink is channel 0, the second serial port channel 1 etc.
An example filename is message-intervals-chan0.txt
The format is simple but strict. There are two columns, separated by a single space and both containing numbers. The first number is a mavlink message ID. The second is the message interval, in milliseconds. Each line must be terminated by either carriage-return or a line-feed.
30 50
28 100
29 200
This sample file content will stream ATTITUDE (ID=30) at 20Hz and SCALED_PRESSURE (ID=29) at 5Hz. Message ID 28 is RAW_PRESSURE which ArduPilot does not send - this line will be ignored.
Configuration files can be included in ROMFS (i.e. compiled into the image) by specifying their path in the relevant board’s hwdef file:
ROMFS message-intervals-chan0.txt libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/message-intervals-chan0.txt
The second parameter is a path relative to the ArduPilot checkout’s root directory.
Example use cases of this include locking telemetry rates on boards that can’t run scripting, or before scripting can be run.
Checking The Message Rates¶
Some ground stations including Mission Planner and QGC include a “MAVLink Inspector” which is useful when checking the update rate of specific messages.
If using Mission Planner:
Press Ctrl-F
Push the “MAVLink Inspector” button
Expand the vehicle and component IDs to see individual messages and their update rate
If using MAVProxy:
module load messagerate
messagerate status