Lowering Telemetry Datarates in ArduPilot

This post is an explainer on the telemetry datarates in ArduPilot, plus information and data on how to configure the datarate to fit in lower-bandwidth radio systems.

All datarates in this article are averages and are rounded to 1 decimal place. Does not include actions such as downloading parameters or waypoints. All datarates are in the Vehicle → GCS direction.

ArduPilot telemetry is a series of MAVLink messages output from a UART (or serial) port on the flight controller.

The MAVLink messages may be a streamed message (message is emitted at some regular rate), such as the vehicle’s GPS position or hardware status. Other messages are emitted in response to a command or query from the ground station, such as downloading parameters or a confirmation of a flight mode change.

The following table shows the average datarate of the default streamed messages from the different ArduPilot firmwares at the default rate of 4Hz. Note the datarate whilst the vehicle is armed is slightly higher, as additional streamed messages (such as NAV_CONTROLLER_OUTPUT) are active. The datarate will vary depending on the vehicle hardware and configuration, as additional sensors (such as a 2nd GPS) will increase the datarate.

Firmware Datarate when disarmed Datarate when armed
Plane 3.5 kbytes/sec 4 kbytes/sec
Copter 3.5 kbytes/sec 3.7 kbytes/sec
Rover 3.4 kbytes/sec 3.9 kbytes/sec

On a typical 57600 baud RF telemetry radio, this equates to 59%-69% of the available radio datarate being used.

If you are using a lower baud RF link, then ArduPilot’s streaming datarates may need to be trimmed down. There are several methods to do this.

The easiest method is to lower the rate of the streams. By default, a GCS will ask ArduPilot to stream at 4 Hz. This can be changed in Mission Planner in Config→Planner→Telemetry Rates or in MAVProxy via the --streamrate=n commandline option.

So, lowering the streamrates down to 1Hz gives the following average datarates:

Firmware Datarate when disarmed Datarate when armed
Plane 0.9 kbytes/sec 1.0 kbytes/sec
Copter 0.9 kbytes/sec 0.9 kbytes/sec
Rover 0.9 kbytes/sec 1.0 kbytes/sec

Taking this further, streams can be disabled. For example, you may not want raw sensor readings or RC channel values. In that case, set the “Sensor” and “RC” streams to “0” in Mission Planner. At this time, MAVProxy does not support setting individual streamrates.

If preferred, these streamrates can be set on ArduPilot instead of the GCS.

The average datarates are now:

Firmware Datarate when disarmed Datarate when armed
Plane 0.7 kbytes/sec 0.8 kbytes/sec
Copter 0.6 kbytes/sec 0.7 kbytes/sec
Rover 0.6 kbytes/sec 0.8 kbytes/sec

If finer grained control of which MAVLink messages are streamed is desired, the individual messages and rates can be controlled. There are a few methods for doing this.

For this example, a file containing the message ID’s and rate (in milliseconds) is placed in the SD card’s root directory:

message-intervals-chan0.txt

33 200
1 1000
74 2000

The above file tells ArduPilot that chan0 should stream message 33 (GLOBAL_POSITION_INT) at 5 Hz, message 1 (SYS_STATUS) at 1 Hz and message 74 (VFR_HUD) at 0.5 Hz. This gives basic information of the vehicle’s state and position.

Using this file, the telemetry datarate is lowered to 0.3 kbyte/sec. This sort of datarate would be suitable for radios operating at 2400 baud and above.

If you are working with very low datarate radios (<100 bytes/sec), you may wish to lower the datarate even further. For this, the new “MAVLinkHL” serial protocol option will be of interest. MAVLinkHL is an implementation of the High Latency MAVLink protocol and is designed primarily for low datarate satellite systems (such as SBD modems, such as Iridium Short Burst Data (SBD) | Iridium Satellite Communications). This protocol sends out a HIGH_LATENCY2 MAVLink message at 0.2 Hz (by default) in place of a HEARTBEAT packet.

The HIGH_LATENCY2 message contains a summary of the vehicle’s state and status in a single message, replacing the need to stream multiple different messages to get similar information.

To use High Latency MAVLink, set the relevant SERIALn_PROTOCOL to 43.

By default, this connection does not stream any data. It needs to be activated first. In MAVProxy, this can be done via the link hl on|off commands. Otherwise, the message can be requested via the MAV_CMD_CONTROL_HIGH_LATENCY or SET_MESSAGE_INTERVAL commands. The MAV_CMD_CONTROL_HIGH_LATENCY command can be sent over any link to ArduPilot – it does not need to be sent via the High Latency link.

Via this method, the telemetry datarate is reduced to 0.01 kbyte/sec!

So, for those running low datarate modems or radio systems, ArduPilot has a number of tools to reduce the telemetry datarate. This includes lowering the frequency of message updates and not sending less-useful messages.

EDIT:

For those interested in exploring the different message data throughputs, there is an excellent tool in the pymavlink repository: pymavlink/mavtelemetry_datarates.py at master · ArduPilot/pymavlink · GitHub

15 Likes

Thanks for this very interesting post!

In the past I have used a companion computer (on the same network as MP) to change the stream rates but then some seconds later MP would change them back again to it’s configured rates. Almost like it periodically monitored the rate and made sure it’s kept at that rate.

Just a question regarding this part:

What would be the correct way to calculate it?
It looks like you used 8 bits per byte transfered: 57600 / 8 = 7200 and then the min/max value, min = (3.4 / 7.2) * 100 = 47% and max = (4 / 7.2) * 100 = 55%
Since the UART also uses a start and stop bit should we not use 10 bits per byte transfered? This will bring the min and max closer to 59% and 69%

To exactly calculate it you must use this tool: pymavlink/mavtelemetry_datarates.py at master · ArduPilot/pymavlink · GitHub

@stephendade please add it to your excellent blog post.

That’s correct - I did forget to include the start/stop bit. I’ll update the post

That’s very cool! I did not know we had that tool :slight_smile:

Just FYI mission planners defaults are not 4hz for all, I’ve always been mindfull of this saturation point
MissionPlanner/CurrentState.cs at 0ff0fc6c69c3216bc1a8c9e9eee90a2b18594015 · ArduPilot/MissionPlanner · GitHub

Lowering telemetry rates doesn’t mean that you will get more range, or?
But it means that I potentially get more range because I can lower the air rate on the telemetry radio and get more range because of that, correct?
Is there any rule of thumb how much more range one gets if air rate is halved?

  1. yes, correct.
  2. yes, correct.
  3. I do not know of any

Hi Stephen, thanks a gazillion for this post. Very helpful and timely for me.

I’d appreciate some more clues on how to use a file on the SD card. I tried this and it seemed to work once (on about the 3rd or 4th try, not sure why), and it’s the level of control I need, but it’s extremely hit-and-miss. After seeming to work once, any further file changes now seem to be completely ignored.

So can we start with the basics.

  1. The file should be in the root directory of the SD card. Can we confirm this is where there’s a directory called ‘APM’, and nothing else? I am using a Windows computer to access the SD card’s file system. Could the SD card have partitions that Windows can’t see? Am I seeing the true root?

  2. The docs say, “An example filename is message-intervals-chan0.txt”. I get this is an “example” but it’s not clear what the rules are. Is the name mandatory, and only the numeral at the end is allowed to change? Or does Ardupilot look for any text file with a numeric digit at the end?

  3. Is there any other part of the process which a regular user might consider is so obvious that it doesn’t need to be written down, which I might possibly have missed? To summarise, I’m:

  • powering down the autopilot (Cube Orange)
  • removing the SD card from the autopilot
  • inserting the SD card into the card reader on my Windows laptop
  • editing a TXT file on my Windows computer and saving it to the root of the SD card in Windows
  • ejecting the SD card from the Windows computer, then inserting it back in the Cube Orange
  • powering the autopilot back on again

My issue is that TELEM2 is stuck on an extremely sparse setting that is no use to me, and it is not changing no matter what I try.

Many thanks once again.

Correct

The name is mandatory, with the numeral specifying the MAVLink channel number. For example, message-intervals-chan0.txt will be the USB port, message-intervals-chan1.txt will be the first MAVLink telemetry port (usually TELEM1), and so on.

Also, try with the latest 4.2.0 beta, as this is a recent feature.

You may also need to reset the streamrate parameters (SR0_* for chan0, SR1_* for chan1, etc) to 0 for the relevant port too. You will also need to ensure the GCS is not sending any streamrate overrides.

1 Like

Ah great, thanks. I’ve just gone through everything and it turns out that my file never worked at all. The time I thought it worked, it was actually because I’d changed the SRx_ rates (as per the linked article) but I got mixed up and thought SR0 was Telem1 & SR1 was Telem2, which explains why it was all so hit-and-miss. To make it doubly confusing, I’ve just realised that my APSync flight computer automatically sets the stream rates to 4 Hz and overrides the rates on Telem1. That’s something I’ll have to look into separately.

So… I can get the result I need (streamrate below 1 kbyte/sec) for my serial connection on Telem2 just with the SRx settings. I’ll keep an eye out for whenever the file method makes its way into the stable version.

Thanks again,

AP_sync probably uses mavproxy.
Start it will --streamrate=-1 to solve your problem.

Thank you @amilcarlucas, that worked.

Hello, how can I reduce the frequency of some data?

1 Like