|
14 | 14 |
|
15 | 15 | #include "rclcpp/node_interfaces/node_parameters.hpp"
|
16 | 16 |
|
| 17 | +#include <rcl_yaml_param_parser/parser.h> |
| 18 | + |
17 | 19 | #include <map>
|
18 | 20 | #include <memory>
|
19 | 21 | #include <string>
|
|
22 | 24 |
|
23 | 25 | #include "rcl_interfaces/srv/list_parameters.hpp"
|
24 | 26 | #include "rclcpp/create_publisher.hpp"
|
| 27 | +#include "rclcpp/parameter_map.hpp" |
| 28 | +#include "rclcpp/scope_exit.hpp" |
25 | 29 | #include "rcutils/logging_macros.h"
|
26 | 30 | #include "rmw/qos_profiles.h"
|
27 | 31 |
|
@@ -52,10 +56,100 @@ NodeParameters::NodeParameters(
|
52 | 56 | use_intra_process,
|
53 | 57 | allocator);
|
54 | 58 |
|
| 59 | + // Get the node options |
| 60 | + const rcl_node_t * node = node_base->get_rcl_node_handle(); |
| 61 | + if (nullptr == node) { |
| 62 | + throw std::runtime_error("Need valid node handle in NodeParameters"); |
| 63 | + } |
| 64 | + const rcl_node_options_t * options = rcl_node_get_options(node); |
| 65 | + if (nullptr == options) { |
| 66 | + throw std::runtime_error("Need valid node options NodeParameters"); |
| 67 | + } |
| 68 | + |
| 69 | + // Get paths to yaml files containing initial parameter values |
| 70 | + std::vector<std::string> yaml_paths; |
| 71 | + |
| 72 | + auto get_yaml_paths = [&yaml_paths, &options](const rcl_arguments_t * args) { |
| 73 | + int num_yaml_files = rcl_arguments_get_param_files_count(args); |
| 74 | + if (num_yaml_files > 0) { |
| 75 | + char ** param_files; |
| 76 | + rcl_ret_t ret = rcl_arguments_get_param_files(args, options->allocator, ¶m_files); |
| 77 | + if (RCL_RET_OK != ret) { |
| 78 | + rclcpp::exceptions::throw_from_rcl_error(ret); |
| 79 | + } |
| 80 | + auto cleanup_param_files = make_scope_exit( |
| 81 | + [¶m_files, &num_yaml_files, &options]() { |
| 82 | + for (int i = 0; i < num_yaml_files; ++i) { |
| 83 | + options->allocator.deallocate(param_files[i], options->allocator.state); |
| 84 | + } |
| 85 | + options->allocator.deallocate(param_files, options->allocator.state); |
| 86 | + }); |
| 87 | + for (int i = 0; i < num_yaml_files; ++i) { |
| 88 | + yaml_paths.emplace_back(param_files[i]); |
| 89 | + } |
| 90 | + } |
| 91 | + }; |
| 92 | + |
| 93 | + // global before local so that local overwrites global |
| 94 | + if (options->use_global_arguments) { |
| 95 | + get_yaml_paths(rcl_get_global_arguments()); |
| 96 | + } |
| 97 | + get_yaml_paths(&(options->arguments)); |
| 98 | + |
| 99 | + // Get fully qualified node name post-remapping to use to find node's params in yaml files |
| 100 | + const std::string node_name = node_base->get_name(); |
| 101 | + const std::string node_namespace = node_base->get_namespace(); |
| 102 | + if (0u == node_namespace.size() || 0u == node_name.size()) { |
| 103 | + // Should never happen |
| 104 | + throw std::runtime_error("Node name and namespace were not set"); |
| 105 | + } |
| 106 | + std::string combined_name; |
| 107 | + if ('/' == node_namespace.at(node_namespace.size() - 1)) { |
| 108 | + combined_name = node_namespace + node_name; |
| 109 | + } else { |
| 110 | + combined_name = node_namespace + '/' + node_name; |
| 111 | + } |
| 112 | + |
| 113 | + std::map<std::string, rclcpp::Parameter> parameters; |
| 114 | + |
| 115 | + // TODO(sloretz) use rcl to parse yaml when circular dependency is solved |
| 116 | + for (const std::string & yaml_path : yaml_paths) { |
| 117 | + rcl_params_t * yaml_params = rcl_yaml_node_struct_init(options->allocator); |
| 118 | + if (nullptr == yaml_params) { |
| 119 | + throw std::bad_alloc(); |
| 120 | + } |
| 121 | + if (!rcl_parse_yaml_file(yaml_path.c_str(), yaml_params)) { |
| 122 | + throw std::runtime_error("Failed to parse parameters " + yaml_path); |
| 123 | + } |
| 124 | + |
| 125 | + rclcpp::ParameterMap initial_map = rclcpp::parameter_map_from(yaml_params); |
| 126 | + rcl_yaml_node_struct_fini(yaml_params); |
| 127 | + auto iter = initial_map.find(combined_name); |
| 128 | + if (initial_map.end() == iter) { |
| 129 | + continue; |
| 130 | + } |
| 131 | + |
| 132 | + // Combine parameter yaml files, overwriting values in older ones |
| 133 | + for (auto & param : iter->second) { |
| 134 | + parameters[param.get_name()] = param; |
| 135 | + } |
| 136 | + } |
| 137 | + |
| 138 | + // initial values passed to constructor overwrite yaml file sources |
| 139 | + for (auto & param : initial_parameters) { |
| 140 | + parameters[param.get_name()] = param; |
| 141 | + } |
| 142 | + |
| 143 | + std::vector<rclcpp::Parameter> combined_values; |
| 144 | + combined_values.reserve(parameters.size()); |
| 145 | + for (auto & kv : parameters) { |
| 146 | + combined_values.emplace_back(kv.second); |
| 147 | + } |
| 148 | + |
55 | 149 | // TODO(sloretz) store initial values and use them when a parameter is created ros2/rclcpp#475
|
56 | 150 | // Set initial parameter values
|
57 |
| - if (!initial_parameters.empty()) { |
58 |
| - rcl_interfaces::msg::SetParametersResult result = set_parameters_atomically(initial_parameters); |
| 151 | + if (!combined_values.empty()) { |
| 152 | + rcl_interfaces::msg::SetParametersResult result = set_parameters_atomically(combined_values); |
59 | 153 | if (!result.successful) {
|
60 | 154 | throw std::runtime_error("Failed to set initial parameters");
|
61 | 155 | }
|
|
0 commit comments