rclcpp
master
C++ ROS Client Library API
|
Encapsulation of Quality of Service settings. More...
#include <qos.hpp>
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_t & | get_rmw_qos_profile () |
Return the rmw qos profile. More... | |
const rmw_qos_profile_t & | get_rmw_qos_profile () const |
Return the rmw qos profile. More... | |
QoS & | history (rmw_qos_history_policy_t history) |
Set the history policy. More... | |
QoS & | keep_last (size_t depth) |
Set the history to keep last. More... | |
QoS & | keep_all () |
Set the history to keep all. More... | |
QoS & | reliability (rmw_qos_reliability_policy_t reliability) |
Set the reliability setting. More... | |
QoS & | reliable () |
Set the reliability setting to reliable. More... | |
QoS & | best_effort () |
Set the reliability setting to best effort. More... | |
QoS & | durability (rmw_qos_durability_policy_t durability) |
Set the durability setting. More... | |
QoS & | durability_volatile () |
Set the durability setting to volatile. More... | |
QoS & | transient_local () |
Set the durability setting to transient local. More... | |
QoS & | deadline (rmw_time_t deadline) |
Set the deadline setting. More... | |
QoS & | deadline (const rclcpp::Duration &deadline) |
Set the deadline setting, rclcpp::Duration. More... | |
QoS & | lifespan (rmw_time_t lifespan) |
Set the lifespan setting. More... | |
QoS & | lifespan (const rclcpp::Duration &lifespan) |
Set the lifespan setting, rclcpp::Duration. More... | |
QoS & | liveliness (rmw_qos_liveliness_policy_t liveliness) |
Set the liveliness setting. More... | |
QoS & | liveliness_lease_duration (rmw_time_t liveliness_lease_duration) |
Set the liveliness_lease_duration setting. More... | |
QoS & | liveliness_lease_duration (const rclcpp::Duration &liveliness_lease_duration) |
Set the liveliness_lease_duration setting, rclcpp::Duration. More... | |
QoS & | avoid_ros_namespace_conventions (bool avoid_ros_namespace_conventions) |
Set the avoid_ros_namespace_conventions setting. More... | |
Encapsulation of Quality of Service settings.
|
explicit |
Constructor which allows you to construct a QoS by giving the only required settings.
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)).
rmw_qos_profile_t& rclcpp::QoS::get_rmw_qos_profile | ( | ) |
Return the rmw qos profile.
const rmw_qos_profile_t& rclcpp::QoS::get_rmw_qos_profile | ( | ) | const |
Return the rmw qos profile.
QoS& rclcpp::QoS::history | ( | rmw_qos_history_policy_t | history | ) |
Set the history policy.
QoS& rclcpp::QoS::keep_last | ( | size_t | depth | ) |
Set the history to keep last.
QoS& rclcpp::QoS::keep_all | ( | ) |
Set the history to keep all.
QoS& rclcpp::QoS::reliability | ( | rmw_qos_reliability_policy_t | reliability | ) |
Set the reliability setting.
QoS& rclcpp::QoS::reliable | ( | ) |
Set the reliability setting to reliable.
QoS& rclcpp::QoS::best_effort | ( | ) |
Set the reliability setting to best effort.
QoS& rclcpp::QoS::durability | ( | rmw_qos_durability_policy_t | durability | ) |
Set the durability setting.
QoS& rclcpp::QoS::durability_volatile | ( | ) |
Set the durability setting to volatile.
Note that this cannot be named volatile
because it is a C++ keyword.
QoS& rclcpp::QoS::transient_local | ( | ) |
Set the durability setting to transient local.
QoS& rclcpp::QoS::deadline | ( | rmw_time_t | deadline | ) |
Set the deadline setting.
QoS& rclcpp::QoS::deadline | ( | const rclcpp::Duration & | deadline | ) |
Set the deadline setting, rclcpp::Duration.
QoS& rclcpp::QoS::lifespan | ( | rmw_time_t | lifespan | ) |
Set the lifespan setting.
QoS& rclcpp::QoS::lifespan | ( | const rclcpp::Duration & | lifespan | ) |
Set the lifespan setting, rclcpp::Duration.
QoS& rclcpp::QoS::liveliness | ( | rmw_qos_liveliness_policy_t | liveliness | ) |
Set the liveliness setting.
QoS& rclcpp::QoS::liveliness_lease_duration | ( | rmw_time_t | liveliness_lease_duration | ) |
Set the liveliness_lease_duration setting.
QoS& rclcpp::QoS::liveliness_lease_duration | ( | const rclcpp::Duration & | liveliness_lease_duration | ) |
Set the liveliness_lease_duration setting, rclcpp::Duration.
QoS& rclcpp::QoS::avoid_ros_namespace_conventions | ( | bool | avoid_ros_namespace_conventions | ) |
Set the avoid_ros_namespace_conventions setting.