3131#include " ../../mocking_utils/patch.hpp"
3232#include " ../../utils/rclcpp_gtest_macros.hpp"
3333
34+ #include " rcpputils/filesystem_helper.hpp"
35+
3436class TestNodeParameters : public ::testing::Test
3537{
3638public:
@@ -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
5760protected:
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
6267TEST_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+ }
0 commit comments