rclcpp  master
C++ ROS Client Library API
Public Member Functions | List of all members
rclcpp::QoS Class Reference

Encapsulation of Quality of Service settings. More...

#include <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)
 Constructor which allows you to construct a QoS by giving the only required settings. More...
 
 QoS (size_t history_depth)
 Conversion constructor to ease construction in the common case of just specifying depth. More...
 
rmw_qos_profile_tget_rmw_qos_profile ()
 Return the rmw qos profile. More...
 
const rmw_qos_profile_tget_rmw_qos_profile () const
 Return the rmw qos profile. More...
 
QoShistory (rmw_qos_history_policy_t history)
 Set the history policy. More...
 
QoSkeep_last (size_t depth)
 Set the history to keep last. More...
 
QoSkeep_all ()
 Set the history to keep all. More...
 
QoSreliability (rmw_qos_reliability_policy_t reliability)
 Set the reliability setting. More...
 
QoSreliable ()
 Set the reliability setting to reliable. More...
 
QoSbest_effort ()
 Set the reliability setting to best effort. More...
 
QoSdurability (rmw_qos_durability_policy_t durability)
 Set the durability setting. More...
 
QoSdurability_volatile ()
 Set the durability setting to volatile. More...
 
QoStransient_local ()
 Set the durability setting to transient local. More...
 
QoSdeadline (rmw_time_t deadline)
 Set the deadline setting. More...
 
QoSdeadline (const rclcpp::Duration &deadline)
 Set the deadline setting, rclcpp::Duration. More...
 
QoSlifespan (rmw_time_t lifespan)
 Set the lifespan setting. More...
 
QoSlifespan (const rclcpp::Duration &lifespan)
 Set the lifespan setting, rclcpp::Duration. More...
 
QoSliveliness (rmw_qos_liveliness_policy_t liveliness)
 Set the liveliness setting. More...
 
QoSliveliness_lease_duration (rmw_time_t liveliness_lease_duration)
 Set the liveliness_lease_duration setting. More...
 
QoSliveliness_lease_duration (const rclcpp::Duration &liveliness_lease_duration)
 Set the liveliness_lease_duration setting, rclcpp::Duration. More...
 
QoSavoid_ros_namespace_conventions (bool avoid_ros_namespace_conventions)
 Set the avoid_ros_namespace_conventions setting. More...
 

Detailed Description

Encapsulation of Quality of Service settings.

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

Constructor which allows you to construct a QoS by giving the only required settings.

◆ QoS() [2/2]

rclcpp::QoS::QoS ( size_t  history_depth)

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

Convenience constructor, equivalent to QoS(KeepLast(history_depth)).

Member Function Documentation

◆ get_rmw_qos_profile() [1/2]

rmw_qos_profile_t& rclcpp::QoS::get_rmw_qos_profile ( )

Return the rmw qos profile.

◆ get_rmw_qos_profile() [2/2]

const rmw_qos_profile_t& rclcpp::QoS::get_rmw_qos_profile ( ) const

Return the rmw qos profile.

◆ history()

QoS& rclcpp::QoS::history ( rmw_qos_history_policy_t  history)

Set the history policy.

◆ keep_last()

QoS& rclcpp::QoS::keep_last ( size_t  depth)

Set the history to keep last.

◆ keep_all()

QoS& rclcpp::QoS::keep_all ( )

Set the history to keep all.

◆ reliability()

QoS& rclcpp::QoS::reliability ( rmw_qos_reliability_policy_t  reliability)

Set the reliability setting.

◆ reliable()

QoS& rclcpp::QoS::reliable ( )

Set the reliability setting to reliable.

◆ best_effort()

QoS& rclcpp::QoS::best_effort ( )

Set the reliability setting to best effort.

◆ durability()

QoS& rclcpp::QoS::durability ( rmw_qos_durability_policy_t  durability)

Set the durability setting.

◆ 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.

◆ transient_local()

QoS& rclcpp::QoS::transient_local ( )

Set the durability setting to transient local.

◆ deadline() [1/2]

QoS& rclcpp::QoS::deadline ( rmw_time_t  deadline)

Set the deadline setting.

◆ deadline() [2/2]

QoS& rclcpp::QoS::deadline ( const rclcpp::Duration deadline)

Set the deadline setting, rclcpp::Duration.

◆ lifespan() [1/2]

QoS& rclcpp::QoS::lifespan ( rmw_time_t  lifespan)

Set the lifespan setting.

◆ lifespan() [2/2]

QoS& rclcpp::QoS::lifespan ( const rclcpp::Duration lifespan)

Set the lifespan setting, rclcpp::Duration.

◆ liveliness()

QoS& rclcpp::QoS::liveliness ( rmw_qos_liveliness_policy_t  liveliness)

Set the liveliness setting.

◆ liveliness_lease_duration() [1/2]

QoS& rclcpp::QoS::liveliness_lease_duration ( rmw_time_t  liveliness_lease_duration)

Set the liveliness_lease_duration setting.

◆ liveliness_lease_duration() [2/2]

QoS& rclcpp::QoS::liveliness_lease_duration ( const rclcpp::Duration liveliness_lease_duration)

Set the liveliness_lease_duration setting, rclcpp::Duration.

◆ avoid_ros_namespace_conventions()

QoS& rclcpp::QoS::avoid_ros_namespace_conventions ( bool  avoid_ros_namespace_conventions)

Set the avoid_ros_namespace_conventions setting.


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