rclcpp  master
C++ ROS Client Library API
qos_overriding_options.hpp
Go to the documentation of this file.
1 // Copyright 2020 Open Source Robotics Foundation, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef RCLCPP__QOS_OVERRIDING_OPTIONS_HPP_
16 #define RCLCPP__QOS_OVERRIDING_OPTIONS_HPP_
17 
18 #include <functional>
19 #include <initializer_list>
20 #include <ostream>
21 #include <string>
22 #include <utility>
23 #include <vector>
24 
25 #include "rclcpp/qos.hpp"
27 
28 #include "rcl_interfaces/msg/set_parameters_result.hpp"
29 #include "rmw/qos_policy_kind.h"
30 
31 namespace rclcpp
32 {
33 
34 enum class RCLCPP_PUBLIC_TYPE QosPolicyKind
35 {
46 };
47 
49 const char *
50 qos_policy_kind_to_cstr(const QosPolicyKind & qpk);
51 
54 operator<<(std::ostream & os, const QosPolicyKind & qpk);
55 
56 using QosCallbackResult = rcl_interfaces::msg::SetParametersResult;
58 
59 namespace detail
60 {
61 // forward declare
62 template<typename T>
64 }
65 
67 
90 {
91 public:
94  QosOverridingOptions() = default;
95 
97 
117  QosCallback validation_callback = nullptr,
118  std::string id = {});
119 
121  const std::string &
122  get_id() const;
123 
126  get_policy_kinds() const;
127 
129  const QosCallback &
130  get_validation_callback() const;
131 
133 
139  static
141  with_default_policies(QosCallback validation_callback = nullptr, std::string id = {});
142 
143 private:
145  std::string id_;
147  std::vector<QosPolicyKind> policy_kinds_;
149  QosCallback validation_callback_;
150 };
151 
152 } // namespace rclcpp
153 
154 #endif // RCLCPP__QOS_OVERRIDING_OPTIONS_HPP_
RMW_QOS_POLICY_AVOID_ROS_NAMESPACE_CONVENTIONS
RMW_QOS_POLICY_AVOID_ROS_NAMESPACE_CONVENTIONS
LivelinessLeaseDuration
LivelinessLeaseDuration
Definition: qos_overriding_options.hpp:43
std::string
rclcpp::qos_policy_kind_to_cstr
const char * qos_policy_kind_to_cstr(const QosPolicyKind &qpk)
Depth
Depth
Definition: qos_overriding_options.hpp:38
RMW_QOS_POLICY_DEPTH
RMW_QOS_POLICY_DEPTH
rclcpp::QosOverridingOptions::get_policy_kinds
const std::vector< QosPolicyKind > & get_policy_kinds() const
rclcpp::QosOverridingOptions::get_validation_callback
const QosCallback & get_validation_callback() const
History
History
Definition: qos_overriding_options.hpp:40
rclcpp::operator<<
std::ostream & operator<<(std::ostream &os, const FutureReturnCode &future_return_code)
Stream operator for FutureReturnCode.
std::vector< QosPolicyKind >
Deadline
Deadline
Definition: qos_overriding_options.hpp:37
rclcpp::QosOverridingOptions::with_default_policies
static QosOverridingOptions with_default_policies(QosCallback validation_callback=nullptr, std::string id={})
Construct passing a list of QoS policies and a verification callback.
RMW_QOS_POLICY_DURABILITY
RMW_QOS_POLICY_DURABILITY
std::function< QosCallbackResult(const rclcpp::QoS &)>
Invalid
Invalid
Definition: qos_overriding_options.hpp:45
Liveliness
Liveliness
Definition: qos_overriding_options.hpp:42
RMW_QOS_POLICY_LIFESPAN
RMW_QOS_POLICY_LIFESPAN
rclcpp
This header provides the get_node_base_interface() template function.
Definition: allocator_common.hpp:24
qos.hpp
RCLCPP_PUBLIC
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
rclcpp::QosOverridingOptions
Options that are passed in subscription/publisher constructor to specify QoSConfigurability.
Definition: qos_overriding_options.hpp:89
rclcpp::QoS
Encapsulation of Quality of Service settings.
Definition: qos.hpp:110
rclcpp::QosOverridingOptions::get_id
const std::string & get_id() const
rclcpp::QosOverridingOptions::QosOverridingOptions
QosOverridingOptions()=default
Default constructor, no overrides allowed.
RMW_QOS_POLICY_HISTORY
RMW_QOS_POLICY_HISTORY
RMW_QOS_POLICY_DEADLINE
RMW_QOS_POLICY_DEADLINE
std::ostream
qos_policy_kind.h
RMW_QOS_POLICY_INVALID
RMW_QOS_POLICY_INVALID
RMW_QOS_POLICY_RELIABILITY
RMW_QOS_POLICY_RELIABILITY
Durability
Durability
Definition: qos_overriding_options.hpp:39
Reliability
Reliability
Definition: qos_overriding_options.hpp:44
Lifespan
Lifespan
Definition: qos_overriding_options.hpp:41
RCLCPP_PUBLIC_TYPE
#define RCLCPP_PUBLIC_TYPE
Definition: visibility_control.hpp:53
AvoidRosNamespaceConventions
AvoidRosNamespaceConventions
Definition: qos_overriding_options.hpp:36
visibility_control.hpp
rclcpp::detail::QosParameters
Definition: qos_overriding_options.hpp:63
RMW_QOS_POLICY_LIVELINESS
RMW_QOS_POLICY_LIVELINESS
RMW_QOS_POLICY_LIVELINESS_LEASE_DURATION
RMW_QOS_POLICY_LIVELINESS_LEASE_DURATION
rclcpp::QosCallbackResult
rcl_interfaces::msg::SetParametersResult QosCallbackResult
Definition: qos_overriding_options.hpp:56
std::initializer_list