rclcpp  master
C++ ROS Client Library API
parameter.hpp
Go to the documentation of this file.
1 // Copyright 2015 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__PARAMETER_HPP_
16 #define RCLCPP__PARAMETER_HPP_
17 
18 #include <iostream>
19 #include <ostream>
20 #include <sstream>
21 #include <string>
22 #include <vector>
23 
24 #include "rcl_interfaces/msg/parameter.hpp"
27 
28 namespace rclcpp
29 {
30 
32 class Parameter
33 {
34 public:
36  Parameter();
37 
39  Parameter(const std::string & name, const ParameterValue & value);
40 
41  template<typename ValueTypeT>
42  explicit Parameter(const std::string & name, ValueTypeT value)
43  : Parameter(name, ParameterValue(value))
44  {
45  }
46 
49  get_type() const;
50 
53  get_type_name() const;
54 
56  const std::string &
57  get_name() const;
58 
60  rcl_interfaces::msg::ParameterValue
61  get_value_message() const;
62 
64  template<ParameterType ParamT>
65  decltype(auto)
66  get_value() const
67  {
68  return value_.get<ParamT>();
69  }
70 
72  template<typename T>
73  decltype(auto)
74  get_value() const
75  {
76  return value_.get<T>();
77  }
78 
80  bool
81  as_bool() const;
82 
84  int64_t
85  as_int() const;
86 
88  double
89  as_double() const;
90 
92  const std::string &
93  as_string() const;
94 
96  const std::vector<uint8_t> &
97  as_byte_array() const;
98 
100  const std::vector<bool> &
101  as_bool_array() const;
102 
104  const std::vector<int64_t> &
105  as_integer_array() const;
106 
108  const std::vector<double> &
109  as_double_array() const;
110 
113  as_string_array() const;
114 
116  static Parameter
117  from_parameter_msg(const rcl_interfaces::msg::Parameter & parameter);
118 
120  rcl_interfaces::msg::Parameter
121  to_parameter_msg() const;
122 
125  value_to_string() const;
126 
127 private:
128  std::string name_;
129  ParameterValue value_;
130 };
131 
135 _to_json_dict_entry(const Parameter & param);
136 
138 std::ostream &
139 operator<<(std::ostream & os, const rclcpp::Parameter & pv);
140 
142 std::ostream &
143 operator<<(std::ostream & os, const std::vector<Parameter> & parameters);
144 
145 } // namespace rclcpp
146 
147 namespace std
148 {
149 
153 to_string(const rclcpp::Parameter & param);
154 
158 to_string(const std::vector<rclcpp::Parameter> & parameters);
159 
160 } // namespace std
161 
162 #endif // RCLCPP__PARAMETER_HPP_
decltype(auto) get_value() const
Get value of parameter using rclcpp::ParameterType as template argument.
Definition: parameter.hpp:66
const std::string & get_name() const
std::enable_if< type==ParameterType::PARAMETER_BOOL, bool >::type get() const
Definition: parameter_value.hpp:136
Store the type and value of a parameter.
Definition: parameter_value.hpp:70
rcl_interfaces::msg::ParameterValue get_value_message() const
bool as_bool() const
const std::vector< bool > & as_bool_array() const
T to_string(T... args)
Definition: allocator_common.hpp:24
const std::vector< double > & as_double_array() const
Structure to store an arbitrary parameter with templated get/set methods.
Definition: parameter.hpp:32
double as_double() const
Parameter(const std::string &name, ValueTypeT value)
Definition: parameter.hpp:42
const std::vector< uint8_t > & as_byte_array() const
ParameterType
Definition: parameter_value.hpp:31
static Parameter from_parameter_msg(const rcl_interfaces::msg::Parameter &parameter)
rcl_interfaces::msg::Parameter to_parameter_msg() const
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
ParameterType get_type() const
int64_t as_int() const
std::ostream & operator<<(std::ostream &os, const rclcpp::Parameter &pv)
std::string _to_json_dict_entry(const Parameter &param)
Return a json encoded version of the parameter intended for a dict.
const std::vector< std::string > & as_string_array() const
const std::string & as_string() const
std::string value_to_string() const
const std::vector< int64_t > & as_integer_array() const
std::string get_type_name() const