ROS 2 rclcpp + rcl - jazzy  jazzy
ROS 2 C++ Client Library with ROS Client Library
qos_overriding_options.hpp
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"
26 #include "rclcpp/visibility_control.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 {
36  AvoidRosNamespaceConventions = RMW_QOS_POLICY_AVOID_ROS_NAMESPACE_CONVENTIONS,
37  Deadline = RMW_QOS_POLICY_DEADLINE,
38  Depth = RMW_QOS_POLICY_DEPTH,
39  Durability = RMW_QOS_POLICY_DURABILITY,
40  History = RMW_QOS_POLICY_HISTORY,
41  Lifespan = RMW_QOS_POLICY_LIFESPAN,
42  Liveliness = RMW_QOS_POLICY_LIVELINESS,
43  LivelinessLeaseDuration = RMW_QOS_POLICY_LIVELINESS_LEASE_DURATION,
44  Reliability = RMW_QOS_POLICY_RELIABILITY,
45  Invalid = RMW_QOS_POLICY_INVALID,
46 };
47 
48 RCLCPP_PUBLIC
49 const char *
50 qos_policy_kind_to_cstr(const QosPolicyKind & qpk);
51 
52 RCLCPP_PUBLIC
53 std::ostream &
54 operator<<(std::ostream & os, const QosPolicyKind & qpk);
55 
56 using QosCallbackResult = rcl_interfaces::msg::SetParametersResult;
57 using QosCallback = std::function<QosCallbackResult(const rclcpp::QoS &)>;
58 
59 namespace detail
60 {
61 // forward declare
62 template<typename T>
64 }
65 
67 
90 {
91 public:
93  RCLCPP_PUBLIC
94  QosOverridingOptions() = default;
95 
97 
114  RCLCPP_PUBLIC
116  std::initializer_list<QosPolicyKind> policy_kinds,
117  QosCallback validation_callback = nullptr,
118  std::string id = {});
119 
120  RCLCPP_PUBLIC
121  const std::string &
122  get_id() const;
123 
124  RCLCPP_PUBLIC
125  const std::vector<QosPolicyKind> &
126  get_policy_kinds() const;
127 
128  RCLCPP_PUBLIC
129  const QosCallback &
130  get_validation_callback() const;
131 
133 
138  RCLCPP_PUBLIC
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_
Encapsulation of Quality of Service settings.
Definition: qos.hpp:116
Options that are passed in subscription/publisher constructor to specify QoSConfigurability.
RCLCPP_PUBLIC QosOverridingOptions()=default
Default constructor, no overrides allowed.
static RCLCPP_PUBLIC QosOverridingOptions with_default_policies(QosCallback validation_callback=nullptr, std::string id={})
Construct passing a list of QoS policies and a verification callback.
Versions of rosidl_typesupport_cpp::get_message_type_support_handle that handle adapted types.
RCLCPP_PUBLIC std::ostream & operator<<(std::ostream &os, const FutureReturnCode &future_return_code)
Stream operator for FutureReturnCode.