.. _program_listing_file_include_rclcpp_qos_overriding_options.hpp: Program Listing for File qos_overriding_options.hpp =================================================== |exhale_lsh| :ref:`Return to documentation for file ` (``include/rclcpp/qos_overriding_options.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp // Copyright 2020 Open Source Robotics Foundation, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 // // Unless required by applicable law or agreed to in writing, software // distributed under the License is distributed on an "AS IS" BASIS, // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. #ifndef RCLCPP__QOS_OVERRIDING_OPTIONS_HPP_ #define RCLCPP__QOS_OVERRIDING_OPTIONS_HPP_ #include #include #include #include #include #include #include "rclcpp/qos.hpp" #include "rclcpp/visibility_control.hpp" #include "rcl_interfaces/msg/set_parameters_result.hpp" #include "rmw/qos_policy_kind.h" namespace rclcpp { enum class RCLCPP_PUBLIC_TYPE QosPolicyKind { AvoidRosNamespaceConventions = RMW_QOS_POLICY_AVOID_ROS_NAMESPACE_CONVENTIONS, Deadline = RMW_QOS_POLICY_DEADLINE, Depth = RMW_QOS_POLICY_DEPTH, Durability = RMW_QOS_POLICY_DURABILITY, History = RMW_QOS_POLICY_HISTORY, Lifespan = RMW_QOS_POLICY_LIFESPAN, Liveliness = RMW_QOS_POLICY_LIVELINESS, LivelinessLeaseDuration = RMW_QOS_POLICY_LIVELINESS_LEASE_DURATION, Reliability = RMW_QOS_POLICY_RELIABILITY, Invalid = RMW_QOS_POLICY_INVALID, }; RCLCPP_PUBLIC const char * qos_policy_kind_to_cstr(const QosPolicyKind & qpk); RCLCPP_PUBLIC std::ostream & operator<<(std::ostream & os, const QosPolicyKind & qpk); using QosCallbackResult = rcl_interfaces::msg::SetParametersResult; using QosCallback = std::function; namespace detail { // forward declare template class QosParameters; } class QosOverridingOptions { public: RCLCPP_PUBLIC QosOverridingOptions() = default; RCLCPP_PUBLIC QosOverridingOptions( std::initializer_list policy_kinds, QosCallback validation_callback = nullptr, std::string id = {}); RCLCPP_PUBLIC const std::string & get_id() const; RCLCPP_PUBLIC const std::vector & get_policy_kinds() const; RCLCPP_PUBLIC const QosCallback & get_validation_callback() const; RCLCPP_PUBLIC static QosOverridingOptions with_default_policies(QosCallback validation_callback = nullptr, std::string id = {}); private: std::string id_; std::vector policy_kinds_; QosCallback validation_callback_; }; } // namespace rclcpp #endif // RCLCPP__QOS_OVERRIDING_OPTIONS_HPP_