Skip to content

Commit 7436bbe

Browse files
Dynamic Parameters Only validating params that are part of the plugin (#5106)
* Only validating params that are part of the plugin Signed-off-by: Nils-ChristianIseke <[email protected]> * review Signed-off-by: Nils-Christian Iseke <[email protected]> * Refactoring type with param_type and name with param_name to get more consistency. Signed-off-by: Nils-Christian Iseke <[email protected]> * Check if plugin_name is part of param_name Signed-off-by: Nils-Christian Iseke <[email protected]> * Check if param_name contains name_ Signed-off-by: Nils-Christian Iseke <[email protected]> * Uncrustify Signed-off-by: Nils-Christian Iseke <[email protected]> * Add check param name in dynamic parameter upate. Signed-off-by: Nils-Christian Iseke <[email protected]> * fix Signed-off-by: Nils-Christian Iseke <[email protected]> * Merge remote-tracking branch 'upstream/main' into FixNamespaceCheck Signed-off-by: Nils-Christian Iseke <[email protected]> * Remove controller_frequency as dynamic parameter Signed-off-by: Nils-Christian Iseke <[email protected]> * Revert "Merge remote-tracking branch 'origin/main' into FixNamespaceCheck" This reverts commit 7632e41, reversing changes made to 19afc9e. Signed-off-by: Nils-Christian Iseke <[email protected]> * Merge remote-tracking branch 'upstream/main' into FixNamespaceCheck Signed-off-by: Nils-Christian Iseke <[email protected]> * Fix merge errors. Signed-off-by: Nils-Christian Iseke <[email protected]> * Add missing check to simple_goal_checker Signed-off-by: Nils-Christian Iseke <[email protected]> * Handel param_name resolution for smac_planner_hybrid Signed-off-by: Nils-Christian Iseke <[email protected]> * fix typo Signed-off-by: Nils-Christian Iseke <[email protected]> * uncrustify Signed-off-by: Nils-Christian Iseke <[email protected]> * fix Signed-off-by: Nils-Christian Iseke <[email protected]> * Revert "uncrustify" This reverts commit 43749c2. Signed-off-by: Nils-Christian Iseke <[email protected]> * uncrustify Signed-off-by: Nils-Christian Iseke <[email protected]> * Revert "uncrustify" This reverts commit e18f704. Signed-off-by: Nils-Christian Iseke <[email protected]> * Revert "fix" This reverts commit a0a7892. Signed-off-by: Nils-Christian Iseke <[email protected]> * Merge remote-tracking branch 'upstream/main' into FixNamespaceCheck Signed-off-by: Nils-Christian Iseke <[email protected]> * MPPI Check Namespace. Signed-off-by: Nils-Christian Iseke <[email protected]> * fixing parameter_handler tests. Signed-off-by: Nils-Christian Iseke <[email protected]> * Fix optimizer Signed-off-by: Nils-Christian Iseke <[email protected]> * Fix indentation Signed-off-by: Nils-Christian Iseke <[email protected]> * mppi param handler only execute post_callbacks if a param of mppi was updated. Signed-off-by: Nils-Christian Iseke <[email protected]> * Update nav2_rotation_shim_controller.hpp Signed-off-by: Nils-Christian Iseke <[email protected]> * Review Signed-off-by: Nils-Christian Iseke <[email protected]> * Update nav2_mppi_controller/src/parameters_handler.cpp Signed-off-by: Steve Macenski <[email protected]> * Update nav2_mppi_controller/src/parameters_handler.cpp Signed-off-by: Steve Macenski <[email protected]> * Update nav2_mppi_controller/src/parameters_handler.cpp Signed-off-by: Steve Macenski <[email protected]> --------- Signed-off-by: Nils-ChristianIseke <[email protected]> Signed-off-by: Nils-Christian Iseke <[email protected]> Signed-off-by: Nils-Christian Iseke <[email protected]> Signed-off-by: Steve Macenski <[email protected]> Co-authored-by: Steve Macenski <[email protected]>
1 parent cb39462 commit 7436bbe

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

43 files changed

+533
-404
lines changed

nav2_amcl/src/amcl_node.cpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1182,6 +1182,9 @@ AmclNode::dynamicParametersCallback(
11821182
for (auto parameter : parameters) {
11831183
const auto & param_type = parameter.get_type();
11841184
const auto & param_name = parameter.get_name();
1185+
if (param_name.find('.') != std::string::npos) {
1186+
continue;
1187+
}
11851188

11861189
if (param_type == ParameterType::PARAMETER_DOUBLE) {
11871190
if (param_name == "alpha1") {

nav2_collision_monitor/src/polygon.cpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -578,7 +578,9 @@ Polygon::dynamicParametersCallback(
578578
for (auto parameter : parameters) {
579579
const auto & param_type = parameter.get_type();
580580
const auto & param_name = parameter.get_name();
581-
581+
if(param_name.find(polygon_name_ + ".") != 0) {
582+
continue;
583+
}
582584
if (param_type == rcl_interfaces::msg::ParameterType::PARAMETER_BOOL) {
583585
if (param_name == polygon_name_ + "." + "enabled") {
584586
enabled_ = parameter.as_bool();

nav2_collision_monitor/src/source.cpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -121,7 +121,9 @@ Source::dynamicParametersCallback(
121121
for (auto parameter : parameters) {
122122
const auto & param_type = parameter.get_type();
123123
const auto & param_name = parameter.get_name();
124-
124+
if(param_name.find(source_name_ + ".") != 0) {
125+
continue;
126+
}
125127
if (param_type == rcl_interfaces::msg::ParameterType::PARAMETER_BOOL) {
126128
if (param_name == source_name_ + "." + "enabled") {
127129
enabled_ = parameter.as_bool();

nav2_controller/plugins/pose_progress_checker.cpp

Lines changed: 7 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -79,11 +79,14 @@ PoseProgressChecker::dynamicParametersCallback(std::vector<rclcpp::Parameter> pa
7979
{
8080
rcl_interfaces::msg::SetParametersResult result;
8181
for (auto parameter : parameters) {
82-
const auto & type = parameter.get_type();
83-
const auto & name = parameter.get_name();
82+
const auto & param_type = parameter.get_type();
83+
const auto & param_name = parameter.get_name();
84+
if (param_name.find(plugin_name_ + ".") != 0) {
85+
continue;
86+
}
8487

85-
if (type == ParameterType::PARAMETER_DOUBLE) {
86-
if (name == plugin_name_ + ".required_movement_angle") {
88+
if (param_type == ParameterType::PARAMETER_DOUBLE) {
89+
if (param_name == plugin_name_ + ".required_movement_angle") {
8790
required_movement_angle_ = parameter.as_double();
8891
}
8992
}

nav2_controller/plugins/simple_goal_checker.cpp

Lines changed: 10 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -145,18 +145,20 @@ SimpleGoalChecker::dynamicParametersCallback(std::vector<rclcpp::Parameter> para
145145
{
146146
rcl_interfaces::msg::SetParametersResult result;
147147
for (auto & parameter : parameters) {
148-
const auto & type = parameter.get_type();
149-
const auto & name = parameter.get_name();
150-
151-
if (type == ParameterType::PARAMETER_DOUBLE) {
152-
if (name == plugin_name_ + ".xy_goal_tolerance") {
148+
const auto & param_type = parameter.get_type();
149+
const auto & param_name = parameter.get_name();
150+
if (param_name.find(plugin_name_ + ".") != 0) {
151+
continue;
152+
}
153+
if (param_type == ParameterType::PARAMETER_DOUBLE) {
154+
if (param_name == plugin_name_ + ".xy_goal_tolerance") {
153155
xy_goal_tolerance_ = parameter.as_double();
154156
xy_goal_tolerance_sq_ = xy_goal_tolerance_ * xy_goal_tolerance_;
155-
} else if (name == plugin_name_ + ".yaw_goal_tolerance") {
157+
} else if (param_name == plugin_name_ + ".yaw_goal_tolerance") {
156158
yaw_goal_tolerance_ = parameter.as_double();
157159
}
158-
} else if (type == ParameterType::PARAMETER_BOOL) {
159-
if (name == plugin_name_ + ".stateful") {
160+
} else if (param_type == ParameterType::PARAMETER_BOOL) {
161+
if (param_name == plugin_name_ + ".stateful") {
160162
stateful_ = parameter.as_bool();
161163
}
162164
}

nav2_controller/plugins/simple_progress_checker.cpp

Lines changed: 8 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -98,13 +98,16 @@ SimpleProgressChecker::dynamicParametersCallback(std::vector<rclcpp::Parameter>
9898
{
9999
rcl_interfaces::msg::SetParametersResult result;
100100
for (auto parameter : parameters) {
101-
const auto & type = parameter.get_type();
102-
const auto & name = parameter.get_name();
101+
const auto & param_type = parameter.get_type();
102+
const auto & param_name = parameter.get_name();
103+
if (param_name.find(plugin_name_ + ".") != 0) {
104+
continue;
105+
}
103106

104-
if (type == ParameterType::PARAMETER_DOUBLE) {
105-
if (name == plugin_name_ + ".required_movement_radius") {
107+
if (param_type == ParameterType::PARAMETER_DOUBLE) {
108+
if (param_name == plugin_name_ + ".required_movement_radius") {
106109
radius_ = parameter.as_double();
107-
} else if (name == plugin_name_ + ".movement_time_allowance") {
110+
} else if (param_name == plugin_name_ + ".movement_time_allowance") {
108111
time_allowance_ = rclcpp::Duration::from_seconds(parameter.as_double());
109112
}
110113
}

nav2_controller/plugins/stopped_goal_checker.cpp

Lines changed: 8 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -119,13 +119,16 @@ StoppedGoalChecker::dynamicParametersCallback(std::vector<rclcpp::Parameter> par
119119
{
120120
rcl_interfaces::msg::SetParametersResult result;
121121
for (auto parameter : parameters) {
122-
const auto & type = parameter.get_type();
123-
const auto & name = parameter.get_name();
122+
const auto & param_type = parameter.get_type();
123+
const auto & param_name = parameter.get_name();
124+
if (param_name.find(plugin_name_ + ".") != 0) {
125+
continue;
126+
}
124127

125-
if (type == ParameterType::PARAMETER_DOUBLE) {
126-
if (name == plugin_name_ + ".rot_stopped_velocity") {
128+
if (param_type == ParameterType::PARAMETER_DOUBLE) {
129+
if (param_name == plugin_name_ + ".rot_stopped_velocity") {
127130
rot_stopped_velocity_ = parameter.as_double();
128-
} else if (name == plugin_name_ + ".trans_stopped_velocity") {
131+
} else if (param_name == plugin_name_ + ".trans_stopped_velocity") {
129132
trans_stopped_velocity_ = parameter.as_double();
130133
}
131134
}

nav2_controller/src/controller_server.cpp

Lines changed: 8 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -834,12 +834,12 @@ ControllerServer::dynamicParametersCallback(std::vector<rclcpp::Parameter> param
834834
rcl_interfaces::msg::SetParametersResult result;
835835

836836
for (auto parameter : parameters) {
837-
const auto & type = parameter.get_type();
838-
const auto & name = parameter.get_name();
837+
const auto & param_type = parameter.get_type();
838+
const auto & param_name = parameter.get_name();
839839

840840
// If we are trying to change the parameter of a plugin we can just skip it at this point
841841
// as they handle parameter changes themselves and don't need to lock the mutex
842-
if (name.find('.') != std::string::npos) {
842+
if (param_name.find('.') != std::string::npos) {
843843
continue;
844844
}
845845

@@ -853,16 +853,14 @@ ControllerServer::dynamicParametersCallback(std::vector<rclcpp::Parameter> param
853853
return result;
854854
}
855855

856-
if (type == ParameterType::PARAMETER_DOUBLE) {
857-
if (name == "controller_frequency") {
858-
controller_frequency_ = parameter.as_double();
859-
} else if (name == "min_x_velocity_threshold") {
856+
if (param_type == ParameterType::PARAMETER_DOUBLE) {
857+
if (param_name == "min_x_velocity_threshold") {
860858
min_x_velocity_threshold_ = parameter.as_double();
861-
} else if (name == "min_y_velocity_threshold") {
859+
} else if (param_name == "min_y_velocity_threshold") {
862860
min_y_velocity_threshold_ = parameter.as_double();
863-
} else if (name == "min_theta_velocity_threshold") {
861+
} else if (param_name == "min_theta_velocity_threshold") {
864862
min_theta_velocity_threshold_ = parameter.as_double();
865-
} else if (name == "failure_tolerance") {
863+
} else if (param_name == "failure_tolerance") {
866864
failure_tolerance_ = parameter.as_double();
867865
}
868866
}

nav2_controller/test/test_dynamic_parameters.cpp

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -62,8 +62,7 @@ TEST(WPTest, test_dynamic_parameters)
6262
controller->get_node_services_interface());
6363

6464
auto results = rec_param->set_parameters_atomically(
65-
{rclcpp::Parameter("controller_frequency", 100.0),
66-
rclcpp::Parameter("min_x_velocity_threshold", 100.0),
65+
{rclcpp::Parameter("min_x_velocity_threshold", 100.0),
6766
rclcpp::Parameter("min_y_velocity_threshold", 100.0),
6867
rclcpp::Parameter("min_theta_velocity_threshold", 100.0),
6968
rclcpp::Parameter("failure_tolerance", 5.0)});
@@ -72,7 +71,6 @@ TEST(WPTest, test_dynamic_parameters)
7271
controller->get_node_base_interface(),
7372
results);
7473

75-
EXPECT_EQ(controller->get_parameter("controller_frequency").as_double(), 100.0);
7674
EXPECT_EQ(controller->get_parameter("min_x_velocity_threshold").as_double(), 100.0);
7775
EXPECT_EQ(controller->get_parameter("min_y_velocity_threshold").as_double(), 100.0);
7876
EXPECT_EQ(controller->get_parameter("min_theta_velocity_threshold").as_double(), 100.0);

nav2_costmap_2d/plugins/inflation_layer.cpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -444,6 +444,9 @@ InflationLayer::dynamicParametersCallback(
444444
for (auto parameter : parameters) {
445445
const auto & param_type = parameter.get_type();
446446
const auto & param_name = parameter.get_name();
447+
if (param_name.find(name_ + ".") != 0) {
448+
continue;
449+
}
447450

448451
if (param_type == ParameterType::PARAMETER_DOUBLE) {
449452
if (param_name == name_ + "." + "inflation_radius" &&

0 commit comments

Comments
 (0)