ROS 2 rclcpp + rcl - humble  humble
ROS 2 C++ Client Library with ROS Client Library
Public Member Functions | List of all members
rclcpp::QoS Class Reference

Encapsulation of Quality of Service settings. More...

#include <rclcpp/qos.hpp>

Inheritance diagram for rclcpp::QoS:
Inheritance graph
[legend]

Public Member Functions

 QoS (const QoSInitialization &qos_initialization, const rmw_qos_profile_t &initial_profile=rmw_qos_profile_default)
 Create a QoS by specifying only the history policy and history depth. More...
 
 QoS (size_t history_depth)
 Conversion constructor to ease construction in the common case of just specifying depth. More...
 
rmw_qos_profile_t & get_rmw_qos_profile ()
 Return the rmw qos profile.
 
const rmw_qos_profile_t & get_rmw_qos_profile () const
 Return the rmw qos profile.
 
QoShistory (HistoryPolicy history)
 Set the history policy.
 
QoShistory (rmw_qos_history_policy_t history)
 Set the history policy.
 
QoSkeep_last (size_t depth)
 Set the history to keep last.
 
QoSkeep_all ()
 Set the history to keep all.
 
QoSreliability (rmw_qos_reliability_policy_t reliability)
 Set the reliability setting.
 
QoSreliability (ReliabilityPolicy reliability)
 Set the reliability setting.
 
QoSreliable ()
 Set the reliability setting to reliable.
 
QoSbest_effort ()
 Set the reliability setting to best effort.
 
QoSdurability (rmw_qos_durability_policy_t durability)
 Set the durability setting.
 
QoSdurability (DurabilityPolicy durability)
 Set the durability setting.
 
QoSdurability_volatile ()
 Set the durability setting to volatile. More...
 
QoStransient_local ()
 Set the durability setting to transient local.
 
QoSdeadline (rmw_time_t deadline)
 Set the deadline setting.
 
QoSdeadline (const rclcpp::Duration &deadline)
 Set the deadline setting, rclcpp::Duration.
 
QoSlifespan (rmw_time_t lifespan)
 Set the lifespan setting.
 
QoSlifespan (const rclcpp::Duration &lifespan)
 Set the lifespan setting, rclcpp::Duration.
 
QoSliveliness (rmw_qos_liveliness_policy_t liveliness)
 Set the liveliness setting.
 
QoSliveliness (LivelinessPolicy liveliness)
 Set the liveliness setting.
 
QoSliveliness_lease_duration (rmw_time_t liveliness_lease_duration)
 Set the liveliness_lease_duration setting.
 
QoSliveliness_lease_duration (const rclcpp::Duration &liveliness_lease_duration)
 Set the liveliness_lease_duration setting, rclcpp::Duration.
 
QoSavoid_ros_namespace_conventions (bool avoid_ros_namespace_conventions)
 Set the avoid_ros_namespace_conventions setting.
 
HistoryPolicy history () const
 Get the history qos policy.
 
size_t depth () const
 Get the history depth.
 
ReliabilityPolicy reliability () const
 Get the reliability policy.
 
DurabilityPolicy durability () const
 Get the durability policy.
 
rclcpp::Duration deadline () const
 Get the deadline duration setting.
 
rclcpp::Duration lifespan () const
 Get the lifespan duration setting.
 
LivelinessPolicy liveliness () const
 Get the liveliness policy.
 
rclcpp::Duration liveliness_lease_duration () const
 Get the liveliness lease duration setting.
 
bool avoid_ros_namespace_conventions () const
 Get the avoid ros namespace convention setting.
 

Detailed Description

Encapsulation of Quality of Service settings.

Quality of Service settings control the behavior of publishers, subscriptions, and other entities, and includes things like how data is sent or resent, how data is buffered on the publishing and subscribing side, and other things. See: https://docs.ros.org/en/rolling/Concepts/About-Quality-of-Service-Settings.html

Definition at line 110 of file qos.hpp.

Constructor & Destructor Documentation

◆ QoS() [1/2]

rclcpp::QoS::QoS ( const QoSInitialization qos_initialization,
const rmw_qos_profile_t &  initial_profile = rmw_qos_profile_default 
)
explicit

Create a QoS by specifying only the history policy and history depth.

When using the default initial profile, the defaults will include:

See rmw_qos_profile_default for a full list of default settings. If some other rmw_qos_profile_t is passed to initial_profile, then the defaults will derive from that profile instead.

Parameters
[in]qos_initializationSpecifies history policy and history depth.
[in]initial_profileThe rmw_qos_profile_t instance on which to base the default settings.

Definition at line 74 of file qos.cpp.

◆ QoS() [2/2]

rclcpp::QoS::QoS ( size_t  history_depth)

Conversion constructor to ease construction in the common case of just specifying depth.

This is a convenience constructor that calls QoS(KeepLast(history_depth)).

Parameters
[in]history_depthHow many messages can be queued when publishing with a Publisher, or how many messages can be queued before being replaced by a Subscription.

Definition at line 83 of file qos.cpp.

Member Function Documentation

◆ durability_volatile()

QoS & rclcpp::QoS::durability_volatile ( )

Set the durability setting to volatile.

Note that this cannot be named volatile because it is a C++ keyword.

Definition at line 170 of file qos.cpp.

References durability().

Here is the call graph for this function:

The documentation for this class was generated from the following files: