Skip to content

Commit 6dd3a03

Browse files
Chen Lihuirpaaron
andauthored
use regex for wildcard matching (#1839)
* use regex for wildcard matching Co-authored-by: Aaron Lipinski <aaron.lipinski@roboticsplus.co.nz> Signed-off-by: Chen Lihui <lihui.chen@sony.com> * use map to process the content of parameter file by order Signed-off-by: Chen Lihui <lihui.chen@sony.com> * add more test cases Signed-off-by: Chen Lihui <lihui.chen@sony.com> * try to not decrease the performance and make the param win last Signed-off-by: Chen Lihui <lihui.chen@sony.com> * update node name Signed-off-by: Chen Lihui <lihui.chen@sony.com> * update document comment Signed-off-by: Chen Lihui <lihui.chen@sony.com> * add more test for parameter_map_from Signed-off-by: Chen Lihui <lihui.chen@sony.com> Co-authored-by: Aaron Lipinski <aaron.lipinski@roboticsplus.co.nz>
1 parent 33dae5d commit 6dd3a03

8 files changed

Lines changed: 364 additions & 13 deletions

File tree

rclcpp/include/rclcpp/parameter_map.hpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -35,11 +35,13 @@ using ParameterMap = std::unordered_map<std::string, std::vector<Parameter>>;
3535

3636
/// Convert parameters from rcl_yaml_param_parser into C++ class instances.
3737
/// \param[in] c_params C structures containing parameters for multiple nodes.
38+
/// \param[in] node_fqn a Fully Qualified Name of node, default value is nullptr.
39+
/// If it's not nullptr, return the relative node parameters belonging to this node_fqn.
3840
/// \returns a map where the keys are fully qualified node names and values a list of parameters.
3941
/// \throws InvalidParametersException if the `rcl_params_t` is inconsistent or invalid.
4042
RCLCPP_PUBLIC
4143
ParameterMap
42-
parameter_map_from(const rcl_params_t * const c_params);
44+
parameter_map_from(const rcl_params_t * const c_params, const char * node_fqn = nullptr);
4345

4446
/// Convert parameter value from rcl_yaml_param_parser into a C++ class instance.
4547
/// \param[in] c_value C structure containing a value of a parameter.

rclcpp/src/rclcpp/detail/resolve_parameter_overrides.cpp

Lines changed: 6 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -51,18 +51,13 @@ rclcpp::detail::resolve_parameter_overrides(
5151
[params]() {
5252
rcl_yaml_node_struct_fini(params);
5353
});
54-
rclcpp::ParameterMap initial_map = rclcpp::parameter_map_from(params);
54+
rclcpp::ParameterMap initial_map = rclcpp::parameter_map_from(params, node_fqn.c_str());
5555

56-
// Enforce wildcard matching precedence
57-
// TODO(cottsay) implement further wildcard matching
58-
const std::array<std::string, 2> node_matching_names{"/**", node_fqn};
59-
for (const auto & node_name : node_matching_names) {
60-
if (initial_map.count(node_name) > 0) {
61-
// Combine parameter yaml files, overwriting values in older ones
62-
for (const rclcpp::Parameter & param : initial_map.at(node_name)) {
63-
result[param.get_name()] =
64-
rclcpp::ParameterValue(param.get_value_message());
65-
}
56+
if (initial_map.count(node_fqn) > 0) {
57+
// Combine parameter yaml files, overwriting values in older ones
58+
for (const rclcpp::Parameter & param : initial_map.at(node_fqn)) {
59+
result[param.get_name()] =
60+
rclcpp::ParameterValue(param.get_value_message());
6661
}
6762
}
6863
}

rclcpp/src/rclcpp/parameter_map.cpp

Lines changed: 15 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -13,8 +13,10 @@
1313
// limitations under the License.
1414

1515
#include <string>
16+
#include <regex>
1617
#include <vector>
1718

19+
#include "rcpputils/find_and_replace.hpp"
1820
#include "rclcpp/parameter_map.hpp"
1921

2022
using rclcpp::exceptions::InvalidParametersException;
@@ -23,7 +25,7 @@ using rclcpp::ParameterMap;
2325
using rclcpp::ParameterValue;
2426

2527
ParameterMap
26-
rclcpp::parameter_map_from(const rcl_params_t * const c_params)
28+
rclcpp::parameter_map_from(const rcl_params_t * const c_params, const char * node_fqn)
2729
{
2830
if (NULL == c_params) {
2931
throw InvalidParametersException("parameters struct is NULL");
@@ -49,6 +51,17 @@ rclcpp::parameter_map_from(const rcl_params_t * const c_params)
4951
node_name = c_node_name;
5052
}
5153

54+
if (node_fqn) {
55+
// Update the regular expression ["/*" -> "(/\\w+)" and "/**" -> "(/\\w+)*"]
56+
std::string regex = rcpputils::find_and_replace(node_name, "/*", "(/\\w+)");
57+
if (!std::regex_match(node_fqn, std::regex(regex))) {
58+
// No need to parse the items because the user just care about node_fqn
59+
continue;
60+
}
61+
62+
node_name = node_fqn;
63+
}
64+
5265
const rcl_node_params_t * const c_params_node = &(c_params->params[n]);
5366

5467
std::vector<Parameter> & params_node = parameters[node_name];
@@ -65,6 +78,7 @@ rclcpp::parameter_map_from(const rcl_params_t * const c_params)
6578
params_node.emplace_back(c_param_name, parameter_value_from(c_param_value));
6679
}
6780
}
81+
6882
return parameters;
6983
}
7084

rclcpp/test/rclcpp/node_interfaces/test_node_parameters.cpp

Lines changed: 132 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -31,6 +31,8 @@
3131
#include "../../mocking_utils/patch.hpp"
3232
#include "../../utils/rclcpp_gtest_macros.hpp"
3333

34+
#include "rcpputils/filesystem_helper.hpp"
35+
3436
class TestNodeParameters : public ::testing::Test
3537
{
3638
public:
@@ -47,6 +49,7 @@ class TestNodeParameters : public ::testing::Test
4749
dynamic_cast<rclcpp::node_interfaces::NodeParameters *>(
4850
node->get_node_parameters_interface().get());
4951
ASSERT_NE(nullptr, node_parameters);
52+
test_resources_path /= "test_node_parameters";
5053
}
5154

5255
void TearDown()
@@ -57,6 +60,8 @@ class TestNodeParameters : public ::testing::Test
5760
protected:
5861
std::shared_ptr<rclcpp::Node> node;
5962
rclcpp::node_interfaces::NodeParameters * node_parameters;
63+
64+
rcpputils::fs::path test_resources_path{TEST_RESOURCES_DIRECTORY};
6065
};
6166

6267
TEST_F(TestNodeParameters, construct_destruct_rcl_errors) {
@@ -199,3 +204,130 @@ TEST_F(TestNodeParameters, add_remove_parameters_callback) {
199204
node_parameters->remove_on_set_parameters_callback(handle.get()),
200205
std::runtime_error("Callback doesn't exist"));
201206
}
207+
208+
TEST_F(TestNodeParameters, wildcard_with_namespace)
209+
{
210+
rclcpp::NodeOptions opts;
211+
opts.arguments(
212+
{
213+
"--ros-args",
214+
"--params-file", (test_resources_path / "wildcards.yaml").string()
215+
});
216+
217+
std::shared_ptr<rclcpp::Node> node = std::make_shared<rclcpp::Node>("node2", "ns", opts);
218+
219+
auto * node_parameters =
220+
dynamic_cast<rclcpp::node_interfaces::NodeParameters *>(
221+
node->get_node_parameters_interface().get());
222+
ASSERT_NE(nullptr, node_parameters);
223+
224+
const auto & parameter_overrides = node_parameters->get_parameter_overrides();
225+
EXPECT_EQ(7u, parameter_overrides.size());
226+
EXPECT_EQ(parameter_overrides.at("full_wild").get<std::string>(), "full_wild");
227+
EXPECT_EQ(parameter_overrides.at("namespace_wild").get<std::string>(), "namespace_wild");
228+
EXPECT_EQ(
229+
parameter_overrides.at("namespace_wild_another").get<std::string>(),
230+
"namespace_wild_another");
231+
EXPECT_EQ(
232+
parameter_overrides.at("namespace_wild_one_star").get<std::string>(),
233+
"namespace_wild_one_star");
234+
EXPECT_EQ(parameter_overrides.at("node_wild_in_ns").get<std::string>(), "node_wild_in_ns");
235+
EXPECT_EQ(
236+
parameter_overrides.at("node_wild_in_ns_another").get<std::string>(),
237+
"node_wild_in_ns_another");
238+
EXPECT_EQ(parameter_overrides.at("explicit_in_ns").get<std::string>(), "explicit_in_ns");
239+
EXPECT_EQ(parameter_overrides.count("should_not_appear"), 0u);
240+
}
241+
242+
TEST_F(TestNodeParameters, wildcard_no_namespace)
243+
{
244+
rclcpp::NodeOptions opts;
245+
opts.arguments(
246+
{
247+
"--ros-args",
248+
"--params-file", (test_resources_path / "wildcards.yaml").string()
249+
});
250+
251+
std::shared_ptr<rclcpp::Node> node = std::make_shared<rclcpp::Node>("node2", opts);
252+
253+
auto * node_parameters =
254+
dynamic_cast<rclcpp::node_interfaces::NodeParameters *>(
255+
node->get_node_parameters_interface().get());
256+
ASSERT_NE(nullptr, node_parameters);
257+
258+
const auto & parameter_overrides = node_parameters->get_parameter_overrides();
259+
EXPECT_EQ(5u, parameter_overrides.size());
260+
EXPECT_EQ(parameter_overrides.at("full_wild").get<std::string>(), "full_wild");
261+
EXPECT_EQ(parameter_overrides.at("namespace_wild").get<std::string>(), "namespace_wild");
262+
EXPECT_EQ(
263+
parameter_overrides.at("namespace_wild_another").get<std::string>(),
264+
"namespace_wild_another");
265+
EXPECT_EQ(parameter_overrides.at("node_wild_no_ns").get<std::string>(), "node_wild_no_ns");
266+
EXPECT_EQ(parameter_overrides.at("explicit_no_ns").get<std::string>(), "explicit_no_ns");
267+
EXPECT_EQ(parameter_overrides.count("should_not_appear"), 0u);
268+
// "/*" match exactly one token, not expect to get `namespace_wild_one_star`
269+
EXPECT_EQ(parameter_overrides.count("namespace_wild_one_star"), 0u);
270+
}
271+
272+
TEST_F(TestNodeParameters, params_by_order)
273+
{
274+
rclcpp::NodeOptions opts;
275+
opts.arguments(
276+
{
277+
"--ros-args",
278+
"--params-file", (test_resources_path / "params_by_order.yaml").string()
279+
});
280+
281+
std::shared_ptr<rclcpp::Node> node = std::make_shared<rclcpp::Node>("node2", "ns", opts);
282+
283+
auto * node_parameters =
284+
dynamic_cast<rclcpp::node_interfaces::NodeParameters *>(
285+
node->get_node_parameters_interface().get());
286+
ASSERT_NE(nullptr, node_parameters);
287+
288+
const auto & parameter_overrides = node_parameters->get_parameter_overrides();
289+
EXPECT_EQ(3u, parameter_overrides.size());
290+
EXPECT_EQ(parameter_overrides.at("a_value").get<std::string>(), "last_one_win");
291+
EXPECT_EQ(parameter_overrides.at("foo").get<std::string>(), "foo");
292+
EXPECT_EQ(parameter_overrides.at("bar").get<std::string>(), "bar");
293+
}
294+
295+
TEST_F(TestNodeParameters, complicated_wildcards)
296+
{
297+
rclcpp::NodeOptions opts;
298+
opts.arguments(
299+
{
300+
"--ros-args",
301+
"--params-file", (test_resources_path / "complicated_wildcards.yaml").string()
302+
});
303+
304+
{
305+
// regex matched: /**/foo/*/bar
306+
std::shared_ptr<rclcpp::Node> node =
307+
std::make_shared<rclcpp::Node>("node2", "/a/b/c/foo/d/bar", opts);
308+
309+
auto * node_parameters =
310+
dynamic_cast<rclcpp::node_interfaces::NodeParameters *>(
311+
node->get_node_parameters_interface().get());
312+
ASSERT_NE(nullptr, node_parameters);
313+
314+
const auto & parameter_overrides = node_parameters->get_parameter_overrides();
315+
EXPECT_EQ(2u, parameter_overrides.size());
316+
EXPECT_EQ(parameter_overrides.at("foo").get<std::string>(), "foo");
317+
EXPECT_EQ(parameter_overrides.at("bar").get<std::string>(), "bar");
318+
}
319+
320+
{
321+
// regex not matched: /**/foo/*/bar
322+
std::shared_ptr<rclcpp::Node> node =
323+
std::make_shared<rclcpp::Node>("node2", "/a/b/c/foo/bar", opts);
324+
325+
auto * node_parameters =
326+
dynamic_cast<rclcpp::node_interfaces::NodeParameters *>(
327+
node->get_node_parameters_interface().get());
328+
ASSERT_NE(nullptr, node_parameters);
329+
330+
const auto & parameter_overrides = node_parameters->get_parameter_overrides();
331+
EXPECT_EQ(0u, parameter_overrides.size());
332+
}
333+
}

rclcpp/test/rclcpp/test_parameter_map.cpp

Lines changed: 130 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919

2020
#include <cstdio>
2121
#include <string>
22+
#include <unordered_map>
2223
#include <vector>
2324

2425
#include "rclcpp/parameter_map.hpp"
@@ -353,3 +354,132 @@ TEST(Test_parameter_map_from, string_array_param_value)
353354
c_params->params[0].parameter_values[0].string_array_value = NULL;
354355
rcl_yaml_node_struct_fini(c_params);
355356
}
357+
358+
TEST(Test_parameter_map_from, one_node_one_param_by_node_fqn)
359+
{
360+
rcl_params_t * c_params = make_params({"foo"});
361+
make_node_params(c_params, 0, {"string_param"});
362+
363+
std::string hello_world = "hello world";
364+
char * c_hello_world = new char[hello_world.length() + 1];
365+
std::snprintf(c_hello_world, hello_world.size() + 1, "%s", hello_world.c_str());
366+
c_params->params[0].parameter_values[0].string_value = c_hello_world;
367+
368+
rclcpp::ParameterMap map = rclcpp::parameter_map_from(c_params, "/foo");
369+
const std::vector<rclcpp::Parameter> & params = map.at("/foo");
370+
EXPECT_STREQ("string_param", params.at(0).get_name().c_str());
371+
EXPECT_STREQ(hello_world.c_str(), params.at(0).get_value<std::string>().c_str());
372+
373+
c_params->params[0].parameter_values[0].string_value = NULL;
374+
delete[] c_hello_world;
375+
rcl_yaml_node_struct_fini(c_params);
376+
}
377+
378+
TEST(Test_parameter_map_from, multi_nodes_same_param_name_by_node_fqn)
379+
{
380+
std::vector<std::string> node_names_keys = {
381+
"/**", // index: 0
382+
"/*", // index: 1
383+
"/**/node", // index: 2
384+
"/*/node", // index: 3
385+
"/ns/node" // index: 4
386+
};
387+
388+
rcl_params_t * c_params = make_params(node_names_keys);
389+
390+
std::vector<char *> param_values;
391+
for (size_t i = 0; i < node_names_keys.size(); ++i) {
392+
make_node_params(c_params, i, {"string_param"});
393+
std::string hello_world = "hello world" + std::to_string(i);
394+
char * c_hello_world = new char[hello_world.length() + 1];
395+
std::snprintf(c_hello_world, hello_world.size() + 1, "%s", hello_world.c_str());
396+
c_params->params[i].parameter_values[0].string_value = c_hello_world;
397+
param_values.push_back(c_hello_world);
398+
}
399+
400+
std::unordered_map<std::string, std::vector<size_t>> node_fqn_expected = {
401+
{"/ns/foo/another_node", {0}},
402+
{"/another", {0, 1}},
403+
{"/node", {0, 1, 2}},
404+
{"/another_ns/node", {0, 2, 3}},
405+
{"/ns/node", {0, 2, 3, 4}},
406+
};
407+
408+
for (auto & kv : node_fqn_expected) {
409+
rclcpp::ParameterMap map = rclcpp::parameter_map_from(c_params, kv.first.c_str());
410+
const std::vector<rclcpp::Parameter> & params = map.at(kv.first);
411+
412+
EXPECT_EQ(kv.second.size(), params.size());
413+
for (size_t i = 0; i < params.size(); ++i) {
414+
std::string param_value = "hello world" + std::to_string(kv.second[i]);
415+
EXPECT_STREQ("string_param", params.at(i).get_name().c_str());
416+
EXPECT_STREQ(param_value.c_str(), params.at(i).get_value<std::string>().c_str());
417+
}
418+
}
419+
420+
for (size_t i = 0; i < node_names_keys.size(); ++i) {
421+
c_params->params[i].parameter_values[0].string_value = NULL;
422+
}
423+
for (auto c_hello_world : param_values) {
424+
delete[] c_hello_world;
425+
}
426+
rcl_yaml_node_struct_fini(c_params);
427+
}
428+
429+
TEST(Test_parameter_map_from, multi_nodes_diff_param_name_by_node_fqn)
430+
{
431+
std::vector<std::string> node_names_keys = {
432+
"/**", // index: 0
433+
"/*", // index: 1
434+
"/**/node", // index: 2
435+
"/*/node", // index: 3
436+
"/ns/**", // index: 4
437+
"/ns/*", // index: 5
438+
"/ns/**/node", // index: 6
439+
"/ns/*/node", // index: 7
440+
"/ns/**/a/*/node", // index: 8
441+
"/ns/node" // index: 9
442+
};
443+
444+
rcl_params_t * c_params = make_params(node_names_keys);
445+
446+
for (size_t i = 0; i < node_names_keys.size(); ++i) {
447+
std::string param_name = "string_param" + std::to_string(i);
448+
make_node_params(c_params, i, {param_name});
449+
}
450+
451+
std::string hello_world = "hello world";
452+
char * c_hello_world = new char[hello_world.length() + 1];
453+
std::snprintf(c_hello_world, hello_world.size() + 1, "%s", hello_world.c_str());
454+
455+
for (size_t i = 0; i < node_names_keys.size(); ++i) {
456+
c_params->params[i].parameter_values[0].string_value = c_hello_world;
457+
}
458+
459+
std::unordered_map<std::string, std::vector<size_t>> node_fqn_expected = {
460+
{"/ns/node", {0, 2, 3, 4, 5, 6, 9}},
461+
{"/node", {0, 1, 2}},
462+
{"/ns/foo/node", {0, 2, 4, 6, 7}},
463+
{"/ns/foo/a/node", {0, 2, 4, 6}},
464+
{"/ns/foo/a/bar/node", {0, 2, 4, 6, 8}},
465+
{"/ns/a/bar/node", {0, 2, 4, 6, 8}},
466+
{"/ns/foo/zoo/a/bar/node", {0, 2, 4, 6, 8}},
467+
};
468+
469+
for (auto & kv : node_fqn_expected) {
470+
rclcpp::ParameterMap map = rclcpp::parameter_map_from(c_params, kv.first.c_str());
471+
const std::vector<rclcpp::Parameter> & params = map.at(kv.first);
472+
EXPECT_EQ(kv.second.size(), params.size());
473+
for (size_t i = 0; i < params.size(); ++i) {
474+
std::string param_name = "string_param" + std::to_string(kv.second[i]);
475+
EXPECT_STREQ(param_name.c_str(), params.at(i).get_name().c_str());
476+
EXPECT_STREQ(hello_world.c_str(), params.at(i).get_value<std::string>().c_str());
477+
}
478+
}
479+
480+
for (size_t i = 0; i < node_names_keys.size(); ++i) {
481+
c_params->params[i].parameter_values[0].string_value = NULL;
482+
}
483+
delete[] c_hello_world;
484+
rcl_yaml_node_struct_fini(c_params);
485+
}
Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,5 @@
1+
/**/foo/*/bar:
2+
node2:
3+
ros__parameters:
4+
foo: "foo"
5+
bar: "bar"

0 commit comments

Comments
 (0)