Agenda

Welcome to Part 3 of the uORB Explained Series! In the past posts, we discussed the following:

  • In Part 1 : Why we need uORB, basic functionalities of uORB
  • In Part 2 : What uORB is really about, how uORB topics are instantiated, ORB Metadata

And in this post we will cover the in-depth inner workings of publishing / subscribing to an uORB topic!

Refreshing the Librarian Analogy

In case you haven’t read Part 2, we have established an analogy of uORB as a librarian, who manages books (topics), reading and writing information on them on behalf of readers and authors.

If you haven’t read Part 2 already, I highly recommend you to read it first!

uORB Publishing

What happens when we publish an uORB Topic?

In Part 1, we learned how the uORB::Publication class can be used to publish data to a uORB topic. In this section we will figure out exactly what happens inside the Publication class.

uORB::Publication

You can find the definition in the folder where all the other uORB libraries are : platforms/common/uORB/.

/**
* Publish the struct
* @param data The uORB message struct we are updating.
*/
bool publish(const T &data)
{
       if (!advertised()) {
               advertise(); // Advertise publishing of the topic
       }
 
       return (Manager::orb_publish(get_topic(), _handle, &data) == PX4_OK);
}

https://github.com/PX4/PX4-Autopilot/blob/cdfa65d792f1662ac18862370e840ee11a9f82df/platforms/common/uORB/Publication.hpp#L122-L133

Here I copied the publish( ) function from the uORB::Publication class. First you will notice a line where it calls the advertised( ) function, and if it returns false, advertise( ) is called. How are these functions defined?

// ORB’s Queue size is defined
template<typename T, uint8_t ORB_QSIZE = DefaultQueueSize<T>::value>
// _handle is the internal variable of uORB::Publication class!
orb_advert_t _handle{nullptr};
// This function checks if we have a valid advertiser handle
bool advertised() const { return _handle != nullptr; }
 
// This actually advertises our publication and gets the handle
bool advertise()
{
       if (!advertised()) {
               _handle = orb_advertise_queue(get_topic(), nullptr, ORB_QSIZE);
       }
 
       return advertised();
}

https://github.com/PX4/PX4-Autopilot/blob/cdfa65d792f1662ac18862370e840ee11a9f82df/platforms/common/uORB/Publication.hpp#L113-L120

Basically the advertise() function calls the orb_advertise_queue()’ function to get the ORB topic advertiser handle. You can think of ‘advertising’ as creating a physical book on the shelf. Unless a topic is advertised, the physical book where the data can be read/written isn’t created at all. For example, if none of our modules use the topic pasta_cook, the physical memory space for that topic wouldn’t exist!

The advertised() function simply checks if we have a valid ‘handle’ for advertising.

Take notice that we have a concept of a queue. This can be defined in the uORB message definition to keep a queue of data instead of overwriting the data every time there’s a new publish event. Having a queue takes more memory (pages in the book) for the librarian to maintain, but it also ensures that published messages won’t be lost so easily since we have some buffer to preserve past publications.

ORB topic advertiser handle

Here’s one fact that will hopefully blow your mind: when you publish or subscribe to a topic in uORB, it accesses the device file by the advertiser handle. The device file itself is organized in the /obj folder with the name of the topic, and data is written / read from the internal buffer of the DeviceNode instance tied to that device file. Interested? Confused? Read on!

Let’s see what orb_advert_t, the ORB topic advertiser handle, actually is.

/**
* ORB topic advertiser handle.
*/
typedef void    *orb_advert_t;

https://github.com/PX4/PX4-Autopilot/blob/cdfa65d792f1662ac18862370e840ee11a9f82df/platforms/common/uORB/uORB.cpp#L120-L123

The advertiser handle is owned by a class in the uORB namespace : ‘Manager’ that maintains the active topics on behalf of the interface. You can find the definition of the Manager class here:

https://github.com/PX4/PX4-Autopilot/blob/a7683eea07619d1be8bdcd154754507adbbb9880/platforms/common/uORB/uORBManager.hpp#L168

Here’s the definition of the ‘orb_advertise’ function that’s called inside the orb_advertise_queue() function above:

/**
* Advertise as the publisher of a topic.
*
* This performs the initial advertisement of a topic; it creates the topic
* node in /obj if required and publishes the initial data.
*
* Any number of advertisers may publish to a topic; publications are atomic
* but co-ordination between publishers is not provided by the ORB.
*
* Internally this will call orb_advertise_multi with an instance of 0.
*
* @param meta    The uORB metadata (usually from the ORB_ID() macro)
*      for the topic.
* @param data    A pointer to the initial data to be published.
*      For topics updated by interrupt handlers, the advertisement
*      must be performed from non-interrupt context.
* @param queue_size  Maximum number of buffered elements. If this is 1, no queuing is
*      used.
* @return    nullptr on error, otherwise returns an object pointer
*      that can be used to publish to the topic.
*      If the topic in question is not known (due to an
*      ORB_DEFINE with no corresponding ORB_DECLARE)
*      this function will return nullptr and set errno to ENOENT.
*/
orb_advert_t orb_advertise(const struct orb_metadata *meta, const void *data, unsigned int queue_size = 1)
{
       return orb_advertise_multi(meta, data, nullptr, queue_size);
}

https://github.com/PX4/PX4-Autopilot/blob/cdfa65d792f1662ac18862370e840ee11a9f82df/platforms/common/uORB/uORBManager.hpp#L207-L235

Here we observe a couple of things.

First, the comment mentions that as part of initially advertising a topic, it creates the topic node in /obj. This is really the heart of uORB, as we finally have the concept of a ‘topic node’ in a file system: a “physical book on the shelf”. And yes, uORB manages its data by creating a device file (https://en.wikipedia.org/wiki/Device_file) in the ‘/obj’ folder in the NuttX operating system.

Second, the concept of which topic we are dealing with is exclusively being tracked via the orb_metadata we discussed in the beginning of the Series (Part 1). Remember the __orb_pasta_cook?

Third, the Queue size is taken into account. Which basically tells how much buffer this uORB topic has to store the past received data.

Lastly, it is possible to advertise multiple instances of the same topic with the orb_advertise_multi, which is not the case in orb_advertise. Imagine you have multiple waiters publishing the pasta_cook topic for ordering pasta from the chef. We could all share the same topic and have a giant pot of ‘pasta cook’ order messages.

But if you want to know which waiter has sent the specific message, individual topic instances for each waiter would be needed! That’s why multi-instances are supported. In reality, this is used when the flight controller has multiple gyroscope sensors, etc.

You can check the definition for orb_advertise_multi in uORB::Manager, which will give you an in-depth insight in how the topic nodes are created.

https://github.com/PX4/PX4-Autopilot/blob/cdfa65d792f1662ac18862370e840ee11a9f82df/platforms/common/uORB/uORBManager.cpp#L297-L368

The /obj folder with device files for topics

Regarding the first point in the last section, yes it’s true that uORB maintains the full range of topic instances as a device file in the /obj/ directory. You can check this via connecting your Autopilot, opening up QGC, going to MAVLink Console, and typing : “ls /obj”:

You will find all the names of the topics uORB is handling at that moment. Note how the multiple topic instances are differentiated by having the index (0, 1, 2, ..) at the end. For our pasta example, it would have been ‘pasta_cook0’, ‘pasta_cook1’, and so on.

It’s even more fun to try out “uorb status”, which shows the status of all the topics in an organized view:

Using the status you can see the instance number, number of subscribers, length of the queue, size of the data and the /obj path where the device files for each topic are located. I hope by now you are familiar with all of these concepts! Feel free to play around with the uORB command to learn more!

Internal workings of publishing a data

Remember how the discussion all started with describing the publish function as shown below:

bool publish(const T &data)
{
       if (!advertised()) {
               advertise(); // Advertise publishing of the topic
       }
 
       return (Manager::orb_publish(get_topic(), _handle, &data) == PX4_OK);
}

We now know what the advertising bit does, but what about the publish command?

int uORB::Manager::orb_publish(const struct orb_metadata *meta, orb_advert_t handle, const void *data)
{
       // ...
       return uORB::DeviceNode::publish(meta, handle, data);
}

https://github.com/PX4/PX4-Autopilot/blob/cdfa65d792f1662ac18862370e840ee11a9f82df/platforms/common/uORB/uORBManager.cpp#L399-L410

The orb_publish takes three arguments: the topic’s metadata, the advertiser handle and the pointer to the data itself. And this information gets passed straight to the DeviceNode class, which again is the ‘instance’ of the device file in the /obj folder we discussed earlier. This basically controls the read/write of the data to the uORB topic in the memory. And note that it doesn’t actually write into the device file inside the /obj folder, it’s just using it as a middleware!

If you are interested, you can read the page 3 of the paper that explains the PX4 Architecture, which explains:

The topic handle is implemented as virtual file, allowing listeners to do blocking waits on interfaces and drivers (such as serial ports) and topics in parallel. This is commonly not supported by middleware solutions but saves a complete worker thread.

Pretty complicated! We are going pretty deep here, but one last fascinating thing is that the orb_advert_t handle is actually a pointer to the DeviceNode object tied to the specific topic’s device file! It just has a different name as a “ORB Advertiser” but it just points to the device file of that topic!

ssize_t
uORB::DeviceNode::publish(const orb_metadata *meta, orb_advert_t handle, const void *data)
{
       uORB::DeviceNode *devnode = (uORB::DeviceNode *)handle;
       int ret;
       // ...
       /* call the devnode write method with no file pointer */
       ret = devnode->write(nullptr, (const char *)data, meta->o_size);
 
       // Write to the buffer failed
       if (ret < 0) {
               errno = -ret;
               return PX4_ERROR;
       }
       // Number of bytes written doesn’t match the topic’s struct size
       if (ret != (int)meta->o_size) {
               errno = EIO;
               return PX4_ERROR;
       }
       // ...
       return PX4_OK;
}

https://github.com/PX4/PX4-Autopilot/blob/cdfa65d792f1662ac18862370e840ee11a9f82df/platforms/common/uORB/uORBDeviceNode.cpp#L276-L323

As shown above, when you publish a data it does a simple buffer write to that device node. Pretty simple right? uORB publishing in a nutshell is a write command to a buffer in the memory!

uORB Subscribing

uORB::DeviceNode and UNIX

Before learning how Subscription works, here’s a little history: UNIX system considers everything to be a file: even the connected USB devices (if curious, type “ls /dev/tty*” in your linux console), and they call this a ‘Device File’.

So sending data to the USB drive can be done by just writing to the device file of this USB as if it was a text file. This is what’s used for the uORB Topics, which is possible since PX4 is based on NuttX, which is based on UNIX.

When you write to the USB, you also read the data from it. Therefore it should be no surprise that the Subscription for uORB also uses the DeviceNode!

uORB::Subscription

Here I copied a small part of the Subscription class:

// Member of the Subscription class
void *_node{nullptr};
 
// Checks if we have a valid subscription node
bool valid() const { return _node != nullptr; }
 
/**
* Update the struct
* @param dst The uORB message struct we are updating.
*/
bool update(void *dst)
{
       if (!valid()) {
               subscribe();
       }
 
       return valid() ? Manager::orb_data_copy(_node, dst, _last_generation, true) : false;
}

https://github.com/PX4/PX4-Autopilot/blob/cdfa65d792f1662ac18862370e840ee11a9f82df/platforms/common/uORB/Subscription.hpp#L118-L159

It is very similar to the Publication class. The _node object is the DeviceNode pointer for the topic instance, just like the advertisement handle. It has a similar check logic to verify if the _node is a valid pointer, and if not it subscribes to the topic. Let’s figure out what the subscribe() function does.

uORB::Subscription::subscribe()

// Subscribes to the topic
bool Subscription::subscribe()
{
       // check if already subscribed
       if (_node != nullptr) {
               return true;
       }
 
       if (_orb_id != ORB_ID::INVALID && uORB::Manager::get_instance()) {
               unsigned initial_generation;
               void *node = uORB::Manager::orb_add_internal_subscriber(_orb_id, _instance, &initial_generation);
 
               if (node) {
                       _node = node;
                       _last_generation = initial_generation;
                       return true;
               }
       }
 
       return false;
}

https://github.com/PX4/PX4-Autopilot/blob/cdfa65d792f1662ac18862370e840ee11a9f82df/platforms/common/uORB/Subscription.cpp#L45-L64

Basically the ‘uORB::Manager::orb_add_internal_subscriber’ gets called and _node gets updated to the DeviceNode pointer returned from the function. Also, there’s quite an interesting thing going on with the ‘generation’. Let’s figure out what this is all about:

void *uORB::Manager::orb_add_internal_subscriber(ORB_ID orb_id, uint8_t instance, unsigned *initial_generation)
{
       uORB::DeviceNode *node = nullptr;
       DeviceMaster *device_master = uORB::Manager::get_instance()->get_device_master();
 
       if (device_master != nullptr) {
               node = device_master->getDeviceNode(get_orb_meta(orb_id), instance);
 
               if (node) {
                       node->add_internal_subscriber();
                       *initial_generation = node->get_initial_generation();
               }
       }
 
       return node;
}

https://github.com/PX4/PX4-Autopilot/blob/cdfa65d792f1662ac18862370e840ee11a9f82df/platforms/common/uORB/uORBManager.cpp#L458-L473

OK so the device node part is what we already know about, but it also calls ‘add_internal_subscriber’ of the DeviceNode. This basically updates the subscriber count inside the DeviceNode object, to keep track of how many subscribers it has for the topic. Remember the ‘# SUB’ column from the “uorb status” output?

Then it fetches the ‘generation’ number. This is an internally tracked number inside DeviceNode, and it increases whenever new data is published on the topic. By keeping track of this number internally on Subscriber’s side, it is possible to detect whether new data is available or not. This is how uORB knows whether new data is available to the Subscriber or not. Which is why it needs to internally store the value.

There’s just so much to unpack regarding the generation number, and for curious readers I will leave this link for you to check exactly how it gets utilized to fetch data from the DeviceNode:

https://github.com/PX4/PX4-Autopilot/blob/cdfa65d792f1662ac18862370e840ee11a9f82df/platforms/common/uORB/uORBDeviceNode.hpp#L217-L266

Thank you

Did this blog post explain the concept clearly? Did I miss anything important? Do you have suggestions on how to improve this blog post? Or have any suggested future topics? If so, please give us your valuable feedback in the form below. I’m eager to read your feedback and thoughts on this blog post.

Fun Links to browse to learn more about uORB Publish / Subscribe

Here are some links that you can visit in order to understand what we were talking about more in detail!

  1. uORBDeviceNode, the magic device file handle : https://github.com/PX4/PX4-Autopilot/blob/57a02896276969ffffc82636170f93bd9abfd0fc/platforms/common/uORB/uORBDeviceNode.hpp
  2. uORB Manager, which handles advertising, subscribing, etc : https://github.com/PX4/PX4-Autopilot/blob/57a02896276969ffffc82636170f93bd9abfd0fc/platforms/common/uORB/uORBManager.hpp
  3. uORB Subscription : https://github.com/PX4/PX4-Autopilot/blob/57a02896276969ffffc82636170f93bd9abfd0fc/platforms/common/uORB/uORBManager.hpp
  4. uORB Publication : https://github.com/PX4/PX4-Autopilot/blob/57a02896276969ffffc82636170f93bd9abfd0fc/platforms/common/uORB/uORBManager.hpp

Want to check out more episodes of the PX4 Explained Series?

Meet you next time!

Junwoo

PS: You can find me on Dronecode Discord Server (click to get an invite)