Class QoS

Class Documentation

class QoS

Quality of service profile for ROS node entities.

Encapsulates QoS profiles for a group of ROS publishers and subscriptions. Supports parsing SDF <qos> tags.

Note, this implementation groups QoS profiles by entity type (publisher or subscription) and topic name. For example, two publishers using the same topic will have the same QoS returned by this class.


Public Functions

QoS()
QoS(sdf::ElementPtr _sdf, const std::string node_name, const std::string node_namespace, const rclcpp::NodeOptions &options)

Constructor with SDF.

Create a new QoS profile for a collection of node entities from SDF. SDF should have the form:

<qos>
 <!-- Zero or more topic tags with topic names to configure -->
 <topic name="my/topic/name">
   <!-- Optional tag for setting the QoS profile for subscriptions -->
   <subscription>
     <!-- Optional tags for overriding default settings (see below)-->
   </subscription>
   <!-- Optional tag for setting the QoS profile for publishers -->
   <publisher>
     <!-- Optionally tags for overriding default settings (see below) -->
   </publisher>
 </topic>
</qos>

The available QoS settings that can be overridden are outlined below. For more information on each option and their possible values, see http://design.ros2.org/articles/qos.html and http://design.ros2.org/articles/qos_deadline_liveliness_lifespan.html.

The <reliability> element must contain one of the following: “reliable”, “best_effort”, or “system”.

The <durability> element must contain one of the following: “volatile”, “transient_local”, or “system”.

The <history> element must contain one of the following: “keep_last”, “keep_all”, or “system”. If “keep_last” is used, a “depth” attribute must be present and set to a positive integer.

The <deadline> element must contain a positive integer representing a duration in milliseconds.

The <lifespan> element must contain a positive integer representing a duration in milliseconds.

The <liveliness> element must contain one of the following: “automatic”, “manual_by_topic”, or “system”.

The <liveliness_lease_duration> element must contain a positive integer representing a duration in milliseconds.

For any QoS setting that is not specified in the SDF, the default QoS object passed to the getter methods is used.

The topic name should be the name expected after any remapping occurs. For example, if a <remapping> tag remaps a topic ‘foo’ to the name ‘bar’, then the <topic> tag’s name attribute should have the value ‘bar’ to override any QoS settings:

<remapping>foo:=bar</remapping>
<qos>
  <topic name='bar'>
  </topic>
</qos>
Parameters:
  • _sdf[in] An SDF element in the style documented above

  • node_name[in] The name of the node associated with these QoS settings.

  • node_namespace[in] The namespace of the node associated with these QoS settings.

  • options[in] Node options that were also passed to the node associated with these QoS settings. This contains the necessary information extracting the remappings.

Throws:

gazebo_ros::InvalidQoSException – if there is an invalid QoS value or a topic element is missing a “name” attribute.

rclcpp::QoS get_publisher_qos(const std::string topic, rclcpp::QoS default_qos = rclcpp::QoS(10)) const

Get the QoS for a publisher.

rclcpp::QoS get_subscription_qos(const std::string topic, rclcpp::QoS default_qos = rclcpp::QoS(10)) const

Get the QoS for a subscription.

QoS(const QoS &other)

QoS is copyable.

QoS(QoS &&other)

QoS is movable.

QoS &operator=(const QoS &other)

QoS is copy assignable.

QoS &operator=(QoS &&other)

QoS is move assignable.

~QoS()