ROS 2 rclcpp + rcl - rolling  rolling-a919a6e5
ROS 2 C++ Client Library with ROS Client Library
parameter.cpp
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 #include "rclcpp/parameter.hpp"
16 
17 #include <ostream>
18 #include <sstream>
19 #include <string>
20 #include <vector>
21 
22 #include "rclcpp/node_interfaces/node_parameters.hpp"
23 #include "rclcpp/utilities.hpp"
24 
25 using rclcpp::ParameterType;
26 using rclcpp::Parameter;
27 
28 Parameter::Parameter()
29 : name_("")
30 {
31 }
32 
33 Parameter::Parameter(const std::string & name)
34 : name_(name), value_()
35 {
36 }
37 
38 Parameter::Parameter(const std::string & name, const rclcpp::ParameterValue & value)
39 : name_(name), value_(value)
40 {
41 }
42 
44 : Parameter(parameter_info.descriptor.name, parameter_info.value)
45 {
46 }
47 
48 bool
49 Parameter::operator==(const Parameter & rhs) const
50 {
51  return this->name_ == rhs.name_ && this->value_ == rhs.value_;
52 }
53 
54 bool
55 Parameter::operator!=(const Parameter & rhs) const
56 {
57  return !(*this == rhs);
58 }
59 
60 ParameterType
62 {
63  return value_.get_type();
64 }
65 
66 std::string
68 {
69  return rclcpp::to_string(get_type());
70 }
71 
72 const std::string &
74 {
75  return name_;
76 }
77 
78 rcl_interfaces::msg::ParameterValue
80 {
81  return value_.to_value_msg();
82 }
83 
86 {
87  return value_;
88 }
89 
90 bool
92 {
93  return get_value<ParameterType::PARAMETER_BOOL>();
94 }
95 
96 int64_t
98 {
99  return get_value<ParameterType::PARAMETER_INTEGER>();
100 }
101 
102 double
104 {
105  return get_value<ParameterType::PARAMETER_DOUBLE>();
106 }
107 
108 const std::string &
110 {
111  return get_value<ParameterType::PARAMETER_STRING>();
112 }
113 
114 const std::vector<uint8_t> &
116 {
117  return get_value<ParameterType::PARAMETER_BYTE_ARRAY>();
118 }
119 
120 const std::vector<bool> &
122 {
123  return get_value<ParameterType::PARAMETER_BOOL_ARRAY>();
124 }
125 
126 const std::vector<int64_t> &
128 {
129  return get_value<ParameterType::PARAMETER_INTEGER_ARRAY>();
130 }
131 
132 const std::vector<double> &
134 {
135  return get_value<ParameterType::PARAMETER_DOUBLE_ARRAY>();
136 }
137 
138 const std::vector<std::string> &
140 {
141  return get_value<ParameterType::PARAMETER_STRING_ARRAY>();
142 }
143 
144 Parameter
145 Parameter::from_parameter_msg(const rcl_interfaces::msg::Parameter & parameter)
146 {
147  return Parameter(parameter.name, parameter.value);
148 }
149 
150 rcl_interfaces::msg::Parameter
152 {
153  rcl_interfaces::msg::Parameter parameter;
154  parameter.name = name_;
155  parameter.value = value_.to_value_msg();
156  return parameter;
157 }
158 
159 std::string
161 {
162  return rclcpp::to_string(value_);
163 }
164 
165 std::string
167 {
168  std::stringstream ss;
169  ss << "\"" << param.get_name() << "\": ";
170  ss << "{\"type\": \"" << param.get_type_name() << "\", ";
171  ss << "\"value\": \"" << param.value_to_string() << "\"}";
172  return ss.str();
173 }
174 
175 std::ostream &
176 rclcpp::operator<<(std::ostream & os, const rclcpp::Parameter & pv)
177 {
178  os << std::to_string(pv);
179  return os;
180 }
181 
182 std::ostream &
183 rclcpp::operator<<(std::ostream & os, const std::vector<Parameter> & parameters)
184 {
185  os << std::to_string(parameters);
186  return os;
187 }
188 
189 std::string
190 std::to_string(const rclcpp::Parameter & param)
191 {
192  std::stringstream ss;
193  ss << "{\"name\": \"" << param.get_name() << "\", ";
194  ss << "\"type\": \"" << param.get_type_name() << "\", ";
195  ss << "\"value\": \"" << param.value_to_string() << "\"}";
196  return ss.str();
197 }
198 
199 std::string
200 std::to_string(const std::vector<rclcpp::Parameter> & parameters)
201 {
202  std::stringstream ss;
203  ss << "{";
204  bool first = true;
205  for (const auto & pv : parameters) {
206  if (first == false) {
207  ss << ", ";
208  } else {
209  first = false;
210  }
211  ss << rclcpp::_to_json_dict_entry(pv);
212  }
213  ss << "}";
214  return ss.str();
215 }
Store the type and value of a parameter.
RCLCPP_PUBLIC rcl_interfaces::msg::ParameterValue to_value_msg() const
Return a message populated with the parameter value.
RCLCPP_PUBLIC ParameterType get_type() const
Return an enum indicating the type of the set value.
Structure to store an arbitrary parameter with templated get/set methods.
Definition: parameter.hpp:53
RCLCPP_PUBLIC const std::vector< bool > & as_bool_array() const
Get value of parameter as bool array (vector<bool>).
Definition: parameter.cpp:121
static RCLCPP_PUBLIC Parameter from_parameter_msg(const rcl_interfaces::msg::Parameter &parameter)
Convert a parameter message in a Parameter class object.
Definition: parameter.cpp:145
RCLCPP_PUBLIC const std::string & as_string() const
Get value of parameter as string.
Definition: parameter.cpp:109
RCLCPP_PUBLIC int64_t as_int() const
Get value of parameter as integer.
Definition: parameter.cpp:97
RCLCPP_PUBLIC const std::vector< double > & as_double_array() const
Get value of parameter as double array (vector<double>).
Definition: parameter.cpp:133
RCLCPP_PUBLIC std::string get_type_name() const
Get the type name of the parameter.
Definition: parameter.cpp:67
RCLCPP_PUBLIC const std::vector< uint8_t > & as_byte_array() const
Get value of parameter as byte array (vector<uint8_t>).
Definition: parameter.cpp:115
RCLCPP_PUBLIC Parameter()
Construct with an empty name and a parameter value of type rclcpp::PARAMETER_NOT_SET.
Definition: parameter.cpp:28
RCLCPP_PUBLIC rcl_interfaces::msg::Parameter to_parameter_msg() const
Convert the class in a parameter message.
Definition: parameter.cpp:151
RCLCPP_PUBLIC bool operator!=(const Parameter &rhs) const
Not equal operator.
Definition: parameter.cpp:55
RCLCPP_PUBLIC const std::string & get_name() const
Get the name of the parameter.
Definition: parameter.cpp:73
RCLCPP_PUBLIC std::string value_to_string() const
Get value of parameter as a string.
Definition: parameter.cpp:160
RCLCPP_PUBLIC const std::vector< int64_t > & as_integer_array() const
Get value of parameter as integer array (vector<int64_t>).
Definition: parameter.cpp:127
RCLCPP_PUBLIC const rclcpp::ParameterValue & get_parameter_value() const
Get the internal storage for the parameter value.
Definition: parameter.cpp:85
RCLCPP_PUBLIC ParameterType get_type() const
Get the type of the parameter.
Definition: parameter.cpp:61
RCLCPP_PUBLIC rcl_interfaces::msg::ParameterValue get_value_message() const
Get value of parameter as a parameter message.
Definition: parameter.cpp:79
RCLCPP_PUBLIC double as_double() const
Get value of parameter as double.
Definition: parameter.cpp:103
RCLCPP_PUBLIC const std::vector< std::string > & as_string_array() const
Get value of parameter as string array (vector<std::string>).
Definition: parameter.cpp:139
RCLCPP_PUBLIC bool operator==(const Parameter &rhs) const
Equal operator.
Definition: parameter.cpp:49
RCLCPP_PUBLIC bool as_bool() const
Get value of parameter as boolean.
Definition: parameter.cpp:91
RCLCPP_PUBLIC std::string to_string(const FutureReturnCode &future_return_code)
String conversion function for FutureReturnCode.
RCLCPP_PUBLIC std::ostream & operator<<(std::ostream &os, const FutureReturnCode &future_return_code)
Stream operator for FutureReturnCode.
RCLCPP_PUBLIC std::string _to_json_dict_entry(const Parameter &param)
Return a json encoded version of the parameter intended for a dict.
Definition: parameter.cpp:166