diff --git a/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp b/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp index 009c06a548..6a946a6959 100644 --- a/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp +++ b/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp @@ -260,8 +260,6 @@ __check_parameters( for (const rclcpp::Parameter & parameter : parameters) { const rcl_interfaces::msg::ParameterDescriptor & descriptor = parameter_infos[parameter.get_name()].descriptor; - result = descriptor.type == parameter.get_type() || - descriptor.type == rclcpp::PARAMETER_NOT_SET; result = result && __check_parameter_value_in_range( descriptor, parameter.get_parameter_value()); @@ -295,8 +293,7 @@ __set_parameters_atomically_common( if (result.successful) { for (size_t i = 0; i < parameters.size(); ++i) { const std::string & name = parameters[i].get_name(); - // TODO(ivanpauno): Why updating the descriptor name in each set? - // Maybe, set the correct name when declare parameter is call, and delete it here. + parameter_infos[name].descriptor.type = parameters[i].get_type(); parameter_infos[name].descriptor.name = parameters[i].get_name(); parameter_infos[name].value = parameters[i].get_parameter_value(); } diff --git a/rclcpp/test/test_node.cpp b/rclcpp/test/test_node.cpp index 7850857304..ded6f4f3b9 100644 --- a/rclcpp/test/test_node.cpp +++ b/rclcpp/test/test_node.cpp @@ -699,7 +699,6 @@ TEST_F(TestNode, set_parameter_undeclared_parameters_not_allowed) { // setting a parameter with integer range descriptor auto name = "parameter"_unq; rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rclcpp::PARAMETER_INTEGER; descriptor.integer_range.resize(1); auto & integer_range = descriptor.integer_range.at(0); integer_range.from_value = 10; @@ -726,7 +725,6 @@ TEST_F(TestNode, set_parameter_undeclared_parameters_not_allowed) { // setting a parameter with integer range descriptor and wrong default value will throw auto name = "parameter"_unq; rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rclcpp::PARAMETER_INTEGER; descriptor.integer_range.resize(1); auto & integer_range = descriptor.integer_range.at(0); integer_range.from_value = 10; @@ -735,10 +733,9 @@ TEST_F(TestNode, set_parameter_undeclared_parameters_not_allowed) { ASSERT_THROW(node->declare_parameter(name, 42, descriptor), rclcpp::exceptions::InvalidParameterValueException); } { - // setting a parameter with floatin point range descriptor + // setting a parameter with floating point range descriptor auto name = "parameter"_unq; rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rclcpp::PARAMETER_DOUBLE; descriptor.floating_point_range.resize(1); auto & floating_point_range = descriptor.floating_point_range.at(0); floating_point_range.from_value = 10.0; @@ -762,8 +759,8 @@ TEST_F(TestNode, set_parameter_undeclared_parameters_not_allowed) { EXPECT_EQ(node->get_parameter(name).get_value(), 11.0); } { - // setting a parameter with a different type will fail if - // it has a descriptor specifying a type + // setting a parameter with a different type is still possible + // when having a descriptor specifying a type (type is a status, not a constraint). auto name = "parameter"_unq; rcl_interfaces::msg::ParameterDescriptor descriptor; descriptor.type = rclcpp::PARAMETER_INTEGER; @@ -773,12 +770,11 @@ TEST_F(TestNode, set_parameter_undeclared_parameters_not_allowed) { EXPECT_EQ(value.get_type(), rclcpp::PARAMETER_INTEGER); EXPECT_EQ(value.get_value(), 42); - EXPECT_FALSE(node->set_parameter(rclcpp::Parameter(name, "asd")).successful); - + EXPECT_TRUE(node->set_parameter(rclcpp::Parameter(name, "asd")).successful); EXPECT_TRUE(node->has_parameter(name)); value = node->get_parameter(name); - EXPECT_EQ(value.get_type(), rclcpp::PARAMETER_INTEGER); - EXPECT_EQ(value.get_value(), 42); + EXPECT_EQ(value.get_type(), rclcpp::PARAMETER_STRING); + EXPECT_EQ(value.get_value(), "asd"); } }