Skip to content

Send and Receive 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.

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:

MAVLink messageuORB topic
NAMED_VALUE_FLOATdebug_key_value
DEBUGdebug_value
DEBUG_VECTdebug_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:

All required to set up a debug publication is this code snippet. First add the header file:

C
#include <uORB/uORB.h>
#include <uORB/topics/debug_key_value.h>
#include <string.h>

Then advertise the debug value topic (one advertisement for different published names is sufficient). Put this in front of your main loop:

C
/* advertise debug value */
struct debug_key_value_s dbg;
strncpy(dbg.key, "velx", sizeof(dbg.key));
dbg.value = 0.0f;
orb_advert_t pub_dbg = orb_advertise(ORB_ID(debug_key_value), &dbg);

And sending in the main loop is even simpler:

C
dbg.value = position[0];
orb_publish(ORB_ID(debug_key_value), pub_dbg, &dbg);

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:

QGC debugvalue 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:

C
#include <poll.h>
#include <uORB/topics/debug_key_value.h>

int debug_sub_fd = orb_subscribe(ORB_ID(debug_key_value));
[...]

Then poll on the topic:

C
[...]
/* one could wait for multiple topics with this technique, just using one here */
px4_pollfd_struct_t fds[] = {
    { .fd = debug_sub_fd,   .events = POLLIN },
};

while (true) {
    /* wait for debug_key_value for 1000 ms (1 second) */
    int poll_ret = px4_poll(fds, 1, 1000);

    [...]

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:

C
    [...]
    if (fds[0].revents & POLLIN) {
        /* obtained data for the first file descriptor */
        struct debug_key_value_s dbg;

        /* copy data into local buffer */
        orb_copy(ORB_ID(debug_key_value), debug_sub_fd, &dbg);

        /* filter message based on its key attribute */
        if (strcmp(_sub_debug_vect.get().key, "velx") == 0) {
            PX4_INFO("velx:\t%8.4f", dbg.value);
        }
    }
}