Sending Debug Values
It is often necessary during software development to output individual important numbers. This is where the generic NAMED_VALUE_FLOAT
, DEBUG
and DEBUG_VECT
packets of MAVLink come in.
Mapping between MAVLink Debug Messages and uORB Topics
MAVLink debug messages are translated to/from uORB topics. In order to send or receive a MAVLink debug message, you have to respectively publish or subscribe to the corresponding topic. Here is a table that summarizes the mapping between MAVLink debug messages and uORB topics:
NAMED_VALUE_FLOAT
debug_key_value
DEBUG
debug_value
DEBUG_VECT
debug_vect
Tutorial: Send String / Float Pairs
This tutorial shows how to send the MAVLink message NAMED_VALUE_FLOAT
using the associated uORB topic debug_key_value
.
The code for this tutorial is available here:
Enable the tutorial app by ensuring the MAVLink debug app (CONFIG_EXAMPLES_PX4_MAVLINK_DEBUG) is in the config of your board and set set to 'y'.
All required to set up a debug publication is this code snippet. First add the header file:
Then advertise the debug value topic (one advertisement for different published names is sufficient). Put this in front of your main loop:
And sending in the main loop is even simpler:
:::warning Multiple debug messages must have enough time between their respective publishings for Mavlink to process them. This means that either the code must wait between publishing multiple debug messages, or alternate the messages on each function call iteration. :::
The result in QGroundControl then looks like this on the real-time plot:
Tutorial: Receive String / Float Pairs
The following code snippets show how to receive the velx
debug variable that was sent in the previous tutorial.
First, subscribe to the topic debug_key_value
:
Then poll on the topic:
When a new message is available on the debug_key_value
topic, do not forget to filter it based on its key attribute in order to discard the messages with key different than velx
:
Last updated