Skip to content
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
44 changes: 32 additions & 12 deletions rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -165,14 +165,13 @@ __are_doubles_equal(double x, double y, double ulp = 100.0)
return std::abs(x - y) <= std::numeric_limits<double>::epsilon() * std::abs(x + y) * ulp;
}

RCLCPP_LOCAL
inline
void
format_reason(std::string & reason, const std::string & name, const char * range_type)
static
std::string
format_range_reason(const std::string & name, const char * range_type)
{
std::ostringstream ss;
ss << "Parameter {" << name << "} doesn't comply with " << range_type << " range.";
reason = ss.str();
return ss.str();
}

RCLCPP_LOCAL
Expand All @@ -191,7 +190,7 @@ __check_parameter_value_in_range(
}
if ((v < integer_range.from_value) || (v > integer_range.to_value)) {
result.successful = false;
format_reason(result.reason, descriptor.name, "integer");
result.reason = format_range_reason(descriptor.name, "integer");
return result;
}
if (integer_range.step == 0) {
Expand All @@ -201,7 +200,7 @@ __check_parameter_value_in_range(
return result;
}
result.successful = false;
format_reason(result.reason, descriptor.name, "integer");
result.reason = format_range_reason(descriptor.name, "integer");
return result;
}

Expand All @@ -213,7 +212,7 @@ __check_parameter_value_in_range(
}
if ((v < fp_range.from_value) || (v > fp_range.to_value)) {
result.successful = false;
format_reason(result.reason, descriptor.name, "floating point");
result.reason = format_range_reason(descriptor.name, "floating point");
return result;
}
if (fp_range.step == 0.0) {
Expand All @@ -224,12 +223,23 @@ __check_parameter_value_in_range(
return result;
}
result.successful = false;
format_reason(result.reason, descriptor.name, "floating point");
result.reason = format_range_reason(descriptor.name, "floating point");
return result;
}
return result;
}

static
std::string
format_type_reason(
const std::string & name, const std::string & old_type, const std::string & new_type)
{
std::ostringstream ss;
ss << "Parameter {" << name << "} is of type {" << old_type << "}, setting it to {" <<
new_type << "} is not allowed.";
return ss.str();
}

// Return true if parameter values comply with the descriptors in parameter_infos.
RCLCPP_LOCAL
rcl_interfaces::msg::SetParametersResult
Expand All @@ -240,13 +250,23 @@ __check_parameters(
rcl_interfaces::msg::SetParametersResult result;
result.successful = true;
for (const rclcpp::Parameter & parameter : parameters) {
const rcl_interfaces::msg::ParameterDescriptor & descriptor =
parameter_infos[parameter.get_name()].descriptor;
std::string name = parameter.get_name();
auto item = parameter_infos[name];
const rcl_interfaces::msg::ParameterDescriptor & descriptor = item.descriptor;
const rclcpp::ParameterType old_type = item.value.get_type();
const rclcpp::ParameterType type = parameter.get_type();
result.successful =
!descriptor.static_typing || rclcpp::PARAMETER_NOT_SET == old_type || old_type == type;
if (!result.successful) {
result.reason = format_type_reason(
name, rclcpp::to_string(old_type), rclcpp::to_string(type));
return result;
}
result = __check_parameter_value_in_range(
descriptor,
parameter.get_parameter_value());
if (!result.successful) {
break;
return result;
}
}
return result;
Expand Down
68 changes: 55 additions & 13 deletions rclcpp/test/rclcpp/test_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -842,12 +842,23 @@ TEST_F(TestNode, set_parameter_undeclared_parameters_not_allowed) {
EXPECT_EQ(node->get_parameter(name).get_value<int>(), 43);
}
{
// normal use, change type
// normal use, change type not allowed
auto name = "parameter"_unq;
EXPECT_FALSE(node->has_parameter(name));
node->declare_parameter(name, 42);
EXPECT_TRUE(node->has_parameter(name));
EXPECT_EQ(node->get_parameter(name).get_value<int>(), 42);
EXPECT_FALSE(node->set_parameter(rclcpp::Parameter(name, "not an integer")).successful);
}
{
// normal use, change type
auto name = "parameter"_unq;
EXPECT_FALSE(node->has_parameter(name));
rcl_interfaces::msg::ParameterDescriptor descriptor;
descriptor.static_typing = false;
node->declare_parameter(name, 42, descriptor);
EXPECT_TRUE(node->has_parameter(name));
EXPECT_EQ(node->get_parameter(name).get_value<int>(), 42);
EXPECT_TRUE(node->set_parameter(rclcpp::Parameter(name, "not an integer")).successful);
EXPECT_EQ(node->get_parameter(name).get_value<std::string>(), std::string("not an integer"));
}
Expand All @@ -864,8 +875,6 @@ TEST_F(TestNode, set_parameter_undeclared_parameters_not_allowed) {
EXPECT_TRUE(node->has_parameter(name3));

EXPECT_EQ(node->get_parameter(name1).get_value<int>(), 42);
EXPECT_TRUE(node->set_parameter(rclcpp::Parameter(name1, "not an integer")).successful);
EXPECT_EQ(node->get_parameter(name1).get_value<std::string>(), std::string("not an integer"));

EXPECT_EQ(node->get_parameter(name2).get_value<bool>(), true);
EXPECT_TRUE(node->set_parameter(rclcpp::Parameter(name2, false)).successful);
Expand Down Expand Up @@ -910,13 +919,26 @@ TEST_F(TestNode, set_parameter_undeclared_parameters_not_allowed) {
EXPECT_EQ(value.get_type(), rclcpp::PARAMETER_NOT_SET);
}
{
// setting type of rclcpp::PARAMETER_NOT_SET, when already to another type, will undeclare
// setting type of rclcpp::PARAMETER_NOT_SET, when already to another type, will fail
auto name = "parameter"_unq;
node->declare_parameter(name, 42);
EXPECT_TRUE(node->has_parameter(name));
auto value = node->get_parameter(name);
EXPECT_EQ(value.get_type(), rclcpp::PARAMETER_INTEGER);

EXPECT_FALSE(node->set_parameter(rclcpp::Parameter(name)).successful);
}
{
// setting type of rclcpp::PARAMETER_NOT_SET,
// when dynamic typing is allowing and already set to another type, will undeclare
auto name = "parameter"_unq;
rcl_interfaces::msg::ParameterDescriptor descriptor;
descriptor.static_typing = false;
node->declare_parameter(name, 42, descriptor);
EXPECT_TRUE(node->has_parameter(name));
auto value = node->get_parameter(name);
EXPECT_EQ(value.get_type(), rclcpp::PARAMETER_INTEGER);

EXPECT_TRUE(node->set_parameter(rclcpp::Parameter(name)).successful);

EXPECT_FALSE(node->has_parameter(name));
Expand Down Expand Up @@ -1256,15 +1278,9 @@ TEST_F(TestNode, set_parameter_undeclared_parameters_not_allowed) {
auto name = "parameter"_unq;
rcl_interfaces::msg::ParameterDescriptor descriptor;
descriptor.type = rclcpp::PARAMETER_INTEGER;
node->declare_parameter(name, 42, descriptor);
node->declare_parameter(name, "asd", descriptor);
EXPECT_TRUE(node->has_parameter(name));
auto value = node->get_parameter(name);
EXPECT_EQ(value.get_type(), rclcpp::PARAMETER_INTEGER);
EXPECT_EQ(value.get_value<int64_t>(), 42);

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_STRING);
EXPECT_EQ(value.get_value<std::string>(), "asd");
}
Expand Down Expand Up @@ -1422,13 +1438,26 @@ TEST_F(TestNode, set_parameters_undeclared_parameters_not_allowed) {
EXPECT_EQ(value.get_type(), rclcpp::PARAMETER_NOT_SET);
}
{
// setting type of rclcpp::PARAMETER_NOT_SET, when already to another type, will undeclare
// setting type of rclcpp::PARAMETER_NOT_SET, when already to another type, will fail
auto name = "parameter"_unq;
node->declare_parameter(name, 42);
EXPECT_TRUE(node->has_parameter(name));
auto value = node->get_parameter(name);
EXPECT_EQ(value.get_type(), rclcpp::PARAMETER_INTEGER);

EXPECT_FALSE(node->set_parameters({rclcpp::Parameter(name)})[0].successful);
}
{
// setting type of rclcpp::PARAMETER_NOT_SET,
// when already to another type and dynamic typic allowed, will undeclare
auto name = "parameter"_unq;
rcl_interfaces::msg::ParameterDescriptor descriptor;
descriptor.static_typing = false;
node->declare_parameter(name, 42, descriptor);
EXPECT_TRUE(node->has_parameter(name));
auto value = node->get_parameter(name);
EXPECT_EQ(value.get_type(), rclcpp::PARAMETER_INTEGER);

EXPECT_TRUE(node->set_parameters({rclcpp::Parameter(name)})[0].successful);

EXPECT_FALSE(node->has_parameter(name));
Expand Down Expand Up @@ -1596,13 +1625,26 @@ TEST_F(TestNode, set_parameters_atomically_undeclared_parameters_not_allowed) {
EXPECT_EQ(value.get_type(), rclcpp::PARAMETER_NOT_SET);
}
{
// setting type of rclcpp::PARAMETER_NOT_SET, when already to another type, will undeclare
// setting type of rclcpp::PARAMETER_NOT_SET, when already to another type, will fail
auto name = "parameter"_unq;
node->declare_parameter(name, 42);
EXPECT_TRUE(node->has_parameter(name));
auto value = node->get_parameter(name);
EXPECT_EQ(value.get_type(), rclcpp::PARAMETER_INTEGER);

EXPECT_FALSE(node->set_parameters_atomically({rclcpp::Parameter(name)}).successful);
}
{
// setting type of rclcpp::PARAMETER_NOT_SET,
// when dynamic typing is allowed and already declared to another type, will undeclare
auto name = "parameter"_unq;
rcl_interfaces::msg::ParameterDescriptor descriptor;
descriptor.static_typing = false;
node->declare_parameter(name, 42, descriptor);
EXPECT_TRUE(node->has_parameter(name));
auto value = node->get_parameter(name);
EXPECT_EQ(value.get_type(), rclcpp::PARAMETER_INTEGER);

EXPECT_TRUE(node->set_parameters_atomically({rclcpp::Parameter(name)}).successful);

EXPECT_FALSE(node->has_parameter(name));
Expand Down