Ignore parameters overrides in set parameter methods when allowing undeclared parameters (#756)
* Ignore parameters overrides in set parameter methods when allowing undeclared parameters Signed-off-by: ivanpauno <ivanpauno@ekumenlabs.com> * Address reviewer comment Signed-off-by: ivanpauno <ivanpauno@ekumenlabs.com>
This commit is contained in:
parent
411e748632
commit
91198ef917
3 changed files with 24 additions and 10 deletions
|
@ -516,6 +516,7 @@ public:
|
||||||
* rclcpp::NodeOptions::allow_undeclared_parameters set to true.
|
* rclcpp::NodeOptions::allow_undeclared_parameters set to true.
|
||||||
* If undeclared parameters are allowed, then the parameter is implicitly
|
* If undeclared parameters are allowed, then the parameter is implicitly
|
||||||
* declared with the default parameter meta data before being set.
|
* declared with the default parameter meta data before being set.
|
||||||
|
* Parameter overrides are ignored by set_parameter.
|
||||||
*
|
*
|
||||||
* This method will result in any callback registered with
|
* This method will result in any callback registered with
|
||||||
* set_on_parameters_set_callback to be called.
|
* set_on_parameters_set_callback to be called.
|
||||||
|
|
|
@ -330,19 +330,20 @@ __declare_parameter_common(
|
||||||
const rclcpp::ParameterValue & default_value,
|
const rclcpp::ParameterValue & default_value,
|
||||||
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
|
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
|
||||||
std::map<std::string, rclcpp::node_interfaces::ParameterInfo> & parameters_out,
|
std::map<std::string, rclcpp::node_interfaces::ParameterInfo> & parameters_out,
|
||||||
const std::map<std::string, rclcpp::ParameterValue> & initial_values,
|
const std::map<std::string, rclcpp::ParameterValue> & overrides,
|
||||||
OnParametersSetCallbackType on_set_parameters_callback,
|
OnParametersSetCallbackType on_set_parameters_callback,
|
||||||
rcl_interfaces::msg::ParameterEvent * parameter_event_out)
|
rcl_interfaces::msg::ParameterEvent * parameter_event_out,
|
||||||
|
bool use_overrides = true)
|
||||||
{
|
{
|
||||||
using rclcpp::node_interfaces::ParameterInfo;
|
using rclcpp::node_interfaces::ParameterInfo;
|
||||||
std::map<std::string, ParameterInfo> parameter_infos {{name, ParameterInfo()}};
|
std::map<std::string, ParameterInfo> parameter_infos {{name, ParameterInfo()}};
|
||||||
parameter_infos.at(name).descriptor = parameter_descriptor;
|
parameter_infos.at(name).descriptor = parameter_descriptor;
|
||||||
|
|
||||||
// Use the value from the initial_values if available, otherwise use the default.
|
// Use the value from the overrides if available, otherwise use the default.
|
||||||
const rclcpp::ParameterValue * initial_value = &default_value;
|
const rclcpp::ParameterValue * initial_value = &default_value;
|
||||||
auto initial_value_it = initial_values.find(name);
|
auto overrides_it = overrides.find(name);
|
||||||
if (initial_value_it != initial_values.end()) {
|
if (use_overrides && overrides_it != overrides.end()) {
|
||||||
initial_value = &initial_value_it->second;
|
initial_value = &overrides_it->second;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Check with the user's callback to see if the initial value can be set.
|
// Check with the user's callback to see if the initial value can be set.
|
||||||
|
@ -522,7 +523,8 @@ NodeParameters::set_parameters_atomically(const std::vector<rclcpp::Parameter> &
|
||||||
staged_parameter_changes,
|
staged_parameter_changes,
|
||||||
parameter_overrides_,
|
parameter_overrides_,
|
||||||
nullptr, // callback is explicitly null, so that it is called only once, when setting below.
|
nullptr, // callback is explicitly null, so that it is called only once, when setting below.
|
||||||
¶meter_event_msg);
|
¶meter_event_msg,
|
||||||
|
false);
|
||||||
if (!result.successful) {
|
if (!result.successful) {
|
||||||
// Declare failed, return knowing that nothing was changed because the
|
// Declare failed, return knowing that nothing was changed because the
|
||||||
// staged changes were not applied.
|
// staged changes were not applied.
|
||||||
|
|
|
@ -1066,9 +1066,20 @@ TEST_F(TestNode, set_parameter_undeclared_parameters_not_allowed) {
|
||||||
}
|
}
|
||||||
|
|
||||||
TEST_F(TestNode, set_parameter_undeclared_parameters_allowed) {
|
TEST_F(TestNode, set_parameter_undeclared_parameters_allowed) {
|
||||||
auto node = std::make_shared<rclcpp::Node>(
|
rclcpp::NodeOptions no;
|
||||||
"test_set_parameter_node"_unq,
|
no.parameter_overrides({
|
||||||
rclcpp::NodeOptions().allow_undeclared_parameters(true));
|
{"parameter_with_override", 30},
|
||||||
|
});
|
||||||
|
no.allow_undeclared_parameters(true);
|
||||||
|
auto node = std::make_shared<rclcpp::Node>("test_set_parameter_node"_unq, no);
|
||||||
|
{
|
||||||
|
// overrides are ignored when not declaring a parameter
|
||||||
|
auto name = "parameter_with_override";
|
||||||
|
EXPECT_FALSE(node->has_parameter(name));
|
||||||
|
EXPECT_TRUE(node->set_parameter(rclcpp::Parameter(name, 43)).successful);
|
||||||
|
EXPECT_TRUE(node->has_parameter(name));
|
||||||
|
EXPECT_EQ(node->get_parameter(name).get_value<int>(), 43);
|
||||||
|
}
|
||||||
{
|
{
|
||||||
// normal use (declare first) still works with this true
|
// normal use (declare first) still works with this true
|
||||||
auto name = "parameter"_unq;
|
auto name = "parameter"_unq;
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue