Class QosOptions
Defined in File qos_options.hpp
Class Documentation
-
class QosOptions
Options for overriding QoS settings.
Public Functions
-
QosOptions() = default
Constructor.
Default values:
reliability = nullopt_t (detect automatically)
durability = nullopt_t (detect automatically)
history = rclcpp::HistoryPolicy::KeepLast
depth = 10
deadline = 0 (RMW default)
lifespan = 0 (RMW default)
-
std::optional<rclcpp::ReliabilityPolicy> reliability() const
Get reliability.
-
QosOptions &reliability(const rclcpp::ReliabilityPolicy &reliability)
Set reliability.
-
std::optional<rclcpp::DurabilityPolicy> durability() const
Get durability.
-
QosOptions &durability(const rclcpp::DurabilityPolicy &durability)
Set durability.
-
rclcpp::HistoryPolicy history() const
Get history.
-
QosOptions &history(const rclcpp::HistoryPolicy &history)
Set history.
-
std::size_t depth() const
Get history depth.
-
QosOptions &depth(const std::size_t &depth)
Set history depth.
-
std::optional<std::int64_t> deadline() const
Get deadline in nanoseconds.
If nullopt_t is returned, then use automatic matching.
-
QosOptions &deadline(const std::int64_t &deadline)
Set deadline.
- Parameters
deadline – number of nanoseconds. If zero, then use the RMW default policy. If negative, then it is treated an “infinite” (max number of nanoseconds).
-
QosOptions &deadline_auto()
Set deadline policy to automatically match available publishers.
-
std::optional<std::int64_t> lifespan() const
Get lifespan in nanoseconds.
If nullopt_t is returned, then use automatic matching.
-
QosOptions &lifespan(const std::int64_t &lifespan)
Set lifespan in nanoseconds.
- Parameters
lifespan – number of nanoseconds. If zero, then use the RMW default policy. If negative, then it is treated an “infinite” (max number of nanoseconds).
-
QosOptions &lifespan_auto()
Set lifespan policy to automatically match available publihsers.
-
QosOptions() = default