Disabling MavLink/MavROS messages

What is the best way to disable specific mavlink messages that are sent over Telem2 to the Offboard computer? I would like to disable all messages that I am not using so that the messages I want can go faster over the serial bus.

I’ve seen many places how to change the publish rate. Something like this:
mavlink stream -d /dev/ttyS2 -s ATTITUDE_QUATERNION -r 200

I have used this successfully by adding it to the rcS file.

Is there documentation on the mavlink command above? Are there options besides stream? For example, is there a stop?

If for whatever reason I wanted to stop publishing the attitude, could I do something like:
mavlink stop -d /dev/ttyS2 -s ATTITUDE_QUATERNION

Or what would be the proper way to do that? Do I just set the rate to 0?

Also, it would be nice if I could stop all of them and then start only the ones I want to listen to. Is there a stop all command that I could use, followed by mavlink stream ...? Or maybe a mavlink start between them? Any info on this would be great.

By they way, the root of my issue is that I would like certain topics at a faster rate for my offboard computing. My thought is that the rates are limited by the baud rate over the serial bus, but I guess that could be wrong.

I’ve set the baud rate on the PX4 to 921600 (the max).

Using the mavlink stream command mentioned above, I can increase the rate of various things, but not indefinitely.

For example, the default rate of the Lidar Lite height sensor is publishing at 10 Hz with no changes. I added this line:
mavlink stream -d /dev/ttyS2 -s DISTANCE_SENSOR -r 100
to my rcS file, but after that the rate only went up to 20 Hz. The specs on the sensor itself say that under normal operation it can do 270Hz, and way faster if you change some parameters.

I have similar issues with most of the sensors and topics. The rates I am achieving in practice are far lower than expected.

See Enable/Disable mavlink message, px4fmu-v2

Should be in the same file under the off_board section

Thanks, I was able to find that. It’s actually under the “on_board” section, which is a very confusing name since everywhere else it’s called “offboard”.

Anyway, the distance sensor is still limited to 20 Hz. Is there anywhere else that this rate could be limiting besides here? Maybe in the i2c driver or something? I’ve started looking in these areas but haven’t had any success yet.

I was able to change ATTITUDE and ATTITUDE_QUATERNION to 250 in this file, and this results in them publishing at about 225 Hz in reality. I changed both DISTANCE_SENSOR and ALTITUDE to 100, but the output is still about 19.5 Hz. It did increase from 10 Hz prior to the change, but I’d like to get it up into the triple digits.

There’s nothing else in here that is specified at 20Hz, so I don’t think I’m just missing one of them to change. I also disabled a bunch of messages that I’m not using simply by commenting out the line. I was hoping this would increase the speed of everything else on the serial port.

I found it!!!

It was in fact in the driver. In LidarLite.h there is a macro defined as
#define LL40LS_CONVERSION_INTERVAL 50*1000UL /* 50ms */

50ms corresponds to 20 Hz, which was the maximum rate I was seeing. I changed this to 5 ms, corresponding to 200Hz. Now I’m able to get that topic faster.

Does anyone know if there are issues with polling the Lidar at an order of magnitude faster rate? Will it screw up the Local Position Estimator or EKF?