@@ -409,6 +409,46 @@ TEST_F(TestNode, declare_parameter_with_no_initial_values) {
409409 }
410410}
411411
412+ TEST_F (TestNode, declare_parameter_with_allow_undeclared_parameters) {
413+ // test cases without initial values
414+ auto node = std::make_shared<rclcpp::Node>(
415+ " test_declare_parameter_node" _unq, " /" ,
416+ rclcpp::NodeOptions{}.allow_undeclared_parameters (true ));
417+ {
418+ // declared parameters static typing is still enforced
419+ auto param_name = " parameter" _unq;
420+ auto value = node->declare_parameter (param_name, 5 );
421+ EXPECT_EQ (value, 5 );
422+ EXPECT_FALSE (node->set_parameter ({param_name, " asd" }).successful );
423+ auto param = node->get_parameter (param_name);
424+ EXPECT_EQ (param.get_type (), rclcpp::PARAMETER_INTEGER);
425+ EXPECT_EQ (param.get_value <int64_t >(), 5 );
426+ }
427+ {
428+ // not for automatically declared parameters
429+ auto param_name = " parameter" _unq;
430+ EXPECT_TRUE (node->set_parameter ({param_name, 5 }).successful );
431+ auto param = node->get_parameter (param_name);
432+ EXPECT_EQ (param.get_type (), rclcpp::PARAMETER_INTEGER);
433+ EXPECT_EQ (param.get_value <int64_t >(), 5 );
434+ EXPECT_TRUE (node->set_parameter ({param_name, " asd" }).successful );
435+ param = node->get_parameter (param_name);
436+ EXPECT_EQ (param.get_type (), rclcpp::PARAMETER_STRING);
437+ EXPECT_EQ (param.get_value <std::string>(), " asd" );
438+ }
439+ {
440+ // declare after set is invalid
441+ auto param_name = " parameter" _unq;
442+ EXPECT_TRUE (node->set_parameter ({param_name, 5 }).successful );
443+ auto param = node->get_parameter (param_name);
444+ EXPECT_EQ (param.get_type (), rclcpp::PARAMETER_INTEGER);
445+ EXPECT_EQ (param.get_value <int64_t >(), 5 );
446+ EXPECT_THROW (
447+ node->declare_parameter (param_name, 5 ),
448+ rclcpp::exceptions::ParameterAlreadyDeclaredException);
449+ }
450+ }
451+
412452auto get_fixed_on_parameter_set_callback (const std::string & name, bool successful)
413453{
414454 return
0 commit comments