19 #include "rcpputils/find_and_replace.hpp"
20 #include "rcpputils/scope_exit.hpp"
21 #include "rclcpp/parameter_map.hpp"
28 static bool is_node_name_matched(
const std::string & node_name,
const char * node_fqn)
31 std::string regex = rcpputils::find_and_replace(node_name,
"/*",
"(/\\w+)");
32 return std::regex_match(node_fqn, std::regex(regex));
38 if (NULL == c_params) {
40 }
else if (NULL == c_params->node_names) {
42 }
else if (NULL == c_params->params) {
48 for (
size_t n = 0; n < c_params->num_nodes; ++n) {
49 const char * c_node_name = c_params->node_names[n];
50 if (NULL == c_node_name) {
55 std::string node_name(
"/");
56 if (
'/' != c_node_name[0]) {
57 node_name += c_node_name;
59 node_name = c_node_name;
63 if (!is_node_name_matched(node_name, node_fqn)) {
71 const rcl_node_params_t *
const c_params_node = &(c_params->params[n]);
73 std::vector<Parameter> & params_node = parameters[node_name];
74 params_node.reserve(c_params_node->num_params);
76 for (
size_t p = 0; p < c_params_node->num_params; ++p) {
77 const char *
const c_param_name = c_params_node->parameter_names[p];
78 if (NULL == c_param_name) {
80 "At node " + std::to_string(n) +
" parameter " + std::to_string(p) +
" name is NULL");
83 const rcl_variant_t *
const c_param_value = &(c_params_node->parameter_values[p]);
89 std::string(
"parameter_value_from failed for parameter '") +
90 c_param_name +
"': " + e.what());
92 params_node.emplace_back(c_param_name, value);
102 if (NULL == c_param_value) {
105 if (c_param_value->bool_value) {
107 }
else if (c_param_value->integer_value) {
109 }
else if (c_param_value->double_value) {
111 }
else if (c_param_value->string_value) {
113 }
else if (c_param_value->byte_array_value) {
114 const rcl_byte_array_t *
const byte_array = c_param_value->byte_array_value;
115 std::vector<uint8_t> bytes;
116 bytes.reserve(byte_array->size);
117 for (
size_t v = 0; v < byte_array->size; ++v) {
118 bytes.push_back(byte_array->values[v]);
121 }
else if (c_param_value->bool_array_value) {
122 const rcl_bool_array_t *
const bool_array = c_param_value->bool_array_value;
123 std::vector<bool> bools;
124 bools.reserve(bool_array->size);
125 for (
size_t v = 0; v < bool_array->size; ++v) {
126 bools.push_back(bool_array->values[v]);
129 }
else if (c_param_value->integer_array_value) {
130 const rcl_int64_array_t *
const int_array = c_param_value->integer_array_value;
131 std::vector<int64_t> integers;
132 integers.reserve(int_array->size);
133 for (
size_t v = 0; v < int_array->size; ++v) {
134 integers.push_back(int_array->values[v]);
137 }
else if (c_param_value->double_array_value) {
138 const rcl_double_array_t *
const double_array = c_param_value->double_array_value;
139 std::vector<double> doubles;
140 doubles.reserve(double_array->size);
141 for (
size_t v = 0; v < double_array->size; ++v) {
142 doubles.push_back(double_array->values[v]);
145 }
else if (c_param_value->string_array_value) {
146 const rcutils_string_array_t *
const string_array = c_param_value->string_array_value;
147 std::vector<std::string> strings;
148 strings.reserve(string_array->size);
149 for (
size_t v = 0; v < string_array->size; ++v) {
150 strings.emplace_back(string_array->data[v]);
161 rcutils_allocator_t allocator = rcutils_get_default_allocator();
162 rcl_params_t * rcl_parameters = rcl_yaml_node_struct_init(allocator);
163 RCPPUTILS_SCOPE_EXIT(rcl_yaml_node_struct_fini(rcl_parameters); );
164 const char * path = yaml_filename.c_str();
165 if (!rcl_parse_yaml_file(path, rcl_parameters)) {
172 std::vector<rclcpp::Parameter>
175 std::vector<rclcpp::Parameter> parameters;
176 std::string node_name_old;
177 for (
auto & [node_name, node_parameters] : parameter_map) {
178 if (node_fqn && !is_node_name_matched(node_name, node_fqn)) {
182 parameters.insert(parameters.end(), node_parameters.begin(), node_parameters.end());
Store the type and value of a parameter.
Thrown if passed parameter value is invalid.
Thrown if passed parameters are inconsistent or invalid.
RCLCPP_PUBLIC ParameterMap parameter_map_from_yaml_file(const std::string &yaml_filename, const char *node_fqn=nullptr)
RCLCPP_PUBLIC std::vector< Parameter > parameters_from_map(const ParameterMap ¶meter_map, const char *node_fqn=nullptr)
RCLCPP_PUBLIC ParameterMap parameter_map_from(const rcl_params_t *const c_params, const char *node_fqn=nullptr)
RCLCPP_PUBLIC ParameterValue parameter_value_from(const rcl_variant_t *const c_value)
std::unordered_map< std::string, std::vector< Parameter > > ParameterMap
A map of fully qualified node names to a list of parameters.
#define RCL_RET_ERROR
Unspecified error return code.