Skip to content

Commit a7a59f8

Browse files
authored
Add approach_velocity_scaling_dist to dynamic parameter callback (#5711)
* Add approach_velocity_scaling_dist to dynamic parameter callback The approach_velocity_scaling_dist parameter was declared and initialized but missing from the dynamicParametersCallback function, preventing it from being updated via dynamic reconfigure (e.g., rqt_reconfigure). This commit adds the parameter to the callback handler, enabling runtime reconfiguration like other controller parameters. Signed-off-by: Bram Odrosslij <bram.odros@gmail.com> * Fixed bug that caused build failure Signed-off-by: Bram Odrosslij <bram.odros@gmail.com> * Added test Signed-off-by: Bram Odrosslij <bram.odros@gmail.com> --------- Signed-off-by: Bram Odrosslij <bram.odros@gmail.com>
1 parent 088ff86 commit a7a59f8

File tree

2 files changed

+4
-0
lines changed

2 files changed

+4
-0
lines changed

‎nav2_regulated_pure_pursuit_controller/src/parameter_handler.cpp‎

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -291,6 +291,8 @@ ParameterHandler::updateParametersCallback(
291291
params_.transform_tolerance = parameter.as_double();
292292
} else if (param_name == plugin_name_ + ".max_robot_pose_search_dist") {
293293
params_.max_robot_pose_search_dist = parameter.as_double();
294+
} else if (param_name == plugin_name_ + ".approach_velocity_scaling_dist") {
295+
params_.approach_velocity_scaling_dist = parameter.as_double();
294296
}
295297
} else if (param_type == ParameterType::PARAMETER_BOOL) {
296298
if (param_name == plugin_name_ + ".use_velocity_scaled_lookahead_dist") {

‎nav2_regulated_pure_pursuit_controller/test/test_regulated_pp.cpp‎

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -446,6 +446,7 @@ TEST(RegulatedPurePursuitTest, testDynamicParameter)
446446
rclcpp::Parameter("test.lookahead_time", 1.8),
447447
rclcpp::Parameter("test.rotate_to_heading_angular_vel", 18.0),
448448
rclcpp::Parameter("test.min_approach_linear_velocity", 1.0),
449+
rclcpp::Parameter("test.approach_velocity_scaling_dist", 0.8),
449450
rclcpp::Parameter("test.max_allowed_time_to_collision_up_to_carrot", 2.0),
450451
rclcpp::Parameter("test.min_distance_to_obstacle", 2.0),
451452
rclcpp::Parameter("test.cost_scaling_dist", 2.0),
@@ -474,6 +475,7 @@ TEST(RegulatedPurePursuitTest, testDynamicParameter)
474475
EXPECT_EQ(node->get_parameter("test.lookahead_time").as_double(), 1.8);
475476
EXPECT_EQ(node->get_parameter("test.rotate_to_heading_angular_vel").as_double(), 18.0);
476477
EXPECT_EQ(node->get_parameter("test.min_approach_linear_velocity").as_double(), 1.0);
478+
EXPECT_EQ(node->get_parameter("test.approach_velocity_scaling_dist").as_double(), 0.8);
477479
EXPECT_EQ(
478480
node->get_parameter(
479481
"test.max_allowed_time_to_collision_up_to_carrot").as_double(), 2.0);

0 commit comments

Comments
 (0)