From 70cf9aad22fcadb57b1faa0ec341cb69655ecb0d Mon Sep 17 00:00:00 2001 From: burekn Date: Wed, 13 Feb 2019 01:23:39 -0800 Subject: [PATCH 01/12] Adds design document for Deadline, Liveliness, and Lifespan. This commit adds a new design document that explores how support should be added to ROS for Deadline, Liveliness, and Lifespan QoS policies. Relates to issue: https://github.com/ros2/rclcpp/issues/572 --- articles/qos_deadline_liveliness_lifespan.md | 145 +++++++++++++++++++ 1 file changed, 145 insertions(+) create mode 100644 articles/qos_deadline_liveliness_lifespan.md diff --git a/articles/qos_deadline_liveliness_lifespan.md b/articles/qos_deadline_liveliness_lifespan.md new file mode 100644 index 000000000..d2930a32b --- /dev/null +++ b/articles/qos_deadline_liveliness_lifespan.md @@ -0,0 +1,145 @@ +--- +layout: default +title: ROS QoS - Deadline, Liveliness, and Lifespan +permalink: articles/qos_deadline_liveliness_lifespan.html +abstract: + This article makes the case for adding Deadline, Liveliness, and Lifespan QoS settings to ROS. It outlines the requirements and explores the ways it could be integrated with the existing code base. +author: '[Nick Burek](https://github.com/nburek)' +published: true +categories: Middleware +date: February 13th 2019 +--- + +{:toc} + +# {{ page.title }} + +
+{{ page.abstract }} +
+ +Original Author: {{ page.author }} + +Glossary: + +- DDS - Data Distribution Service +- RTPS - Real-Time Publish Subscribe +- QoS - Quality of Service + +## Existing ROS QoS Settings +While DDS provides many settings to enable fine-grained control over the Quality of Service (QOS) for entities, ROS only provides native support for a handful of them. ROS users are able to specify the History, Depth, Reliability, and Durability via a QoS configuration struct when they create Publishers, Subscribers, etc. + +This leaves a lot of QoS settings that can only be set if DDS vendor can load additional default settings via a configuration file. If a user wants to hook their code into these additional QoS settings then they would need to get a reference to the rmw implementation and program against the vendor specific API. Without the abstraction layer provided by ROS their code becomes less portable. + +## Proposed Changes +As users start to build more robust applications, they are going to need more control over when data is being delivered and information about when the system is failing. +To address these needs it was proposed that we start by adding support for the following new DDS QoS settings. + +### Proposed New QoS Settings +- Deadline - The deadline policy establishes a contract for how often publishers will receive data and how often subscribers expect to receive data. +- Liveliness - The liveliness policy is useful for determining if entities on the network are "alive" and notifying interested parties when they are not. +- Lifespan - The lifespan policy is useful for preventing the delivery of stale messages by specifying a time at which they should no longer be delivered. + +More detailed information on these policies can be found below in Appendix A. + +### DDS Vendor Support +Some of the primary DDS vendors that ROS supports already provide support for these QoS settings. However, the default vendor, Fast-RTPS, does not yet provide full support for these new QoS settings in their library. This does not have to be a blocker for adding support for these policy settings to ROS. We can start adding support for them and just log warning messages when a user attempts to specify an unsupported QoS setting. When support is eventually added for the policies in the vendor library then we can enable it in the rmw implementation. + +### Native ROS Support vs Vendor Configuration +It may be argued that many DDS QoS settings could be used with ROS by simply specifying them using the vendor specific configuration mechanism, such as the xml configuration files used by RTI Connext. This may be acceptable for some QoS policies that only impact the behavior of the underlying DDS middleware, but in the case where support for QoS policy impacts the behavior of the application code this is not good enough. + +For example, it doesn't do much good to specify deadline policy via the vendor configuration mechanism if your ROS application is never notified when a publisher violates the deadline. In such cases the application needs to be able to respond to these events in order to log failures, notify users, or adjust system behavior. + +When interaction with the application is needed it is also preferable to have a ROS defined interface as opposed to having the application program directly against the DDS vendor API. Many nodes in ROS are written to be shared and reused by the community. Since different end users will want to use different middleware vendors for their applications, it is important to maintain that flexibility for nodes that want to take advantage of these additional QoS policies. + +**Based on this criteria, native ROS support should be provided for Deadline and Liveliness but not for the Lifespan policy.** While Deadline and Liveliness will both have events that the application will initiate and need to be informed of, the Lifespan policy can be entirely handled by the underlying DDS service without the need for any intervention by the application. + +### ROS Changes +These are the various changes that would be needed within ROS in order to natively support Deadline and Liveliness. + +#### Topic Status Event Handler +Both the Deadline and Liveliness policies generate events from the DDS service layer that the application will need to be informed of. For Deadlines, the subscriber receives event notifications if it doesn't receive anything within the deadline and the publisher receives event notifications if it doesn't publish anything within the deadline. For Liveliness, subscribers receive events when the publisher they're listening to is no longer alive. Both of these fall under a category of "Topic Status Events". + +To handle these notifications, a new callback function can be provided by the user that will be called any time a `TopicStatusEvent` occurs for a particular topic. It will receive as a parameter a `TopicStatusEvent` enum value that specifies what type of event took place and a timestamp of when the event took place. This callback function would be provided by the user's application when it calls the create function for publishers and subscribers. The constructors and create functions will be overloaded to make this new handler optional. + +The choice to use a callback function as opposed to another notification mechanism is to remain consistent with the existing ROS interface and not add a new method of waiting on ROS data/events. + +#### QoS Struct +Minimal changes will need to be made to the QoS struct that is passed into the creation functions for Topics, Services, and Actions. A couple new enum values will be added for the Deadline and Liveliness settings and then a couple integers will be added to specify the time values for these policies. + +#### Assert Liveliness Functions +Two new functions would need to be added that could be used by the application to explicitly assert liveliness. One function to assert liveliness at the Node level and one to assert it at the Topic level. While liveliness will also be implicitly assumed just based on sending messages, it will also be able to be explicitly declared by the application. These functions will need to be implemented in the rmw layer, the rcl layer, and the language specific client libraries. + +#### rcl_wait and rmw_wait +The rcl layer is currently using a WaitSet in order to be informed of events from the rmw layer, such as incoming messages. These WaitSets contain lists of several types of conditions, such as timers firing or subscriptions receiving data. In order to support new Topic Status Events, a new type will be added to the existing WaitSet and the rmw layer will set them when these events occur. + + +## FAQ +- How does the Deadline policy take into account the additional overhead of ROS (such as deserialization) when determining if a deadline was missed? + - As a simplification it is not going to attempt to take into account any ROS overhead. A deadline will be considered missed if the rmw layer does not receive a message by the deadline and not if the user application on top of ROS does not receive it by the deadline. + + +## Open Questions +- How do Deadlines and Liveliness impact Services and Actions? + + +## Appendix A +Definitions of the QoS policies from the DDS spec. + +### Deadline +This policy is useful for cases where a Topic is expected to have each instance updated periodically. On the publishing side this +setting establishes a contract that the application must meet. On the subscribing side the setting establishes a minimum +requirement for the remote publishers that are expected to supply the data values. + +When the Service ‘matches’ a DataWriter and a DataReader it checks whether the settings are compatible (i.e., offered +deadline period<= requested deadline period) if they are not, the two entities are informed (via the listener or condition +mechanism) of the incompatibility of the QoS settings and communication will not occur. + +Assuming that the reader and writer ends have compatible settings, the fulfillment of this contract is monitored by the Service +and the application is informed of any violations by means of the proper listener or condition. + +The value offered is considered compatible with the value requested if and only if the inequality “offered deadline period <= +requested deadline period” evaluates to ‘TRUE.’ + +The setting of the DEADLINE policy must be set consistently with that of the TIME_BASED_FILTER. For these two policies +to be consistent the settings must be such that “deadline period>= minimum_separation.” + +### Liveliness +This policy controls the mechanism and parameters used by the Service to ensure that particular entities on the network are +still “alive.” The liveliness can also affect the ownership of a particular instance, as determined by the OWNERSHIP QoS +policy. + +This policy has several settings to support both data-objects that are updated periodically as well as those that are changed +sporadically. It also allows customizing for different application requirements in terms of the kinds of failures that will be +detected by the liveliness mechanism. + +The AUTOMATIC liveliness setting is most appropriate for applications that only need to detect failures at the process- +level 27 , but not application-logic failures within a process. The Service takes responsibility for renewing the leases at the +required rates and thus, as long as the local process where a DomainParticipant is running and the link connecting it to remote +participants remains connected, the entities within the DomainParticipant will be considered alive. This requires the lowest +overhead. + +The MANUAL settings (MANUAL_BY_PARTICIPANT, MANUAL_BY_TOPIC), require the application on the publishing +side to periodically assert the liveliness before the lease expires to indicate the corresponding Entity is still alive. The action +can be explicit by calling the assert_liveliness operations, or implicit by writing some data. + +The two possible manual settings control the granularity at which the application must assert liveliness. +• The setting MANUAL_BY_PARTICIPANT requires only that one Entity within the publisher is asserted to be alive to +deduce all other Entity objects within the same DomainParticipant are also alive. +• The setting MANUAL_BY_TOPIC requires that at least one instance within the DataWriter is asserted. + +### Lifespan +The purpose of this QoS is to avoid delivering “stale” data to the application. + +Each data sample written by the DataWriter has an associated ‘expiration time’ beyond which the data should not be delivered +to any application. Once the sample expires, the data will be removed from the DataReader caches as well as from the +transient and persistent information caches. + +The ‘expiration time’ of each sample is computed by adding the duration specified by the LIFESPAN QoS to the source +timestamp. The source timestamp is either automatically computed by the Service +each time the DataWriter write operation is called, or else supplied by the application by means of the write_w_timestamp +operation. + +This QoS relies on the sender and receiving applications having their clocks sufficiently synchronized. If this is not the case +and the Service can detect it, the DataReader is allowed to use the reception timestamp instead of the source timestamp in its +computation of the ‘expiration time. \ No newline at end of file From 05ec0a514bac57abdf215dafc2d600527f1472c0 Mon Sep 17 00:00:00 2001 From: burekn Date: Wed, 13 Feb 2019 09:07:13 -0800 Subject: [PATCH 02/12] Fixing format to match the developers guide and fleshing out the open questions. --- articles/qos_deadline_liveliness_lifespan.md | 89 +++++++++++++++----- 1 file changed, 66 insertions(+), 23 deletions(-) diff --git a/articles/qos_deadline_liveliness_lifespan.md b/articles/qos_deadline_liveliness_lifespan.md index d2930a32b..883fc9386 100644 --- a/articles/qos_deadline_liveliness_lifespan.md +++ b/articles/qos_deadline_liveliness_lifespan.md @@ -27,66 +27,107 @@ Glossary: - QoS - Quality of Service ## Existing ROS QoS Settings -While DDS provides many settings to enable fine-grained control over the Quality of Service (QOS) for entities, ROS only provides native support for a handful of them. ROS users are able to specify the History, Depth, Reliability, and Durability via a QoS configuration struct when they create Publishers, Subscribers, etc. -This leaves a lot of QoS settings that can only be set if DDS vendor can load additional default settings via a configuration file. If a user wants to hook their code into these additional QoS settings then they would need to get a reference to the rmw implementation and program against the vendor specific API. Without the abstraction layer provided by ROS their code becomes less portable. +While DDS provides many settings to enable fine-grained control over the Quality of Service (QOS) for entities, ROS only provides native support for a handful of them. ROS users are able to specify the History, Depth, Reliability, and Durability via a QoS configuration struct when they create Publishers, Subscribers, etc. + +This leaves a lot of QoS settings that can only be set if DDS vendor can load additional default settings via a configuration file. +If a user wants to hook their code into these additional QoS settings then they would need to get a reference to the rmw implementation and program against the vendor specific API. +Without the abstraction layer provided by ROS their code becomes less portable. ## Proposed Changes -As users start to build more robust applications, they are going to need more control over when data is being delivered and information about when the system is failing. -To address these needs it was proposed that we start by adding support for the following new DDS QoS settings. + +As users start to build more robust applications, they are going to need more control over when data is being delivered and information about when the system is failing. +To address these needs it was proposed that we start by adding support for the following new DDS QoS settings. ### Proposed New QoS Settings -- Deadline - The deadline policy establishes a contract for how often publishers will receive data and how often subscribers expect to receive data. -- Liveliness - The liveliness policy is useful for determining if entities on the network are "alive" and notifying interested parties when they are not. -- Lifespan - The lifespan policy is useful for preventing the delivery of stale messages by specifying a time at which they should no longer be delivered. -More detailed information on these policies can be found below in Appendix A. +- Deadline - The deadline policy establishes a contract for how often publishers will receive data and how often subscribers expect to receive data. +- Liveliness - The liveliness policy is useful for determining if entities on the network are "alive" and notifying interested parties when they are not. +- Lifespan - The lifespan policy is useful for preventing the delivery of stale messages by specifying a time at which they should no longer be delivered. + +More detailed information on these policies can be found below in Appendix A. ### DDS Vendor Support -Some of the primary DDS vendors that ROS supports already provide support for these QoS settings. However, the default vendor, Fast-RTPS, does not yet provide full support for these new QoS settings in their library. This does not have to be a blocker for adding support for these policy settings to ROS. We can start adding support for them and just log warning messages when a user attempts to specify an unsupported QoS setting. When support is eventually added for the policies in the vendor library then we can enable it in the rmw implementation. + +Some of the primary DDS vendors that ROS supports already provide support for these QoS settings. +However, the default vendor, Fast-RTPS, does not yet provide full support for these new QoS settings in their library. +This does not have to be a blocker for adding support for these policy settings to ROS. +We can start adding support for them and just log warning messages when a user attempts to specify an unsupported QoS setting. +When support is eventually added for the policies in the vendor library then we can enable it in the rmw implementation. ### Native ROS Support vs Vendor Configuration -It may be argued that many DDS QoS settings could be used with ROS by simply specifying them using the vendor specific configuration mechanism, such as the xml configuration files used by RTI Connext. This may be acceptable for some QoS policies that only impact the behavior of the underlying DDS middleware, but in the case where support for QoS policy impacts the behavior of the application code this is not good enough. -For example, it doesn't do much good to specify deadline policy via the vendor configuration mechanism if your ROS application is never notified when a publisher violates the deadline. In such cases the application needs to be able to respond to these events in order to log failures, notify users, or adjust system behavior. +It may be argued that many DDS QoS settings could be used with ROS by simply specifying them using the vendor specific configuration mechanism, such as the xml configuration files used by RTI Connext. +This may be acceptable for some QoS policies that only impact the behavior of the underlying DDS middleware, but in the case where support for QoS policy impacts the behavior of the application code this is not good enough. -When interaction with the application is needed it is also preferable to have a ROS defined interface as opposed to having the application program directly against the DDS vendor API. Many nodes in ROS are written to be shared and reused by the community. Since different end users will want to use different middleware vendors for their applications, it is important to maintain that flexibility for nodes that want to take advantage of these additional QoS policies. +For example, it doesn't do much good to specify deadline policy via the vendor configuration mechanism if your ROS application is never notified when a publisher violates the deadline. +In such cases the application needs to be able to respond to these events in order to log failures, notify users, or adjust system behavior. -**Based on this criteria, native ROS support should be provided for Deadline and Liveliness but not for the Lifespan policy.** While Deadline and Liveliness will both have events that the application will initiate and need to be informed of, the Lifespan policy can be entirely handled by the underlying DDS service without the need for any intervention by the application. +When interaction with the application is needed it is also preferable to have a ROS defined interface as opposed to having the application program directly against the DDS vendor API. +Many nodes in ROS are written to be shared and reused by the community. +Since different end users will want to use different middleware vendors for their applications, it is important to maintain that flexibility for nodes that want to take advantage of these additional QoS policies. + +**Based on this criteria, native ROS support should be provided for Deadline and Liveliness but not for the Lifespan policy.** +While Deadline and Liveliness will both have events that the application will initiate and need to be informed of, the Lifespan policy can be entirely handled by the underlying DDS service without the need for any intervention by the application. ### ROS Changes -These are the various changes that would be needed within ROS in order to natively support Deadline and Liveliness. + +These are the various changes that would be needed within ROS in order to natively support Deadline and Liveliness. #### Topic Status Event Handler -Both the Deadline and Liveliness policies generate events from the DDS service layer that the application will need to be informed of. For Deadlines, the subscriber receives event notifications if it doesn't receive anything within the deadline and the publisher receives event notifications if it doesn't publish anything within the deadline. For Liveliness, subscribers receive events when the publisher they're listening to is no longer alive. Both of these fall under a category of "Topic Status Events". -To handle these notifications, a new callback function can be provided by the user that will be called any time a `TopicStatusEvent` occurs for a particular topic. It will receive as a parameter a `TopicStatusEvent` enum value that specifies what type of event took place and a timestamp of when the event took place. This callback function would be provided by the user's application when it calls the create function for publishers and subscribers. The constructors and create functions will be overloaded to make this new handler optional. +Both the Deadline and Liveliness policies generate events from the DDS service layer that the application will need to be informed of. +For Deadlines, the subscriber receives event notifications if it doesn't receive anything within the deadline and the publisher receives event notifications if it doesn't publish anything within the deadline. +For Liveliness, subscribers receive events when the publisher they're listening to is no longer alive. Both of these fall under a category of "Topic Status Events". -The choice to use a callback function as opposed to another notification mechanism is to remain consistent with the existing ROS interface and not add a new method of waiting on ROS data/events. +To handle these notifications, a new callback function can be provided by the user that will be called any time a `TopicStatusEvent` occurs for a particular topic. +It will receive as a parameter a `TopicStatusEvent` enum value that specifies what type of event took place and a timestamp of when the event took place. +This callback function would be provided by the user's application when it calls the create function for publishers and subscribers. +The constructors and create functions will be overloaded to make this new handler optional. + +The choice to use a callback function as opposed to another notification mechanism is to remain consistent with the existing ROS interface and not add a new method of waiting on ROS data/events. #### QoS Struct -Minimal changes will need to be made to the QoS struct that is passed into the creation functions for Topics, Services, and Actions. A couple new enum values will be added for the Deadline and Liveliness settings and then a couple integers will be added to specify the time values for these policies. + +Minimal changes will need to be made to the QoS struct that is passed into the creation functions for Topics, Services, and Actions. +A couple new enum values will be added for the Deadline and Liveliness settings and then a couple integers will be added to specify the time values for these policies. #### Assert Liveliness Functions -Two new functions would need to be added that could be used by the application to explicitly assert liveliness. One function to assert liveliness at the Node level and one to assert it at the Topic level. While liveliness will also be implicitly assumed just based on sending messages, it will also be able to be explicitly declared by the application. These functions will need to be implemented in the rmw layer, the rcl layer, and the language specific client libraries. + +Two new functions would need to be added that could be used by the application to explicitly assert liveliness. +One function to assert liveliness at the Node level and one to assert it at the Topic level. +While liveliness will also be implicitly assumed just based on sending messages, it will also be able to be explicitly declared by the application. +These functions will need to be implemented in the rmw layer, the rcl layer, and the language specific client libraries. #### rcl_wait and rmw_wait -The rcl layer is currently using a WaitSet in order to be informed of events from the rmw layer, such as incoming messages. These WaitSets contain lists of several types of conditions, such as timers firing or subscriptions receiving data. In order to support new Topic Status Events, a new type will be added to the existing WaitSet and the rmw layer will set them when these events occur. + +The rcl layer is currently using a WaitSet in order to be informed of events from the rmw layer, such as incoming messages. +These WaitSets contain lists of several types of conditions, such as timers firing or subscriptions receiving data. +In order to support new Topic Status Events, a new type will be added to the existing WaitSet and the rmw layer will set them when these events occur. ## FAQ -- How does the Deadline policy take into account the additional overhead of ROS (such as deserialization) when determining if a deadline was missed? - - As a simplification it is not going to attempt to take into account any ROS overhead. A deadline will be considered missed if the rmw layer does not receive a message by the deadline and not if the user application on top of ROS does not receive it by the deadline. + +- How does the Deadline policy take into account the additional overhead of ROS (such as deserialization) when determining if a deadline was missed? + - As a simplification it is not going to attempt to take into account any ROS overhead. A deadline will be considered missed if the rmw layer does not receive a message by the deadline and not if the user application on top of ROS does not receive it by the deadline. ## Open Questions -- How do Deadlines and Liveliness impact Services and Actions? + +- How do Deadlines and Liveliness impact Services and Actions? + - Actions and Services are slightly different in that they are composed of multiple Topics. It may make sense for a Service to specify a Liveliness policy on its own DataWriter, but it likely doesn't need the same policy on the DataReader. + - One option would be to only apply the QoS settings to one or another of the topics. So Liveliness may only apply to the DataWriters in Services and Actions and the Deadlines might apply only to the "update" topic data writer for Actions. + - Another option would be to modify the interface to allow for different QoS policies for the different underlying Topics, though this adds more complexity. +- How do these new QoS settings impact non-DDS based rmw implementations? + - While these QoS policies are native to the DDS standard, any non-DDS based rmw layer will not have native support for these policies. What does this mean for those implementations? Will they be forced to implement these features in their rmw_implementation layer to be officially supported? ## Appendix A + Definitions of the QoS policies from the DDS spec. ### Deadline + This policy is useful for cases where a Topic is expected to have each instance updated periodically. On the publishing side this setting establishes a contract that the application must meet. On the subscribing side the setting establishes a minimum requirement for the remote publishers that are expected to supply the data values. @@ -105,6 +146,7 @@ The setting of the DEADLINE policy must be set consistently with that of the TIM to be consistent the settings must be such that “deadline period>= minimum_separation.” ### Liveliness + This policy controls the mechanism and parameters used by the Service to ensure that particular entities on the network are still “alive.” The liveliness can also affect the ownership of a particular instance, as determined by the OWNERSHIP QoS policy. @@ -129,6 +171,7 @@ deduce all other Entity objects within the same DomainParticipant are also alive • The setting MANUAL_BY_TOPIC requires that at least one instance within the DataWriter is asserted. ### Lifespan + The purpose of this QoS is to avoid delivering “stale” data to the application. Each data sample written by the DataWriter has an associated ‘expiration time’ beyond which the data should not be delivered From 33431f5396955e3c0993677183f9d2fbfcdcfba5 Mon Sep 17 00:00:00 2001 From: burekn Date: Mon, 18 Feb 2019 14:00:07 -0800 Subject: [PATCH 03/12] Updates the new QoS policy design based on feedback from reviews. --- articles/qos_deadline_liveliness_lifespan.md | 143 +++++++++++++------ 1 file changed, 98 insertions(+), 45 deletions(-) diff --git a/articles/qos_deadline_liveliness_lifespan.md b/articles/qos_deadline_liveliness_lifespan.md index 883fc9386..166575706 100644 --- a/articles/qos_deadline_liveliness_lifespan.md +++ b/articles/qos_deadline_liveliness_lifespan.md @@ -25,63 +25,100 @@ Glossary: - DDS - Data Distribution Service - RTPS - Real-Time Publish Subscribe - QoS - Quality of Service +- Client - Refers to an application that connects to a ROS Service to send requests and receive responses. +- Owner - Refers to the application that is running a ROS Service that receives requests and sends responses. ## Existing ROS QoS Settings -While DDS provides many settings to enable fine-grained control over the Quality of Service (QOS) for entities, ROS only provides native support for a handful of them. ROS users are able to specify the History, Depth, Reliability, and Durability via a QoS configuration struct when they create Publishers, Subscribers, etc. +While DDS provides many settings to enable fine-grained control over the Quality of Service (QoS) for entities, ROS only provides native support for a handful of them. ROS users are able to specify the History, Depth, Reliability, and Durability via a QoS configuration struct when they create Publishers, Subscribers, etc. This leaves a lot of QoS settings that can only be set if DDS vendor can load additional default settings via a configuration file. If a user wants to hook their code into these additional QoS settings then they would need to get a reference to the rmw implementation and program against the vendor specific API. Without the abstraction layer provided by ROS their code becomes less portable. -## Proposed Changes +## New QoS Settings As users start to build more robust applications, they are going to need more control over when data is being delivered and information about when the system is failing. To address these needs it was proposed that we start by adding support for the following new DDS QoS settings. -### Proposed New QoS Settings +### Deadline + +The deadline policy establishes a contract for the amount of time allowed between messages. +For Topic Subscribers it establishes the maximum amount of time allowed to pass between receiving messages. +For Topic Publishers it establishes the maximum amount of time allowed to pass between sending messages. +For Service Owners it establishes the maximum amount of time allowed to pass between receiving a request and when a response for that request is sent. +For Service Clients it establishes the maximum amount of time allowed to pass between sending a request and when a response for that request is received. + +Topics and Services will support the following levels of deadlines. +- DEADLINE_DEFAULT - Use the ROS specified default for deadlines (which is DEADLINE_NONE). +- DEADLINE_NONE - Disables tracking of deadlines. +- DEADLINE_RMW - Tracks deadlines at the ROS rmw layer. + +In order for a Subscriber to listen to a Publisher's Topic the deadline that they request must greater than the deadline set by the Publisher. +A Service Client will **not** be prevent from making a request to a Service Owner if the Owner provides a deadline greater than the deadline requested by the Client. -- Deadline - The deadline policy establishes a contract for how often publishers will receive data and how often subscribers expect to receive data. -- Liveliness - The liveliness policy is useful for determining if entities on the network are "alive" and notifying interested parties when they are not. -- Lifespan - The lifespan policy is useful for preventing the delivery of stale messages by specifying a time at which they should no longer be delivered. +### Liveliness + +The liveliness policy establishes a contract for how entities report that they are still alive. +For Topic Subscribers it establishes the level of reporting that they require from the Topic entities that they are subscribed to. +For Topic Publishers it establishes the level of reporting that they will provide to Subscribers that they are alive. +For Service Owners it establishes both the level of reporting that they will provide to Clients and also the level of reporting that they require from Clients. +For Service Clients it establishes both the level of reporting that they require from Service Owners and the level of reporting that they will provide to the Owner. -More detailed information on these policies can be found below in Appendix A. +Topics will support the following levels of liveliness. +- LIVELINESS_DEFAULT - Use the ROS specified default for liveliness (which is LIVELINESS_AUTOMATIC). +- LIVELINESS_AUTOMATIC - The signal that establishes a Topic is alive comes from the ROS rmw layer. +- LIVELINESS_MANUAL_NODE - The signal that establishes a Topic is alive is at the node level. Publishing a message on any publisher on the node or an explicit signal from the application to assert liveliness on the node will mark all publishes on the node as being alive. +- LIVELINESS_MANUAL_TOPIC - The signal that establishes a Topic is alive is at the Topic level. Only publishing a message on the Topic or an explicit signal from the application to assert liveliness on the Topic will mark the Topic as being alive. -### DDS Vendor Support +Services will support the following levels of liveliness. +- LIVELINESS_DEFAULT - Use the ROS specified default for liveliness (which is LIVELINESS_AUTOMATIC). +- LIVELINESS_AUTOMATIC - The signal that establishes a Service Owner is alive comes from the ROS rmw layer. +- LIVELINESS_MANUAL_NODE - The signal that establishes a Service is alive is at the node level. A message on any outgoing channel on the node or an explicit signal from the application to assert liveliness on the node will mark all Services on the node as being alive. +- LIVELINESS_MANUAL_SERVICE - The signal that establishes a Service is alive is at the Service level. Only sending a response on the Service or an explicit signal from the application to assert liveliness on the Service will mark the Service as being alive. -Some of the primary DDS vendors that ROS supports already provide support for these QoS settings. -However, the default vendor, Fast-RTPS, does not yet provide full support for these new QoS settings in their library. -This does not have to be a blocker for adding support for these policy settings to ROS. -We can start adding support for them and just log warning messages when a user attempts to specify an unsupported QoS setting. -When support is eventually added for the policies in the vendor library then we can enable it in the rmw implementation. +In order for a Subscriber to listen to a Publisher's Topic the liveliness they request must be greater than the liveliness set by the Publisher. -### Native ROS Support vs Vendor Configuration +Service Owners and Clients will each specify two liveliness policies, one for the liveliness policy pertaining to the Owner and one pertaining to the Client. +In order for a Client to connect to an Owner to make a request the Client_Liveliness level requested by the Owner must be greater than the level provided by the Client and the Owner_Liveliness requested by the Client must be greater than the level provided by the Owner. + +### Lifespan -It may be argued that many DDS QoS settings could be used with ROS by simply specifying them using the vendor specific configuration mechanism, such as the xml configuration files used by RTI Connext. -This may be acceptable for some QoS policies that only impact the behavior of the underlying DDS middleware, but in the case where support for QoS policy impacts the behavior of the application code this is not good enough. +The lifespan policy establishes a contract for how long a message remains valid. +For Topic Subscribers it establishes the length of time a message is considered valid, after which time it will not be received. +For Topic Publishers it establishes the length of time a message is considered valid, after which time it will be removed from the Topic history and no longer sent to Subscribers. +For Service Owners it establishes the length of time a request is considered valid, after which time the Owner will not receive and process the request. +For Service Clients it establishes the length of time a response is considered valid, after which time the Client will not accept the response and the request will timeout. -For example, it doesn't do much good to specify deadline policy via the vendor configuration mechanism if your ROS application is never notified when a publisher violates the deadline. -In such cases the application needs to be able to respond to these events in order to log failures, notify users, or adjust system behavior. +- LIFESPAN_DEFAULT - Use the ROS specified default for lifespan (which is LIFESPAN_NONE). +- LIFESPAN_NONE - Messages do not have a time at which they expire. +- LIFESPAN_ENABLED - Messages will have a lifespan enforced. -When interaction with the application is needed it is also preferable to have a ROS defined interface as opposed to having the application program directly against the DDS vendor API. -Many nodes in ROS are written to be shared and reused by the community. -Since different end users will want to use different middleware vendors for their applications, it is important to maintain that flexibility for nodes that want to take advantage of these additional QoS policies. +If a Service Owner receives a request before the lifespan expires it should finish processing that request even if the lifespan expires while the request is being processed. -**Based on this criteria, native ROS support should be provided for Deadline and Liveliness but not for the Lifespan policy.** -While Deadline and Liveliness will both have events that the application will initiate and need to be informed of, the Lifespan policy can be entirely handled by the underlying DDS service without the need for any intervention by the application. +### DDS QoS Relation + +These new policies are all based on the DDS QoS policies, but they do not require a DDS in order for an rmw implementation to support them. +More detailed information on the DDS specifics of these policies can be found below in Appendix A. + +The only new QoS setting that does not directly map to DDS is the deadline policy for Services. +While the deadline policy could map directly to the underlying Publisher and Subscriber like they do for Topics, that would tie the QoS policy to the DDS implementation instead of the generic Service definition that does not specify it be implemented using two Topics. +The definition as it applies to messages on two underlying topics is also less useful than the definition of deadline as it pertains to life of a request. ### ROS Changes These are the various changes that would be needed within ROS in order to natively support Deadline and Liveliness. -#### Topic Status Event Handler +#### Resource Status Event Handler -Both the Deadline and Liveliness policies generate events from the DDS service layer that the application will need to be informed of. -For Deadlines, the subscriber receives event notifications if it doesn't receive anything within the deadline and the publisher receives event notifications if it doesn't publish anything within the deadline. -For Liveliness, subscribers receive events when the publisher they're listening to is no longer alive. Both of these fall under a category of "Topic Status Events". +Both the Deadline and Liveliness policies generate events from the rmw layer that the application will need to be informed of. +For Deadlines, the Subscriber receives event notifications if it doesn't receive anything within the deadline and the Publisher receives event notifications if it doesn't publish anything within the deadline. +For Liveliness, Subscribers receive events when the Publisher they're listening to is no longer alive. +Services generate similar events when Clients and Owners violate the defined policies. +Both of these fall under a category of "Resource Status Events". -To handle these notifications, a new callback function can be provided by the user that will be called any time a `TopicStatusEvent` occurs for a particular topic. -It will receive as a parameter a `TopicStatusEvent` enum value that specifies what type of event took place and a timestamp of when the event took place. +To handle these notifications, a new callback function can be provided by the user that will be called any time a `ResourceStatusEvent` occurs for a particular Topic or Service. +It will receive as a parameter a `ResourceStatusEvent` enum value that specifies what type of event took place and a timestamp of when the event took place. This callback function would be provided by the user's application when it calls the create function for publishers and subscribers. The constructors and create functions will be overloaded to make this new handler optional. @@ -89,15 +126,19 @@ The choice to use a callback function as opposed to another notification mechani #### QoS Struct -Minimal changes will need to be made to the QoS struct that is passed into the creation functions for Topics, Services, and Actions. -A couple new enum values will be added for the Deadline and Liveliness settings and then a couple integers will be added to specify the time values for these policies. +In the current version of ROS there is a single QoS struct that is used to specify the QoS policy whenever a Publisher, Subscriber, Service Owner, and Client are created. +With these new QoS settings the struct diverges for Topic participants and Service participants because Service participants will need to specify the QoS behavior for both the Client and Owner. +Separating them into using two different struct definitions for Topics versus Services will prevent unused QoS policies that would only apply to one being available in the other. + +The new QoS policy structs will have additional fields that use enums based on the values defined above to specify the desired QoS settings. +Each enum field instance in the struct will also have an associated number field added to the struct that represents a time value for the policy. #### Assert Liveliness Functions -Two new functions would need to be added that could be used by the application to explicitly assert liveliness. -One function to assert liveliness at the Node level and one to assert it at the Topic level. -While liveliness will also be implicitly assumed just based on sending messages, it will also be able to be explicitly declared by the application. -These functions will need to be implemented in the rmw layer, the rcl layer, and the language specific client libraries. +New functions will need to be added that can be used by the application to explicitly assert liveliness. +One function to assert liveliness at the Node level, one to assert it at the Topic level, and one to assert it at the Service level. +While liveliness will also be implicitly assumed just based on sending messages, these functions will be used by the application to explicitly declare resources are alive. +These functions will need to be implemented in every layer from the rmw up through the rcl and language specific client libraries, such as rclcpp. #### rcl_wait and rmw_wait @@ -105,22 +146,34 @@ The rcl layer is currently using a WaitSet in order to be informed of events fro These WaitSets contain lists of several types of conditions, such as timers firing or subscriptions receiving data. In order to support new Topic Status Events, a new type will be added to the existing WaitSet and the rmw layer will set them when these events occur. +#### rmw_take_status -## FAQ +A new function called rmw_take_status will need to be added that can directly query the status for a Topic/Service. +It will operate in a similar manner to the rmw_take function that is used to retrieve messages for a subscription. +It will be used by the executors when they receive a notice via the waitset mentioned above that a resource has a new status event available. -- How does the Deadline policy take into account the additional overhead of ROS (such as deserialization) when determining if a deadline was missed? - - As a simplification it is not going to attempt to take into account any ROS overhead. A deadline will be considered missed if the rmw layer does not receive a message by the deadline and not if the user application on top of ROS does not receive it by the deadline. +## RMW Vendor Support +All of these new QoS policies will need to be supported in the rmw implementations. +As we add new QoS policies it is likely that not all rmw vendors will provide support for every QoS policy that ROS defines. +This is especially true for non-DDS based implementations that do not already have native support for these features. +Because of this we need a way for the application to know if the rmw vendor that is being used supports the specified policies at the specified levels. -## Open Questions +In the case where an rmw vendor does not support a requested QoS they can do one of two things. +They could fail with an exception that notes that an unsupported QoS policy was requested or they can choose to continue operating with a reduced QoS policy. +In the case where a vendor chooses to continue operating with a reduced policy it must trigger a status event for the resource that can be handled by the new callback outlined above. +This provides an application a way of being notified that even though their resource is operating, it is doing so with a reduced QoS. -- How do Deadlines and Liveliness impact Services and Actions? - - Actions and Services are slightly different in that they are composed of multiple Topics. It may make sense for a Service to specify a Liveliness policy on its own DataWriter, but it likely doesn't need the same policy on the DataReader. - - One option would be to only apply the QoS settings to one or another of the topics. So Liveliness may only apply to the DataWriters in Services and Actions and the Deadlines might apply only to the "update" topic data writer for Actions. - - Another option would be to modify the interface to allow for different QoS policies for the different underlying Topics, though this adds more complexity. -- How do these new QoS settings impact non-DDS based rmw implementations? - - While these QoS policies are native to the DDS standard, any non-DDS based rmw layer will not have native support for these policies. What does this mean for those implementations? Will they be forced to implement these features in their rmw_implementation layer to be officially supported? +## FAQ +- How does the Deadline policy take into account the additional overhead of ROS (such as deserialization) when determining if a deadline was missed? + - As a simplification it is not going to attempt to take into account any ROS overhead. A deadline will be considered missed if the rmw layer does not receive a message by the deadline and not if the user application on top of ROS does not receive it by the deadline. A new deadline policy could be added later that takes this into account. +- What happens if multiple policy violations occur between the invocation of the callback? + - This is dependent on the rmw implementation. If the rmw layer supports tracking multiple status events then it can return them in subsequent calls to rmw_take_status. If it does not support tracking multiple events at once then it may just return one of the events, such as the first or the last to occur in the sequence. +- How do these QoS policies impact Actions? + - The existing Actions interface exposes that Actions are implemented with multiple Topics and it exposes the QoS settings for those topics. It is therefore up to the application implementing the action to specify the QoS policies for the different Topics. A new interface will need to be added to allow Actions to specify a ResourceStatusHandler, but that will be added in a later design review. +- Why do Services not enforce deadline policies on connection like Publishers and Subscribers? + - This is a simplification being made for initial implementation. It could be changed later to enforce it, but that would require additional complexity in the existing DDS based implementations of the rmw to disallow connections based on non-DDS QoS settings. ## Appendix A From 26c08be8095753c1fc0d0f4a5c61e0aa8772e33b Mon Sep 17 00:00:00 2001 From: burekn Date: Mon, 18 Feb 2019 14:37:09 -0800 Subject: [PATCH 04/12] Adds rcl_take_status function to the ROS changes. --- articles/qos_deadline_liveliness_lifespan.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/articles/qos_deadline_liveliness_lifespan.md b/articles/qos_deadline_liveliness_lifespan.md index 166575706..be00f6226 100644 --- a/articles/qos_deadline_liveliness_lifespan.md +++ b/articles/qos_deadline_liveliness_lifespan.md @@ -146,10 +146,10 @@ The rcl layer is currently using a WaitSet in order to be informed of events fro These WaitSets contain lists of several types of conditions, such as timers firing or subscriptions receiving data. In order to support new Topic Status Events, a new type will be added to the existing WaitSet and the rmw layer will set them when these events occur. -#### rmw_take_status +#### rcl_take_status and rmw_take_status -A new function called rmw_take_status will need to be added that can directly query the status for a Topic/Service. -It will operate in a similar manner to the rmw_take function that is used to retrieve messages for a subscription. +New functions called rcl_take_status and rmw_take_status will need to be added that can directly query the status for a Topic/Service. +It will operate in a similar manner to the rcl_take and rmw_take functions that are used to retrieve messages for a subscription. It will be used by the executors when they receive a notice via the waitset mentioned above that a resource has a new status event available. ## RMW Vendor Support From 2715a7b9cf6a91a00706008ce1c9641a109de621 Mon Sep 17 00:00:00 2001 From: burekn Date: Wed, 20 Feb 2019 16:30:01 -0800 Subject: [PATCH 05/12] Adds additional clarifying information to QoS design document. --- articles/qos_deadline_liveliness_lifespan.md | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/articles/qos_deadline_liveliness_lifespan.md b/articles/qos_deadline_liveliness_lifespan.md index be00f6226..d3a4d3fff 100644 --- a/articles/qos_deadline_liveliness_lifespan.md +++ b/articles/qos_deadline_liveliness_lifespan.md @@ -51,11 +51,11 @@ For Service Clients it establishes the maximum amount of time allowed to pass be Topics and Services will support the following levels of deadlines. - DEADLINE_DEFAULT - Use the ROS specified default for deadlines (which is DEADLINE_NONE). -- DEADLINE_NONE - Disables tracking of deadlines. -- DEADLINE_RMW - Tracks deadlines at the ROS rmw layer. +- DEADLINE_NONE - No deadline will be offered or requested and events will not be generated for missed deadlines. +- DEADLINE_RMW - The rmw layer of ROS will track the deadline. For a Publisher or Subscriber this means that a deadline will be considered missed if the rmw layer has not received a message within the specified time. For a Service this means the time a request is started is marked when the request reaches the rmw layer and the time at which it is finished is when the response message reaches the rmw layer. In order for a Subscriber to listen to a Publisher's Topic the deadline that they request must greater than the deadline set by the Publisher. -A Service Client will **not** be prevent from making a request to a Service Owner if the Owner provides a deadline greater than the deadline requested by the Client. +A Service Client will **not** be prevented from making a request to a Service Owner if the Owner provides a deadline greater than the deadline requested by the Client. ### Liveliness @@ -68,16 +68,16 @@ For Service Clients it establishes both the level of reporting that they require Topics will support the following levels of liveliness. - LIVELINESS_DEFAULT - Use the ROS specified default for liveliness (which is LIVELINESS_AUTOMATIC). - LIVELINESS_AUTOMATIC - The signal that establishes a Topic is alive comes from the ROS rmw layer. -- LIVELINESS_MANUAL_NODE - The signal that establishes a Topic is alive is at the node level. Publishing a message on any publisher on the node or an explicit signal from the application to assert liveliness on the node will mark all publishes on the node as being alive. +- LIVELINESS_MANUAL_NODE - The signal that establishes a Topic is alive is at the node level. Publishing a message on any outgoing channel on the node or an explicit signal from the application to assert liveliness on the node will mark all outgoing channels on the node as being alive. - LIVELINESS_MANUAL_TOPIC - The signal that establishes a Topic is alive is at the Topic level. Only publishing a message on the Topic or an explicit signal from the application to assert liveliness on the Topic will mark the Topic as being alive. Services will support the following levels of liveliness. - LIVELINESS_DEFAULT - Use the ROS specified default for liveliness (which is LIVELINESS_AUTOMATIC). - LIVELINESS_AUTOMATIC - The signal that establishes a Service Owner is alive comes from the ROS rmw layer. -- LIVELINESS_MANUAL_NODE - The signal that establishes a Service is alive is at the node level. A message on any outgoing channel on the node or an explicit signal from the application to assert liveliness on the node will mark all Services on the node as being alive. +- LIVELINESS_MANUAL_NODE - The signal that establishes a Service is alive is at the node level. A message on any outgoing channel on the node or an explicit signal from the application to assert liveliness on the node will mark all outgoing channels on the node as being alive. - LIVELINESS_MANUAL_SERVICE - The signal that establishes a Service is alive is at the Service level. Only sending a response on the Service or an explicit signal from the application to assert liveliness on the Service will mark the Service as being alive. -In order for a Subscriber to listen to a Publisher's Topic the liveliness they request must be greater than the liveliness set by the Publisher. +In order for a Subscriber to listen to a Publisher's Topic the level of liveliness tracking they request must be equal or less verbose than the level of tracking provided by the Publisher and the time until considered not alive set by the Subscriber must be greater than the time set by the Publisher. Service Owners and Clients will each specify two liveliness policies, one for the liveliness policy pertaining to the Owner and one pertaining to the Client. In order for a Client to connect to an Owner to make a request the Client_Liveliness level requested by the Owner must be greater than the level provided by the Client and the Owner_Liveliness requested by the Client must be greater than the level provided by the Owner. From de871b0adefe5416db1b0353bba53e83cc55d67b Mon Sep 17 00:00:00 2001 From: burekn Date: Wed, 20 Feb 2019 17:06:27 -0800 Subject: [PATCH 06/12] Removes lifespan support for Services from the QoS design. --- articles/qos_deadline_liveliness_lifespan.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/articles/qos_deadline_liveliness_lifespan.md b/articles/qos_deadline_liveliness_lifespan.md index d3a4d3fff..266334910 100644 --- a/articles/qos_deadline_liveliness_lifespan.md +++ b/articles/qos_deadline_liveliness_lifespan.md @@ -85,16 +85,16 @@ In order for a Client to connect to an Owner to make a request the Client_Liveli ### Lifespan The lifespan policy establishes a contract for how long a message remains valid. +The lifespan QoS policy only applies to Topics. For Topic Subscribers it establishes the length of time a message is considered valid, after which time it will not be received. For Topic Publishers it establishes the length of time a message is considered valid, after which time it will be removed from the Topic history and no longer sent to Subscribers. -For Service Owners it establishes the length of time a request is considered valid, after which time the Owner will not receive and process the request. -For Service Clients it establishes the length of time a response is considered valid, after which time the Client will not accept the response and the request will timeout. - LIFESPAN_DEFAULT - Use the ROS specified default for lifespan (which is LIFESPAN_NONE). - LIFESPAN_NONE - Messages do not have a time at which they expire. - LIFESPAN_ENABLED - Messages will have a lifespan enforced. -If a Service Owner receives a request before the lifespan expires it should finish processing that request even if the lifespan expires while the request is being processed. +In the future lifespan support could be added for Services to act as a means of timing out requests if they take over a set amount of time. +At present, that would require additional support for Service Clients to be able to handle timeouts and cleanup requests that is out of scope for this design. ### DDS QoS Relation From 50ebf99a180e8f221ea983faab81fd106707313f Mon Sep 17 00:00:00 2001 From: burekn Date: Fri, 1 Mar 2019 10:31:45 -0800 Subject: [PATCH 07/12] Grammar and terminology corrections. --- articles/qos_deadline_liveliness_lifespan.md | 98 +++++++++----------- 1 file changed, 46 insertions(+), 52 deletions(-) diff --git a/articles/qos_deadline_liveliness_lifespan.md b/articles/qos_deadline_liveliness_lifespan.md index 266334910..8512e9b6f 100644 --- a/articles/qos_deadline_liveliness_lifespan.md +++ b/articles/qos_deadline_liveliness_lifespan.md @@ -25,12 +25,13 @@ Glossary: - DDS - Data Distribution Service - RTPS - Real-Time Publish Subscribe - QoS - Quality of Service -- Client - Refers to an application that connects to a ROS Service to send requests and receive responses. -- Owner - Refers to the application that is running a ROS Service that receives requests and sends responses. +- Service Client - Also referred to as just Client, refers to an application that connects to a ROS Service to send requests and receive responses. +- Service Server - Also referred to as just Server, refers to the application that is running a ROS Service that receives requests and sends responses. ## Existing ROS QoS Settings -While DDS provides many settings to enable fine-grained control over the Quality of Service (QoS) for entities, ROS only provides native support for a handful of them. ROS users are able to specify the History, Depth, Reliability, and Durability via a QoS configuration struct when they create Publishers, Subscribers, etc. +While DDS provides many settings to enable fine-grained control over the Quality of Service (QoS) for entities, ROS only provides native support for a handful of them. +ROS users are able to specify the History, Depth, Reliability, and Durability via a QoS configuration struct when they create Publishers, Subscribers, etc. This leaves a lot of QoS settings that can only be set if DDS vendor can load additional default settings via a configuration file. If a user wants to hook their code into these additional QoS settings then they would need to get a reference to the rmw implementation and program against the vendor specific API. @@ -44,50 +45,50 @@ To address these needs it was proposed that we start by adding support for the f ### Deadline The deadline policy establishes a contract for the amount of time allowed between messages. -For Topic Subscribers it establishes the maximum amount of time allowed to pass between receiving messages. -For Topic Publishers it establishes the maximum amount of time allowed to pass between sending messages. -For Service Owners it establishes the maximum amount of time allowed to pass between receiving a request and when a response for that request is sent. +For Subscriptions it establishes the maximum amount of time allowed to pass between receiving messages. +For Publishers it establishes the maximum amount of time allowed to pass between sending messages. +For Service Servers it establishes the maximum amount of time allowed to pass between receiving a request and when a response for that request is sent. For Service Clients it establishes the maximum amount of time allowed to pass between sending a request and when a response for that request is received. -Topics and Services will support the following levels of deadlines. +Topics and Services will support the following levels of deadlines: - DEADLINE_DEFAULT - Use the ROS specified default for deadlines (which is DEADLINE_NONE). - DEADLINE_NONE - No deadline will be offered or requested and events will not be generated for missed deadlines. - DEADLINE_RMW - The rmw layer of ROS will track the deadline. For a Publisher or Subscriber this means that a deadline will be considered missed if the rmw layer has not received a message within the specified time. For a Service this means the time a request is started is marked when the request reaches the rmw layer and the time at which it is finished is when the response message reaches the rmw layer. -In order for a Subscriber to listen to a Publisher's Topic the deadline that they request must greater than the deadline set by the Publisher. -A Service Client will **not** be prevented from making a request to a Service Owner if the Owner provides a deadline greater than the deadline requested by the Client. +In order for a Subscriber to listen to a Publisher's Topic the deadline that they request must be greater than, or equal to, the deadline set by the Publisher. +A Service Client will **not** be prevented from making a request to a Service Server if the Server provides a deadline greater than the deadline requested by the Client. ### Liveliness The liveliness policy establishes a contract for how entities report that they are still alive. -For Topic Subscribers it establishes the level of reporting that they require from the Topic entities that they are subscribed to. -For Topic Publishers it establishes the level of reporting that they will provide to Subscribers that they are alive. -For Service Owners it establishes both the level of reporting that they will provide to Clients and also the level of reporting that they require from Clients. -For Service Clients it establishes both the level of reporting that they require from Service Owners and the level of reporting that they will provide to the Owner. +For Subscriptions it establishes the level of reporting that they require from the Publishers to which they are subscribed. +For Publishers it establishes the level of reporting that they will provide to Subscribers that they are alive. +For Service Servers it establishes both the level of reporting that they will provide to Clients and also the level of reporting that they require from Clients. +For Service Clients it establishes both the level of reporting that they require from Service Servers and the level of reporting that they will provide to the Server. -Topics will support the following levels of liveliness. +Topics will support the following levels of liveliness: - LIVELINESS_DEFAULT - Use the ROS specified default for liveliness (which is LIVELINESS_AUTOMATIC). - LIVELINESS_AUTOMATIC - The signal that establishes a Topic is alive comes from the ROS rmw layer. - LIVELINESS_MANUAL_NODE - The signal that establishes a Topic is alive is at the node level. Publishing a message on any outgoing channel on the node or an explicit signal from the application to assert liveliness on the node will mark all outgoing channels on the node as being alive. - LIVELINESS_MANUAL_TOPIC - The signal that establishes a Topic is alive is at the Topic level. Only publishing a message on the Topic or an explicit signal from the application to assert liveliness on the Topic will mark the Topic as being alive. -Services will support the following levels of liveliness. +Services will support the following levels of liveliness: - LIVELINESS_DEFAULT - Use the ROS specified default for liveliness (which is LIVELINESS_AUTOMATIC). -- LIVELINESS_AUTOMATIC - The signal that establishes a Service Owner is alive comes from the ROS rmw layer. +- LIVELINESS_AUTOMATIC - The signal that establishes a Service Server is alive comes from the ROS rmw layer. - LIVELINESS_MANUAL_NODE - The signal that establishes a Service is alive is at the node level. A message on any outgoing channel on the node or an explicit signal from the application to assert liveliness on the node will mark all outgoing channels on the node as being alive. - LIVELINESS_MANUAL_SERVICE - The signal that establishes a Service is alive is at the Service level. Only sending a response on the Service or an explicit signal from the application to assert liveliness on the Service will mark the Service as being alive. In order for a Subscriber to listen to a Publisher's Topic the level of liveliness tracking they request must be equal or less verbose than the level of tracking provided by the Publisher and the time until considered not alive set by the Subscriber must be greater than the time set by the Publisher. -Service Owners and Clients will each specify two liveliness policies, one for the liveliness policy pertaining to the Owner and one pertaining to the Client. -In order for a Client to connect to an Owner to make a request the Client_Liveliness level requested by the Owner must be greater than the level provided by the Client and the Owner_Liveliness requested by the Client must be greater than the level provided by the Owner. +Service Servers and Clients will each specify two liveliness policies, one for the liveliness policy pertaining to the Server and one pertaining to the Client. +In order for a Client to connect to a Server to make a request the Client_Liveliness level requested by the Server must be greater than the level provided by the Client and the Server_Liveliness requested by the Client must be greater than the level provided by the Server. ### Lifespan The lifespan policy establishes a contract for how long a message remains valid. The lifespan QoS policy only applies to Topics. -For Topic Subscribers it establishes the length of time a message is considered valid, after which time it will not be received. -For Topic Publishers it establishes the length of time a message is considered valid, after which time it will be removed from the Topic history and no longer sent to Subscribers. +For Subscriptions it establishes the length of time a message is considered valid, after which time it will not be received. +For Publishers it establishes the length of time a message is considered valid, after which time it will be removed from the Topic history and no longer sent to Subscribers. - LIFESPAN_DEFAULT - Use the ROS specified default for lifespan (which is LIFESPAN_NONE). - LIFESPAN_NONE - Messages do not have a time at which they expire. @@ -111,10 +112,10 @@ These are the various changes that would be needed within ROS in order to native #### Resource Status Event Handler -Both the Deadline and Liveliness policies generate events from the rmw layer that the application will need to be informed of. +Both the Deadline and Liveliness policies generate events from the rmw layer of which the application will need to be informed. For Deadlines, the Subscriber receives event notifications if it doesn't receive anything within the deadline and the Publisher receives event notifications if it doesn't publish anything within the deadline. For Liveliness, Subscribers receive events when the Publisher they're listening to is no longer alive. -Services generate similar events when Clients and Owners violate the defined policies. +Services generate similar events when Clients and Servers violate the defined policies. Both of these fall under a category of "Resource Status Events". To handle these notifications, a new callback function can be provided by the user that will be called any time a `ResourceStatusEvent` occurs for a particular Topic or Service. @@ -126,8 +127,8 @@ The choice to use a callback function as opposed to another notification mechani #### QoS Struct -In the current version of ROS there is a single QoS struct that is used to specify the QoS policy whenever a Publisher, Subscriber, Service Owner, and Client are created. -With these new QoS settings the struct diverges for Topic participants and Service participants because Service participants will need to specify the QoS behavior for both the Client and Owner. +In the current version of ROS there is a single QoS struct that is used to specify the QoS policy whenever a Publisher, Subscriber, Service Server, and Client are created. +With these new QoS settings the struct diverges for Topic participants and Service participants because Service participants will need to specify the QoS behavior for both the Client and Server. Separating them into using two different struct definitions for Topics versus Services will prevent unused QoS policies that would only apply to one being available in the other. The new QoS policy structs will have additional fields that use enums based on the values defined above to specify the desired QoS settings. @@ -177,19 +178,19 @@ This provides an application a way of being notified that even though their reso ## Appendix A -Definitions of the QoS policies from the DDS spec. +Definitions of the QoS policies from the DDS spec. ### Deadline -This policy is useful for cases where a Topic is expected to have each instance updated periodically. On the publishing side this -setting establishes a contract that the application must meet. On the subscribing side the setting establishes a minimum -requirement for the remote publishers that are expected to supply the data values. +This policy is useful for cases where a Topic is expected to have each instance updated periodically. +On the publishing side this setting establishes a contract that the application must meet. +On the subscribing side the setting establishes a minimum requirement for the remote publishers that are expected to supply the data values. -When the Service ‘matches’ a DataWriter and a DataReader it checks whether the settings are compatible (i.e., offered +When the DDS Service ‘matches’ a DataWriter and a DataReader it checks whether the settings are compatible (i.e., offered deadline period<= requested deadline period) if they are not, the two entities are informed (via the listener or condition mechanism) of the incompatibility of the QoS settings and communication will not occur. -Assuming that the reader and writer ends have compatible settings, the fulfillment of this contract is monitored by the Service +Assuming that the 'DataReader' and 'DataWriter' ends have compatible settings, the fulfillment of this contract is monitored by the DDS Service and the application is informed of any violations by means of the proper listener or condition. The value offered is considered compatible with the value requested if and only if the inequality “offered deadline period <= @@ -200,23 +201,20 @@ to be consistent the settings must be such that “deadline period>= minimum_sep ### Liveliness -This policy controls the mechanism and parameters used by the Service to ensure that particular entities on the network are -still “alive.” The liveliness can also affect the ownership of a particular instance, as determined by the OWNERSHIP QoS -policy. +This policy controls the mechanism and parameters used by the DDS Service to ensure that particular entities on the network are still “alive.” +The liveliness can also affect the ownership of a particular instance, as determined by the OWNERSHIP QoS policy. -This policy has several settings to support both data-objects that are updated periodically as well as those that are changed -sporadically. It also allows customizing for different application requirements in terms of the kinds of failures that will be -detected by the liveliness mechanism. +This policy has several settings to support both data-objects that are updated periodically as well as those that are changed sporadically. +It also allows customizing for different application requirements in terms of the kinds of failures that will be detected by the liveliness mechanism. The AUTOMATIC liveliness setting is most appropriate for applications that only need to detect failures at the process- -level 27 , but not application-logic failures within a process. The Service takes responsibility for renewing the leases at the -required rates and thus, as long as the local process where a DomainParticipant is running and the link connecting it to remote -participants remains connected, the entities within the DomainParticipant will be considered alive. This requires the lowest -overhead. +level 27 , but not application-logic failures within a process. +The DDS Service takes responsibility for renewing the leases at the required rates and thus, as long as the local process where a DomainParticipant is running and the link connecting it to remote participants remains connected, the entities within the DomainParticipant will be considered alive. +This requires the lowest overhead. The MANUAL settings (MANUAL_BY_PARTICIPANT, MANUAL_BY_TOPIC), require the application on the publishing -side to periodically assert the liveliness before the lease expires to indicate the corresponding Entity is still alive. The action -can be explicit by calling the assert_liveliness operations, or implicit by writing some data. +side to periodically assert the liveliness before the lease expires to indicate the corresponding Entity is still alive. +The action can be explicit by calling the assert_liveliness operations, or implicit by writing some data. The two possible manual settings control the granularity at which the application must assert liveliness. • The setting MANUAL_BY_PARTICIPANT requires only that one Entity within the publisher is asserted to be alive to @@ -227,15 +225,11 @@ deduce all other Entity objects within the same DomainParticipant are also alive The purpose of this QoS is to avoid delivering “stale” data to the application. -Each data sample written by the DataWriter has an associated ‘expiration time’ beyond which the data should not be delivered -to any application. Once the sample expires, the data will be removed from the DataReader caches as well as from the -transient and persistent information caches. +Each data sample written by the DataWriter has an associated ‘expiration time’ beyond which the data should not be delivered to any application. +Once the sample expires, the data will be removed from the DataReader caches as well as from the transient and persistent information caches. -The ‘expiration time’ of each sample is computed by adding the duration specified by the LIFESPAN QoS to the source -timestamp. The source timestamp is either automatically computed by the Service -each time the DataWriter write operation is called, or else supplied by the application by means of the write_w_timestamp -operation. +The ‘expiration time’ of each sample is computed by adding the duration specified by the LIFESPAN QoS to the source timestamp. +The source timestamp is either automatically computed by the DDS Service each time the DataWriter write operation is called, or else supplied by the application by means of the write_w_timestamp operation. -This QoS relies on the sender and receiving applications having their clocks sufficiently synchronized. If this is not the case -and the Service can detect it, the DataReader is allowed to use the reception timestamp instead of the source timestamp in its -computation of the ‘expiration time. \ No newline at end of file +This QoS relies on the sender and receiving applications having their clocks sufficiently synchronized. +If this is not the case and the DDS Service can detect it, the DataReader is allowed to use the reception timestamp instead of the source timestamp in its computation of the ‘expiration time. \ No newline at end of file From 3f9aad6a321305f89f200321ff781a0251de44ce Mon Sep 17 00:00:00 2001 From: burekn Date: Wed, 20 Mar 2019 15:03:31 -0700 Subject: [PATCH 08/12] Modifications based on second virtual meeting. --- articles/qos_deadline_liveliness_lifespan.md | 102 +++++++++++-------- 1 file changed, 59 insertions(+), 43 deletions(-) diff --git a/articles/qos_deadline_liveliness_lifespan.md b/articles/qos_deadline_liveliness_lifespan.md index 8512e9b6f..c8d8cd4e0 100644 --- a/articles/qos_deadline_liveliness_lifespan.md +++ b/articles/qos_deadline_liveliness_lifespan.md @@ -47,24 +47,19 @@ To address these needs it was proposed that we start by adding support for the f The deadline policy establishes a contract for the amount of time allowed between messages. For Subscriptions it establishes the maximum amount of time allowed to pass between receiving messages. For Publishers it establishes the maximum amount of time allowed to pass between sending messages. -For Service Servers it establishes the maximum amount of time allowed to pass between receiving a request and when a response for that request is sent. -For Service Clients it establishes the maximum amount of time allowed to pass between sending a request and when a response for that request is received. -Topics and Services will support the following levels of deadlines: +Topics will support the following levels of deadlines: - DEADLINE_DEFAULT - Use the ROS specified default for deadlines (which is DEADLINE_NONE). - DEADLINE_NONE - No deadline will be offered or requested and events will not be generated for missed deadlines. - DEADLINE_RMW - The rmw layer of ROS will track the deadline. For a Publisher or Subscriber this means that a deadline will be considered missed if the rmw layer has not received a message within the specified time. For a Service this means the time a request is started is marked when the request reaches the rmw layer and the time at which it is finished is when the response message reaches the rmw layer. In order for a Subscriber to listen to a Publisher's Topic the deadline that they request must be greater than, or equal to, the deadline set by the Publisher. -A Service Client will **not** be prevented from making a request to a Service Server if the Server provides a deadline greater than the deadline requested by the Client. ### Liveliness The liveliness policy establishes a contract for how entities report that they are still alive. For Subscriptions it establishes the level of reporting that they require from the Publishers to which they are subscribed. For Publishers it establishes the level of reporting that they will provide to Subscribers that they are alive. -For Service Servers it establishes both the level of reporting that they will provide to Clients and also the level of reporting that they require from Clients. -For Service Clients it establishes both the level of reporting that they require from Service Servers and the level of reporting that they will provide to the Server. Topics will support the following levels of liveliness: - LIVELINESS_DEFAULT - Use the ROS specified default for liveliness (which is LIVELINESS_AUTOMATIC). @@ -72,17 +67,8 @@ Topics will support the following levels of liveliness: - LIVELINESS_MANUAL_NODE - The signal that establishes a Topic is alive is at the node level. Publishing a message on any outgoing channel on the node or an explicit signal from the application to assert liveliness on the node will mark all outgoing channels on the node as being alive. - LIVELINESS_MANUAL_TOPIC - The signal that establishes a Topic is alive is at the Topic level. Only publishing a message on the Topic or an explicit signal from the application to assert liveliness on the Topic will mark the Topic as being alive. -Services will support the following levels of liveliness: -- LIVELINESS_DEFAULT - Use the ROS specified default for liveliness (which is LIVELINESS_AUTOMATIC). -- LIVELINESS_AUTOMATIC - The signal that establishes a Service Server is alive comes from the ROS rmw layer. -- LIVELINESS_MANUAL_NODE - The signal that establishes a Service is alive is at the node level. A message on any outgoing channel on the node or an explicit signal from the application to assert liveliness on the node will mark all outgoing channels on the node as being alive. -- LIVELINESS_MANUAL_SERVICE - The signal that establishes a Service is alive is at the Service level. Only sending a response on the Service or an explicit signal from the application to assert liveliness on the Service will mark the Service as being alive. - In order for a Subscriber to listen to a Publisher's Topic the level of liveliness tracking they request must be equal or less verbose than the level of tracking provided by the Publisher and the time until considered not alive set by the Subscriber must be greater than the time set by the Publisher. -Service Servers and Clients will each specify two liveliness policies, one for the liveliness policy pertaining to the Server and one pertaining to the Client. -In order for a Client to connect to a Server to make a request the Client_Liveliness level requested by the Server must be greater than the level provided by the Client and the Server_Liveliness requested by the Client must be greater than the level provided by the Server. - ### Lifespan The lifespan policy establishes a contract for how long a message remains valid. @@ -94,18 +80,11 @@ For Publishers it establishes the length of time a message is considered valid, - LIFESPAN_NONE - Messages do not have a time at which they expire. - LIFESPAN_ENABLED - Messages will have a lifespan enforced. -In the future lifespan support could be added for Services to act as a means of timing out requests if they take over a set amount of time. -At present, that would require additional support for Service Clients to be able to handle timeouts and cleanup requests that is out of scope for this design. - ### DDS QoS Relation These new policies are all based on the DDS QoS policies, but they do not require a DDS in order for an rmw implementation to support them. More detailed information on the DDS specifics of these policies can be found below in Appendix A. -The only new QoS setting that does not directly map to DDS is the deadline policy for Services. -While the deadline policy could map directly to the underlying Publisher and Subscriber like they do for Topics, that would tie the QoS policy to the DDS implementation instead of the generic Service definition that does not specify it be implemented using two Topics. -The definition as it applies to messages on two underlying topics is also less useful than the definition of deadline as it pertains to life of a request. - ### ROS Changes These are the various changes that would be needed within ROS in order to natively support Deadline and Liveliness. @@ -118,26 +97,27 @@ For Liveliness, Subscribers receive events when the Publisher they're listening Services generate similar events when Clients and Servers violate the defined policies. Both of these fall under a category of "Resource Status Events". -To handle these notifications, a new callback function can be provided by the user that will be called any time a `ResourceStatusEvent` occurs for a particular Topic or Service. -It will receive as a parameter a `ResourceStatusEvent` enum value that specifies what type of event took place and a timestamp of when the event took place. -This callback function would be provided by the user's application when it calls the create function for publishers and subscribers. +To handle these notifications, new callback functions can be provided by the user that will be called any time an event occurs for a particular Topic. +It will receive as a parameter a struct value that contains the information about the event such as when the event took place and other metadata related to the event. +These callback functions would be optionally provided by the user's application when it calls the create function for publishers and subscribers. The constructors and create functions will be overloaded to make this new handler optional. -The choice to use a callback function as opposed to another notification mechanism is to remain consistent with the existing ROS interface and not add a new method of waiting on ROS data/events. +The status event handlers will not be called once for every status event. +Instead, the event handlers will only be called if there is an status change event that has not yet been handled when the Executor that services the callbacks checks. #### QoS Struct -In the current version of ROS there is a single QoS struct that is used to specify the QoS policy whenever a Publisher, Subscriber, Service Server, and Client are created. -With these new QoS settings the struct diverges for Topic participants and Service participants because Service participants will need to specify the QoS behavior for both the Client and Server. -Separating them into using two different struct definitions for Topics versus Services will prevent unused QoS policies that would only apply to one being available in the other. +In the current version of ROS there is a single QoS struct that is used to specify the QoS policy whenever a Publisher and Subscriber are created. +With these new QoS settings the supported set of QoS policies for Topics and Services diverges. +Despite this, we are going to stick with a single struct for both Topics and Services instead of switching to two different struct types in order to keep the changes to a minimum and maintain as much backwards compatibility as possible in the client library interfaces. -The new QoS policy structs will have additional fields that use enums based on the values defined above to specify the desired QoS settings. +The existing QoS policy struct will have new fields added that use enums based on the values defined above to specify the desired QoS settings for Deadline, Liveliness, and Lifespan. Each enum field instance in the struct will also have an associated number field added to the struct that represents a time value for the policy. #### Assert Liveliness Functions New functions will need to be added that can be used by the application to explicitly assert liveliness. -One function to assert liveliness at the Node level, one to assert it at the Topic level, and one to assert it at the Service level. +One function to assert liveliness at the Node level and one to assert it at the Topic level. While liveliness will also be implicitly assumed just based on sending messages, these functions will be used by the application to explicitly declare resources are alive. These functions will need to be implemented in every layer from the rmw up through the rcl and language specific client libraries, such as rclcpp. @@ -149,32 +129,68 @@ In order to support new Topic Status Events, a new type will be added to the exi #### rcl_take_status and rmw_take_status -New functions called rcl_take_status and rmw_take_status will need to be added that can directly query the status for a Topic/Service. +New functions called rcl_take_status and rmw_take_status will need to be added that can directly query the status for a Topic. It will operate in a similar manner to the rcl_take and rmw_take functions that are used to retrieve messages for a subscription. It will be used by the executors when they receive a notice via the waitset mentioned above that a resource has a new status event available. ## RMW Vendor Support - All of these new QoS policies will need to be supported in the rmw implementations. As we add new QoS policies it is likely that not all rmw vendors will provide support for every QoS policy that ROS defines. This is especially true for non-DDS based implementations that do not already have native support for these features. Because of this we need a way for the application to know if the rmw vendor that is being used supports the specified policies at the specified levels. +In this case, the rmw vendor should fail the operation by returning an error code that specifies that the requested QoS policy is not supported. +The explicit failure will ensure the requesting application is receiving defined behavior and not operating under unexpected conditions. -In the case where an rmw vendor does not support a requested QoS they can do one of two things. -They could fail with an exception that notes that an unsupported QoS policy was requested or they can choose to continue operating with a reduced QoS policy. -In the case where a vendor chooses to continue operating with a reduced policy it must trigger a status event for the resource that can be handled by the new callback outlined above. -This provides an application a way of being notified that even though their resource is operating, it is doing so with a reduced QoS. +In addition to an application being prevented from running with an unsupported policy, it is useful for an application to be able to query what QoS policies the rmw vendor supports. +The best way to do this is to provide an API that allows the application to check if a specific policy is supported and also get all the supported settings. +The design and implementation of this API is out of scope for this document and should be considered for part of the future work. ## FAQ - How does the Deadline policy take into account the additional overhead of ROS (such as deserialization) when determining if a deadline was missed? - As a simplification it is not going to attempt to take into account any ROS overhead. A deadline will be considered missed if the rmw layer does not receive a message by the deadline and not if the user application on top of ROS does not receive it by the deadline. A new deadline policy could be added later that takes this into account. -- What happens if multiple policy violations occur between the invocation of the callback? - - This is dependent on the rmw implementation. If the rmw layer supports tracking multiple status events then it can return them in subsequent calls to rmw_take_status. If it does not support tracking multiple events at once then it may just return one of the events, such as the first or the last to occur in the sequence. -- How do these QoS policies impact Actions? - - The existing Actions interface exposes that Actions are implemented with multiple Topics and it exposes the QoS settings for those topics. It is therefore up to the application implementing the action to specify the QoS policies for the different Topics. A new interface will need to be added to allow Actions to specify a ResourceStatusHandler, but that will be added in a later design review. -- Why do Services not enforce deadline policies on connection like Publishers and Subscribers? - - This is a simplification being made for initial implementation. It could be changed later to enforce it, but that would require additional complexity in the existing DDS based implementations of the rmw to disallow connections based on non-DDS QoS settings. +- Why will the callback not get called for every status change event instead of potentially combining events of the same type? + - Adding this functionality would require an additional buffer that would be used to store multiple events between servicing them. Additionally, the DDS API lends itself better to only being informed of the latest change and would require a realtime response to status change events so as to not miss a single event. This is not a one way door and we could change this later to allow buffering events without breaking backwards compatibility. +- How do these QoS policies impact Actions and Services? + - The initial implementation does not support Actions and Services as there are more complex subtleties to how these concepts natively support these QoS features. In the future work section below we explore some ways that Services could implement these policies. + +## Future Work + +Actions and Services were considered out of scope for the initial implementation. Here we detail how Services could potentially support these QoS policies in the future. + +### Deadline + +For Service Servers it establishes the maximum amount of time allowed to pass between receiving a request and when a response for that request is sent. +For Service Clients it establishes the maximum amount of time allowed to pass between sending a request and when a response for that request is received. + +Services will support the following levels of deadlines: +- DEADLINE_DEFAULT - Use the ROS specified default for deadlines (which is DEADLINE_NONE). +- DEADLINE_NONE - No deadline will be offered or requested and events will not be generated for missed deadlines. +- DEADLINE_RMW - The rmw layer of ROS will track the deadline. For a Publisher or Subscriber this means that a deadline will be considered missed if the rmw layer has not received a message within the specified time. For a Service this means the time a request is started is marked when the request reaches the rmw layer and the time at which it is finished is when the response message reaches the rmw layer. + +A Service Client will **not** be prevented from making a request to a Service Server if the Server provides a deadline greater than the deadline requested by the Client. + +### Liveliness + +For Service Servers it establishes both the level of reporting that they will provide to Clients and also the level of reporting that they require from Clients. +For Service Clients it establishes both the level of reporting that they require from Service Servers and the level of reporting that they will provide to the Server. + +Services will support the following levels of liveliness: +- LIVELINESS_DEFAULT - Use the ROS specified default for liveliness (which is LIVELINESS_AUTOMATIC). +- LIVELINESS_AUTOMATIC - The signal that establishes a Service Server is alive comes from the ROS rmw layer. +- LIVELINESS_MANUAL_NODE - The signal that establishes a Service is alive is at the node level. A message on any outgoing channel on the node or an explicit signal from the application to assert liveliness on the node will mark all outgoing channels on the node as being alive. +- LIVELINESS_MANUAL_SERVICE - The signal that establishes a Service is alive is at the Service level. Only sending a response on the Service or an explicit signal from the application to assert liveliness on the Service will mark the Service as being alive. + +In order for a Subscriber to listen to a Publisher's Topic the level of liveliness tracking they request must be equal or less verbose than the level of tracking provided by the Publisher and the time until considered not alive set by the Subscriber must be greater than the time set by the Publisher. + +Service Servers and Clients will each specify two liveliness policies, one for the liveliness policy pertaining to the Server and one pertaining to the Client. +In order for a Client to connect to a Server to make a request the Client_Liveliness level requested by the Server must be greater than the level provided by the Client and the Server_Liveliness requested by the Client must be greater than the level provided by the Server. + +### Lifespan + +For Services it establishes a time at which the request is no longer valid. +It would act similar to a timeout on the request. +There are a lot of open questions about how you would notify Client and the Server if a request was timed out and what action should be taken when the lifespan expires. ## Appendix A From f29b7be802d94558beb21c2a916957659c502242 Mon Sep 17 00:00:00 2001 From: burekn Date: Wed, 20 Mar 2019 15:08:51 -0700 Subject: [PATCH 09/12] Adds a blurb about keyed instances. --- articles/qos_deadline_liveliness_lifespan.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/articles/qos_deadline_liveliness_lifespan.md b/articles/qos_deadline_liveliness_lifespan.md index c8d8cd4e0..d5bbb3a48 100644 --- a/articles/qos_deadline_liveliness_lifespan.md +++ b/articles/qos_deadline_liveliness_lifespan.md @@ -153,6 +153,8 @@ The design and implementation of this API is out of scope for this document and - Adding this functionality would require an additional buffer that would be used to store multiple events between servicing them. Additionally, the DDS API lends itself better to only being informed of the latest change and would require a realtime response to status change events so as to not miss a single event. This is not a one way door and we could change this later to allow buffering events without breaking backwards compatibility. - How do these QoS policies impact Actions and Services? - The initial implementation does not support Actions and Services as there are more complex subtleties to how these concepts natively support these QoS features. In the future work section below we explore some ways that Services could implement these policies. +- How are these QoS policies affected by DDS topic instances? + - While all of these policies can and will eventually support keyed instances, this document does not focus on the details of how as it is highly dependent on the design for ROS 2 to support keyed messages in general. ## Future Work From 2de424359604c5a42e3ead70135e3448f7c636e4 Mon Sep 17 00:00:00 2001 From: burekn Date: Fri, 19 Jul 2019 11:38:15 -0700 Subject: [PATCH 10/12] Updating the design to reflect the actual implementation. --- articles/qos_deadline_liveliness_lifespan.md | 39 +++++++------------- 1 file changed, 14 insertions(+), 25 deletions(-) diff --git a/articles/qos_deadline_liveliness_lifespan.md b/articles/qos_deadline_liveliness_lifespan.md index d5bbb3a48..c5bd19066 100644 --- a/articles/qos_deadline_liveliness_lifespan.md +++ b/articles/qos_deadline_liveliness_lifespan.md @@ -47,13 +47,11 @@ To address these needs it was proposed that we start by adding support for the f The deadline policy establishes a contract for the amount of time allowed between messages. For Subscriptions it establishes the maximum amount of time allowed to pass between receiving messages. For Publishers it establishes the maximum amount of time allowed to pass between sending messages. - -Topics will support the following levels of deadlines: -- DEADLINE_DEFAULT - Use the ROS specified default for deadlines (which is DEADLINE_NONE). -- DEADLINE_NONE - No deadline will be offered or requested and events will not be generated for missed deadlines. -- DEADLINE_RMW - The rmw layer of ROS will track the deadline. For a Publisher or Subscriber this means that a deadline will be considered missed if the rmw layer has not received a message within the specified time. For a Service this means the time a request is started is marked when the request reaches the rmw layer and the time at which it is finished is when the response message reaches the rmw layer. - +Topics will support deadline tracking only up to the rmw layer. +This means that a deadline will be considered missed if the rmw layer has not received a message within the specified time. In order for a Subscriber to listen to a Publisher's Topic the deadline that they request must be greater than, or equal to, the deadline set by the Publisher. +A deadline time of 0 will disable the deadline tracking. +The default deadline time will be 0. ### Liveliness @@ -62,27 +60,24 @@ For Subscriptions it establishes the level of reporting that they require from t For Publishers it establishes the level of reporting that they will provide to Subscribers that they are alive. Topics will support the following levels of liveliness: -- LIVELINESS_DEFAULT - Use the ROS specified default for liveliness (which is LIVELINESS_AUTOMATIC). +- LIVELINESS_SYSTEM_DEFAULT - Use the ROS specified default for liveliness (which is LIVELINESS_AUTOMATIC). - LIVELINESS_AUTOMATIC - The signal that establishes a Topic is alive comes from the ROS rmw layer. -- LIVELINESS_MANUAL_NODE - The signal that establishes a Topic is alive is at the node level. Publishing a message on any outgoing channel on the node or an explicit signal from the application to assert liveliness on the node will mark all outgoing channels on the node as being alive. -- LIVELINESS_MANUAL_TOPIC - The signal that establishes a Topic is alive is at the Topic level. Only publishing a message on the Topic or an explicit signal from the application to assert liveliness on the Topic will mark the Topic as being alive. +- LIVELINESS_MANUAL_BY_NODE - The signal that establishes a Topic is alive is at the node level. Publishing a message on any outgoing channel on the node or an explicit signal from the application to assert liveliness on the node will mark all outgoing channels on the node as being alive. +- LIVELINESS_MANUAL_BY_TOPIC - The signal that establishes a Topic is alive is at the Topic level. Only publishing a message on the Topic or an explicit signal from the application to assert liveliness on the Topic will mark the Topic as being alive. In order for a Subscriber to listen to a Publisher's Topic the level of liveliness tracking they request must be equal or less verbose than the level of tracking provided by the Publisher and the time until considered not alive set by the Subscriber must be greater than the time set by the Publisher. ### Lifespan The lifespan policy establishes a contract for how long a message remains valid. -The lifespan QoS policy only applies to Topics. For Subscriptions it establishes the length of time a message is considered valid, after which time it will not be received. For Publishers it establishes the length of time a message is considered valid, after which time it will be removed from the Topic history and no longer sent to Subscribers. - -- LIFESPAN_DEFAULT - Use the ROS specified default for lifespan (which is LIFESPAN_NONE). -- LIFESPAN_NONE - Messages do not have a time at which they expire. -- LIFESPAN_ENABLED - Messages will have a lifespan enforced. +A lifespan time of 0 will disable the lifespan tracking. +The default lifespan time will be 0. ### DDS QoS Relation -These new policies are all based on the DDS QoS policies, but they do not require a DDS in order for an rmw implementation to support them. +These new policies are all based on the DDS QoS policies, but they do not require DDS in order for an rmw implementation to support them. More detailed information on the DDS specifics of these policies can be found below in Appendix A. ### ROS Changes @@ -111,8 +106,8 @@ In the current version of ROS there is a single QoS struct that is used to speci With these new QoS settings the supported set of QoS policies for Topics and Services diverges. Despite this, we are going to stick with a single struct for both Topics and Services instead of switching to two different struct types in order to keep the changes to a minimum and maintain as much backwards compatibility as possible in the client library interfaces. -The existing QoS policy struct will have new fields added that use enums based on the values defined above to specify the desired QoS settings for Deadline, Liveliness, and Lifespan. -Each enum field instance in the struct will also have an associated number field added to the struct that represents a time value for the policy. +The existing QoS policy struct will have new fields added to specify the desired QoS settings for Deadline, Liveliness, and Lifespan. +These new fields instances will be a combination of enum and time values. #### Assert Liveliness Functions @@ -164,12 +159,8 @@ Actions and Services were considered out of scope for the initial implementation For Service Servers it establishes the maximum amount of time allowed to pass between receiving a request and when a response for that request is sent. For Service Clients it establishes the maximum amount of time allowed to pass between sending a request and when a response for that request is received. - -Services will support the following levels of deadlines: -- DEADLINE_DEFAULT - Use the ROS specified default for deadlines (which is DEADLINE_NONE). -- DEADLINE_NONE - No deadline will be offered or requested and events will not be generated for missed deadlines. -- DEADLINE_RMW - The rmw layer of ROS will track the deadline. For a Publisher or Subscriber this means that a deadline will be considered missed if the rmw layer has not received a message within the specified time. For a Service this means the time a request is started is marked when the request reaches the rmw layer and the time at which it is finished is when the response message reaches the rmw layer. - +Services will support deadline tracking only up to the rmw layer. +This means the time a request is started is marked when the request reaches the rmw layer and the time at which it is finished is when the response message reaches the rmw layer. A Service Client will **not** be prevented from making a request to a Service Server if the Server provides a deadline greater than the deadline requested by the Client. ### Liveliness @@ -183,8 +174,6 @@ Services will support the following levels of liveliness: - LIVELINESS_MANUAL_NODE - The signal that establishes a Service is alive is at the node level. A message on any outgoing channel on the node or an explicit signal from the application to assert liveliness on the node will mark all outgoing channels on the node as being alive. - LIVELINESS_MANUAL_SERVICE - The signal that establishes a Service is alive is at the Service level. Only sending a response on the Service or an explicit signal from the application to assert liveliness on the Service will mark the Service as being alive. -In order for a Subscriber to listen to a Publisher's Topic the level of liveliness tracking they request must be equal or less verbose than the level of tracking provided by the Publisher and the time until considered not alive set by the Subscriber must be greater than the time set by the Publisher. - Service Servers and Clients will each specify two liveliness policies, one for the liveliness policy pertaining to the Server and one pertaining to the Client. In order for a Client to connect to a Server to make a request the Client_Liveliness level requested by the Server must be greater than the level provided by the Client and the Server_Liveliness requested by the Client must be greater than the level provided by the Server. From 3e7496418916a0e9b1a5a025ace0248bef61e4b8 Mon Sep 17 00:00:00 2001 From: Nick Burek Date: Tue, 24 Sep 2019 11:29:35 -0700 Subject: [PATCH 11/12] Changed wording to make it more clear... when a subscriber will receive a liveliness event when there are multiple publishers for a topic. --- articles/qos_deadline_liveliness_lifespan.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/articles/qos_deadline_liveliness_lifespan.md b/articles/qos_deadline_liveliness_lifespan.md index c5bd19066..395612a88 100644 --- a/articles/qos_deadline_liveliness_lifespan.md +++ b/articles/qos_deadline_liveliness_lifespan.md @@ -88,7 +88,7 @@ These are the various changes that would be needed within ROS in order to native Both the Deadline and Liveliness policies generate events from the rmw layer of which the application will need to be informed. For Deadlines, the Subscriber receives event notifications if it doesn't receive anything within the deadline and the Publisher receives event notifications if it doesn't publish anything within the deadline. -For Liveliness, Subscribers receive events when the Publisher they're listening to is no longer alive. +For Liveliness, Subscribers receive events when there are no longer any Publishers alive to assert the topic is alive. Services generate similar events when Clients and Servers violate the defined policies. Both of these fall under a category of "Resource Status Events". @@ -239,4 +239,4 @@ The ‘expiration time’ of each sample is computed by adding the duration spec The source timestamp is either automatically computed by the DDS Service each time the DataWriter write operation is called, or else supplied by the application by means of the write_w_timestamp operation. This QoS relies on the sender and receiving applications having their clocks sufficiently synchronized. -If this is not the case and the DDS Service can detect it, the DataReader is allowed to use the reception timestamp instead of the source timestamp in its computation of the ‘expiration time. \ No newline at end of file +If this is not the case and the DDS Service can detect it, the DataReader is allowed to use the reception timestamp instead of the source timestamp in its computation of the ‘expiration time. From 2b4b93716370336a8e86bc691d7dff477eeac7ce Mon Sep 17 00:00:00 2001 From: William Woodall Date: Tue, 24 Sep 2019 11:40:13 -0700 Subject: [PATCH 12/12] fix typo Signed-off-by: William Woodall --- articles/qos_deadline_liveliness_lifespan.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/articles/qos_deadline_liveliness_lifespan.md b/articles/qos_deadline_liveliness_lifespan.md index 395612a88..a2d7f3442 100644 --- a/articles/qos_deadline_liveliness_lifespan.md +++ b/articles/qos_deadline_liveliness_lifespan.md @@ -239,4 +239,4 @@ The ‘expiration time’ of each sample is computed by adding the duration spec The source timestamp is either automatically computed by the DDS Service each time the DataWriter write operation is called, or else supplied by the application by means of the write_w_timestamp operation. This QoS relies on the sender and receiving applications having their clocks sufficiently synchronized. -If this is not the case and the DDS Service can detect it, the DataReader is allowed to use the reception timestamp instead of the source timestamp in its computation of the ‘expiration time. +If this is not the case and the DDS Service can detect it, the DataReader is allowed to use the reception timestamp instead of the source timestamp in its computation of the expiration time.