rclcpp  beta1
C++ ROS Client Library API
node_parameters.hpp
Go to the documentation of this file.
1 // Copyright 2016 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__NODE_INTERFACES__NODE_PARAMETERS_HPP_
16 #define RCLCPP__NODE_INTERFACES__NODE_PARAMETERS_HPP_
17 
18 #include <map>
19 #include <string>
20 #include <vector>
21 
22 #include "rcl_interfaces/msg/list_parameters_result.hpp"
23 #include "rcl_interfaces/msg/parameter_descriptor.hpp"
24 #include "rcl_interfaces/msg/parameter_event.hpp"
25 #include "rcl_interfaces/msg/set_parameters_result.hpp"
26 
27 #include "rclcpp/macros.hpp"
32 #include "rclcpp/parameter.hpp"
33 #include "rclcpp/publisher.hpp"
35 
36 namespace rclcpp
37 {
38 namespace node_interfaces
39 {
40 
43 {
44 public:
46 
50  bool use_intra_process);
51 
53  virtual
55 
57  virtual
61 
63  virtual
64  rcl_interfaces::msg::SetParametersResult
67 
69  virtual
71  get_parameters(const std::vector<std::string> & names) const;
72 
74  virtual
76  get_parameter(const std::string & name) const;
77 
79  virtual
80  bool
82  const std::string & name,
83  rclcpp::parameter::ParameterVariant & parameter) const;
84 
86  virtual
88  describe_parameters(const std::vector<std::string> & names) const;
89 
91  virtual
93  get_parameter_types(const std::vector<std::string> & names) const;
94 
96  virtual
97  rcl_interfaces::msg::ListParametersResult
98  list_parameters(const std::vector<std::string> & prefixes, uint64_t depth) const;
99 
101  virtual
102  void
104 
105 private:
106  RCLCPP_DISABLE_COPY(NodeParameters)
107 
109 
110  mutable std::mutex mutex_;
111 
112  ParametersCallbackFunction parameters_callback_ = nullptr;
113 
115 
117 };
118 
119 } // namespace node_interfaces
120 } // namespace rclcpp
121 
122 #endif // RCLCPP__NODE_INTERFACES__NODE_PARAMETERS_HPP_
#define RCLCPP_DISABLE_COPY(...)
Definition: macros.hpp:26
Pure virtual interface class for the NodeParameters part of the Node API.
Definition: node_parameters_interface.hpp:35
#define RCLCPP_SMART_PTR_ALIASES_ONLY(...)
Definition: macros.hpp:66
std::function< rcl_interfaces::msg::SetParametersResult(const std::vector< rclcpp::parameter::ParameterVariant > &)> ParametersCallbackFunction
Definition: node_parameters_interface.hpp:86
Definition: allocator_common.hpp:24
Implementation of the NodeParameters part of the Node API.
Definition: node_parameters.hpp:42
virtual void register_param_change_callback(ParametersCallbackFunction callback)
virtual std::vector< rcl_interfaces::msg::ParameterDescriptor > describe_parameters(const std::vector< std::string > &names) const
virtual std::vector< rcl_interfaces::msg::SetParametersResult > set_parameters(const std::vector< rclcpp::parameter::ParameterVariant > &parameters)
virtual rclcpp::parameter::ParameterVariant get_parameter(const std::string &name) const
Pure virtual interface class for the NodeTopics part of the Node API.
Definition: node_topics_interface.hpp:38
virtual std::vector< uint8_t > get_parameter_types(const std::vector< std::string > &names) const
virtual std::vector< rclcpp::parameter::ParameterVariant > get_parameters(const std::vector< std::string > &names) const
A publisher publishes messages of any type to a topic.
Definition: publisher.hpp:146
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
virtual rcl_interfaces::msg::ListParametersResult list_parameters(const std::vector< std::string > &prefixes, uint64_t depth) const
NodeParameters(rclcpp::node_interfaces::NodeTopicsInterface *node_topics, bool use_intra_process)
Definition: parameter.hpp:45
virtual rcl_interfaces::msg::SetParametersResult set_parameters_atomically(const std::vector< rclcpp::parameter::ParameterVariant > &parameters)