ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question

Revision history [back]

click to hide/show revision 1
initial version

However, I can't find any mention anywhere about the Ordering of messages.

That's correct, we don't expose that QoS setting from DDS, but if it's something you need repeatedly and there's a compelling reason to move it out of "user space" and into the "middleware space" (like performance), then we can consider adding it. To start that process I'd make an issue on the ros2/ros2 or ros2/rmw issue trackers explaining your case for it.

My understanding is that RTPS guarantees that messages are published in the order they are queued but I couldn't work out whether this also means that all subscribers are guaranteed to receive those messages in the same order as well.

My understand is that they are not guaranteed to be received in order. This is basically a performance trade-off. Especially if you're using "reliable" rather than "best effort". For example, consider you received sequence number 1, 2, and 4. How long do you wait for 3 before you deliver 4?

This is why DDS let's configure the behavior, for example, here's the RTI Connext documentation for the ordered access kind of "presentation" QoS:

https://community.rti.com/static/documentation/connext-dds/5.3.0/doc/api/connext_dds/api_cpp2/classdds_1_1core_1_1policy_1_1Presentation.html#acb0c2c5736e6fa722f871e3c68d39787

I link to their documentation only because it's easy to link to, but the other implementations also support it I believe.

There is some flexibility as to how this is implemented. For example, this page on the CoreDX DDS implementation's page says that they will not deliver messages out of order in best effort:

http://www.twinoakscomputing.com/coredx/architecture

So I think the best bet (and we should clarify this in our API documentation) is to assume they are not delivered in order.

We also removed the "sequence number field" from the standard ROS Header message type, with the idea that it was ill formed and that the middleware should give this information outside of the message data. Unfortunately we haven't exposed this information from the middleware yet either (something we could use help with perhaps), but ideally the sequence numbers would be unique and monotonic for each separate publisher (part of the reason a sequence number in the message data was ill formed).

Moreover, the ROS2 node's callback that is registered to process a message that has been subscribed to on a given topic must also be called in the same order that the message was published (i.e. not necessarily in the same order it was received at least in my understanding..).

I don't understand why you think it "must also be called in the same order that the message was published". As far as I know, that's not a requirement or guarantee of the ROS callbacks. This is the typical behavior, but again not required. In general they are processed and passed to the user's callback first come first serve, as provided by DDS. There is no queueing or buffering in the ROS code (at least at this time) which would allow us to "fix" the ordering on delivery to the user's callback.

This is obviously essential for applications such as transmitting audio or video where we most likely want to ensure subscription of all data messages in the same order they were published - possibly with the option of dropping data messages along the way if latency becomes excessive, but nonetheless preserving the chronological ordering in all cases.

In cases like these (not sure transmitting video frames would ever be ideal over this format), you would want to have your own frame number and/or timestamp so that you could keep track of your latest message received and discard any messages you get that are older than those (i.e. when you get an older message late).

We could also add a standard user space mechanism for dealing with this, something that might live in the equivalent of message_filters from ROS 1 (http://wiki.ros.org/message_filters) which already contains things like a timestamp synchronizer, etc...

Obviously that's repeating a piece of functionality that DDS might provide (ordered access via the presentation QoS setting), but we might not be able to rely on that feature. I'd have to check if Fast-RTPS, our default implementation, has this feature or not. I'm guessing not since this is a feature that I feel might fall into the DDS part of the standard versus the RTPS part of the standard which is only relating to the wire protocol.

If we can rely on it, then it might be more efficient to let the middleware handle ordering. However, the nice thing about the user space solution is that you have more insight and control over how it works. Again in your example with video frames wanting them in order, I also imagine in that case you want to avoid latency, so you wouldn't want to wait even one second for a missed frame if you had newer ones already waiting.

Another case I want to confirm is whether messages published and subscribed to by ROS2 intra-process nodes (i.e. which do not use the DDS for transmitting the data) are also guaranteed to both publish messages and subscribe to them in the same order.

The current implementation of intra-process (might change in the future but not right now) uses DDS to send small messages with the address (or meta data which can be used to lookup the address) of the data. This allows us to, again, avoid queueing and buffering in our code (for the most part) but also provides the same QoS behavior as inter-process comms without us having to emulate all of the intrinsic and extrinsic QoS related behaviors.

So, that means that it's possible the "notification" messages which drive intra-process communications could be delivered out of order, which means the actual data could be delivered out of order as well, even if it is delivered with zero-copy for the data itself.

In the future we might change this, or provide another option to use a version of intra-process communication which does not touch DDS at all, but that will come with some trade-offs in terms of behavior.

However, I can't find any mention anywhere about the Ordering of messages.

That's correct, we don't expose that QoS setting from DDS, but if it's something you need repeatedly and there's a compelling reason to move it out of "user space" and into the "middleware space" (like performance), then we can consider adding it. To start that process I'd make an issue on the ros2/ros2 or ros2/rmw issue trackers explaining your case for it.

My understanding is that RTPS guarantees that messages are published in the order they are queued but I couldn't work out whether this also means that all subscribers are guaranteed to receive those messages in the same order as well.

My understand is that they are not guaranteed to be received in order. This is basically a performance trade-off. Especially if you're using "reliable" rather than "best effort". For example, consider you received sequence number 1, 2, and 4. How long do you wait for 3 before you deliver 4?

This is why DDS let's you configure the behavior, for behavior. For example, here's the RTI Connext documentation for the ordered access kind of "presentation" QoS:

https://community.rti.com/static/documentation/connext-dds/5.3.0/doc/api/connext_dds/api_cpp2/classdds_1_1core_1_1policy_1_1Presentation.html#acb0c2c5736e6fa722f871e3c68d39787

I link to their documentation only because it's easy to link to, but the other DDS implementations also support it I believe.believe (though I'm not sure about pure RTPS implementations).

There is also some flexibility as to how this is implemented. For example, this page on the CoreDX DDS implementation's page says that they will not deliver messages out of order in best effort:

http://www.twinoakscomputing.com/coredx/architecture

So I think the best bet (and we should clarify this in our API documentation) documentation -- something else we could use help with :D) is to assume they are not delivered in order.

We also removed the "sequence number field" from the standard ROS Header message type, type (https://github.com/ros2/common_interfaces/pull/2), with the idea that it was ill formed and that the middleware should give this information outside of the message data. Unfortunately we haven't exposed this information from the middleware yet either (something we could use help with perhaps), but ideally the sequence numbers would be unique and monotonic for each separate publisher (part of the reason a sequence number in the message data was ill formed).

Moreover, the ROS2 node's callback that is registered to process a message that has been subscribed to on a given topic must also be called in the same order that the message was published (i.e. not necessarily in the same order it was received at least in my understanding..).

I don't understand why you think it "must also be called in the same order that the message was published". As far as I know, that's not a requirement or guarantee of the ROS callbacks. This Delivery in order is the typical behavior, but again not required. In general they are processed and passed to the user's callback first come first serve, as provided by DDS. There is no queueing or buffering in the ROS code (at least at this time) which would allow us to "fix" the ordering on delivery to the user's callback.

This is obviously essential for applications such as transmitting audio or video where we most likely want to ensure subscription of all data messages in the same order they were published - possibly with the option of dropping data messages along the way if latency becomes excessive, but nonetheless preserving the chronological ordering in all cases.

In cases like these (not sure transmitting video frames would ever be ideal over this format), you would want to have your own frame number and/or timestamp so that you could keep track of your latest message received and discard any messages you get that are older than those (i.e. when you get an older message late).

We could also add a standard user space mechanism for dealing with this, something that might live in the equivalent of message_filters from ROS 1 (http://wiki.ros.org/message_filters) which already contains things like a timestamp synchronizer, etc...

Obviously that's repeating a piece of functionality that DDS might provide (ordered access via the presentation QoS setting), but we might not be able to rely on that feature. I'd have to check if Fast-RTPS, our default implementation, has this feature or not. I'm guessing not since this is a feature that I feel might fall into the DDS part of the standard versus the RTPS part of the standard which is only relating to the wire protocol.

If we can rely on it, then it might be more efficient to let the middleware handle ordering. ordering (and in that case I recommend you make a suggestion to that effect as I described above). However, the nice thing about the user space solution is that you have more insight and control over how it works. Again in your example with video frames wanting them in order, I also imagine in that case you want to avoid latency, so you wouldn't want to wait even one second for a missed frame if you had newer ones already waiting.

Another case I want to confirm is whether messages published and subscribed to by ROS2 intra-process nodes (i.e. which do not use the DDS for transmitting the data) are also guaranteed to both publish messages and subscribe to them in the same order.

The current implementation of intra-process (might change in the future but not right now) uses DDS to send small messages with the address (or meta data which can be used to lookup the address) of the data. This allows us to, again, avoid queueing and buffering in our code (for the most part) but also provides the same QoS behavior as inter-process comms without us having to emulate all of the intrinsic and extrinsic QoS related behaviors.

So, that means that it's possible the "notification" messages which drive intra-process communications could be delivered out of order, which means the actual data could be delivered out of order as well, even if it is delivered with zero-copy for the data itself.

In the future we might change this, or provide another option to use a version of intra-process communication which does not touch DDS at all, but that will come with some trade-offs in terms of behavior.

Edit 1: typos and links