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) | |
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. More... | |
const rmw_qos_profile_t & | get_rmw_qos_profile () const |
Return the rmw qos profile. More... | |
QoS & | history (HistoryPolicy history) |
Set the history policy. 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 & | reliability (ReliabilityPolicy 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 (DurabilityPolicy 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 (LivelinessPolicy 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... | |
HistoryPolicy | history () const |
Get the history qos policy. More... | |
size_t | depth () const |
Get the history depth. More... | |
ReliabilityPolicy | reliability () const |
Get the reliability policy. More... | |
DurabilityPolicy | durability () const |
Get the durability policy. More... | |
rclcpp::Duration | deadline () const |
Get the deadline duration setting. More... | |
rclcpp::Duration | lifespan () const |
Get the lifespan duration setting. More... | |
LivelinessPolicy | liveliness () const |
Get the liveliness policy. More... | |
rclcpp::Duration | liveliness_lease_duration () const |
Get the liveliness lease duration setting. More... | |
bool | avoid_ros_namespace_conventions () const |
Get the avoid ros namespace convention setting. More... | |
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
|
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.
[in] | qos_initialization | Specifies history policy and history depth. |
[in] | initial_profile | The rmw_qos_profile_t instance on which to base the default settings. |
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)).
[in] | history_depth | How many messages can be queued when publishing with a Publisher, or how many messages can be queued before being replaced by a Subscription. |
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 | ( | HistoryPolicy | history | ) |
Set the history policy.
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::reliability | ( | ReliabilityPolicy | 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 | ( | DurabilityPolicy | 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 | ( | LivelinessPolicy | 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.
HistoryPolicy rclcpp::QoS::history | ( | ) | const |
Get the history qos policy.
size_t rclcpp::QoS::depth | ( | ) | const |
Get the history depth.
ReliabilityPolicy rclcpp::QoS::reliability | ( | ) | const |
Get the reliability policy.
DurabilityPolicy rclcpp::QoS::durability | ( | ) | const |
Get the durability policy.
rclcpp::Duration rclcpp::QoS::deadline | ( | ) | const |
Get the deadline duration setting.
rclcpp::Duration rclcpp::QoS::lifespan | ( | ) | const |
Get the lifespan duration setting.
LivelinessPolicy rclcpp::QoS::liveliness | ( | ) | const |
Get the liveliness policy.
rclcpp::Duration rclcpp::QoS::liveliness_lease_duration | ( | ) | const |
Get the liveliness lease duration setting.
bool rclcpp::QoS::avoid_ros_namespace_conventions | ( | ) | const |
Get the avoid ros namespace convention
setting.