Skip to content

Commit 2cb890e

Browse files
committed
Initialize params from yaml files
1 parent 97a5e3f commit 2cb890e

1 file changed

Lines changed: 87 additions & 2 deletions

File tree

rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp

Lines changed: 87 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,8 @@
1414

1515
#include "rclcpp/node_interfaces/node_parameters.hpp"
1616

17+
#include <rcl_yaml_param_parser/parser.h>
18+
1719
#include <map>
1820
#include <memory>
1921
#include <string>
@@ -22,6 +24,7 @@
2224

2325
#include "rcl_interfaces/srv/list_parameters.hpp"
2426
#include "rclcpp/create_publisher.hpp"
27+
#include "rclcpp/parameter_map.hpp"
2528
#include "rcutils/logging_macros.h"
2629
#include "rmw/qos_profiles.h"
2730

@@ -52,10 +55,92 @@ NodeParameters::NodeParameters(
5255
use_intra_process,
5356
allocator);
5457

58+
// Get the node options
59+
const rcl_node_t * node = node_base->get_rcl_node_handle();
60+
if (NULL == node) {
61+
throw std::runtime_error("Need valid node handle in NodeParameters");
62+
}
63+
const rcl_node_options_t * options = rcl_node_get_options(node);
64+
if (NULL == options) {
65+
throw std::runtime_error("Need valid node options NodeParameters");
66+
}
67+
68+
// Get paths to yaml files containing initial parameter values
69+
std::vector<std::string> yaml_paths;
70+
71+
auto get_yaml_paths = [&yaml_paths, &options] (const rcl_arguments_t * args) {
72+
int num_yaml_files = rcl_arguments_get_param_files_count(args);
73+
if (num_yaml_files > 0) {
74+
char ** param_files;
75+
rcl_ret_t ret = rcl_arguments_get_param_files(args, options->allocator, &param_files);
76+
if (RCL_RET_OK != ret) {
77+
rclcpp::exceptions::throw_from_rcl_error(ret);
78+
}
79+
for (int i = 0; i < num_yaml_files; ++i) {
80+
yaml_paths.emplace_back(param_files[i]);
81+
}
82+
}
83+
};
84+
85+
// global before local so that local overwrites global
86+
if (options->use_global_arguments) {
87+
get_yaml_paths(rcl_get_global_arguments());
88+
}
89+
get_yaml_paths(&(options->arguments));
90+
91+
// Get fully qualified node name post-remapping to use to find node's params in yaml files
92+
const std::string node_name = node_base->get_name();
93+
const std::string node_namespace = node_base->get_namespace();
94+
if (0u == node_namespace.size() || 0u == node_name.size()) {
95+
// Should never happen
96+
throw std::runtime_error("Node name and namespace were not set");
97+
}
98+
std::string combined_name;
99+
if ('/' == node_namespace.at(node_namespace.size() - 1)) {
100+
combined_name = node_namespace + node_name;
101+
} else {
102+
combined_name = node_namespace + '/' + node_name;
103+
}
104+
105+
std::map<std::string, rclcpp::Parameter> parameters;
106+
107+
// TODO(sloretz) rcl too parse yaml when circular dependency is solved
108+
for (const std::string & yaml_path : yaml_paths) {
109+
rcl_params_t * yaml_params = rcl_yaml_node_struct_init(options->allocator);
110+
if (NULL == yaml_params) {
111+
throw std::runtime_error("Failed to initialize yaml params struct");
112+
}
113+
if (!rcl_parse_yaml_file(yaml_path.c_str(), yaml_params)) {
114+
throw std::runtime_error("Failed to parse parameters " + yaml_path);
115+
}
116+
117+
rclcpp::ParameterMap initial_map = rclcpp::parameter_map_from(yaml_params);
118+
auto iter = initial_map.find(combined_name);
119+
if (initial_map.end() == iter) {
120+
continue;
121+
}
122+
123+
// Combind parameter yaml files, overwriting values in older ones
124+
for (auto & param : iter->second) {
125+
parameters[param.get_name()] = param;
126+
}
127+
}
128+
129+
// initial values passed to constructor overwrite yaml file sources
130+
for (auto & param : initial_values) {
131+
parameters[param.get_name()] = param;
132+
}
133+
134+
std::vector<rclcpp::Parameter> combined_values;
135+
combined_values.reserve(parameters.size());
136+
for (auto & kv : parameters) {
137+
combined_values.emplace_back(kv.second);
138+
}
139+
55140
// TODO(sloretz) store initial values and use them when a parameter is created
56141
// Set initial parameter values
57-
if (!initial_values.empty()) {
58-
rcl_interfaces::msg::SetParametersResult result = set_parameters_atomically(initial_values);
142+
if (!combined_values.empty()) {
143+
rcl_interfaces::msg::SetParametersResult result = set_parameters_atomically(combined_values);
59144
if (!result.successful) {
60145
throw std::runtime_error("Failed to set initial parameters");
61146
}

0 commit comments

Comments
 (0)