Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
36 commits
Select commit Hold shift + click to select a range
8cd8ca4
Only validating params that are part of the plugin
Nils-ChristianIseke Apr 25, 2025
3985c95
review
Nils-ChristianIseke May 12, 2025
121466b
Refactoring type with param_type and name with param_name to get more…
Nils-ChristianIseke May 15, 2025
1ca16a4
Check if plugin_name is part of param_name
Nils-ChristianIseke May 15, 2025
f03c24e
Check if param_name contains name_
Nils-ChristianIseke May 15, 2025
2981479
Uncrustify
Nils-ChristianIseke May 15, 2025
ce4ae56
Add check param name in dynamic parameter upate.
Nils-ChristianIseke May 16, 2025
7321da6
fix
Nils-ChristianIseke May 16, 2025
299f1fa
Merge remote-tracking branch 'upstream/main' into FixNamespaceCheck
Nils-ChristianIseke May 16, 2025
19afc9e
Remove controller_frequency as dynamic parameter
Nils-ChristianIseke May 16, 2025
7632e41
Merge remote-tracking branch 'origin/main' into FixNamespaceCheck
Nils-ChristianIseke May 16, 2025
02d46cb
Revert "Merge remote-tracking branch 'origin/main' into FixNamespaceC…
Nils-ChristianIseke May 16, 2025
28ee286
Merge remote-tracking branch 'upstream/main' into FixNamespaceCheck
Nils-ChristianIseke May 16, 2025
4c15bd0
Merge remote-tracking branch 'upstream/main' into FixNamespaceCheck
Nils-ChristianIseke May 17, 2025
7a62414
Fix merge errors.
Nils-ChristianIseke May 18, 2025
3ac3864
Add missing check to simple_goal_checker
Nils-ChristianIseke May 18, 2025
57b5459
Handel param_name resolution for smac_planner_hybrid
Nils-ChristianIseke May 18, 2025
6e4ff4e
fix typo
Nils-ChristianIseke May 18, 2025
43749c2
uncrustify
Nils-ChristianIseke May 18, 2025
a0a7892
fix
Nils-ChristianIseke May 18, 2025
bd12649
Revert "uncrustify"
Nils-ChristianIseke May 18, 2025
e18f704
uncrustify
Nils-ChristianIseke May 18, 2025
b3d216c
Revert "uncrustify"
Nils-ChristianIseke May 20, 2025
aa5b00a
Revert "fix"
Nils-ChristianIseke May 20, 2025
10fbc3a
Merge remote-tracking branch 'upstream/main' into FixNamespaceCheck
Nils-ChristianIseke May 20, 2025
b6bbcdf
Merge remote-tracking branch 'upstream' into FixNamespaceCheck
Nils-ChristianIseke May 20, 2025
15ed1c9
MPPI Check Namespace.
Nils-ChristianIseke May 20, 2025
8331f2f
fixing parameter_handler tests.
Nils-ChristianIseke May 21, 2025
9e2655b
Fix optimizer
Nils-ChristianIseke May 21, 2025
acc41da
Fix indentation
Nils-ChristianIseke May 21, 2025
dad23f5
mppi param handler only execute post_callbacks if a param of mppi was…
Nils-ChristianIseke May 21, 2025
5eea8e7
Update nav2_rotation_shim_controller.hpp
Nils-ChristianIseke May 21, 2025
b52f0b1
Review
Nils-ChristianIseke May 22, 2025
9f5534f
Update nav2_mppi_controller/src/parameters_handler.cpp
SteveMacenski May 22, 2025
47e72b4
Update nav2_mppi_controller/src/parameters_handler.cpp
SteveMacenski May 22, 2025
b9c37b9
Update nav2_mppi_controller/src/parameters_handler.cpp
SteveMacenski May 22, 2025
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
3 changes: 3 additions & 0 deletions nav2_amcl/src/amcl_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1182,6 +1182,9 @@ AmclNode::dynamicParametersCallback(
for (auto parameter : parameters) {
const auto & param_type = parameter.get_type();
const auto & param_name = parameter.get_name();
if (param_name.find('.') != std::string::npos) {
continue;
}

if (param_type == ParameterType::PARAMETER_DOUBLE) {
if (param_name == "alpha1") {
Expand Down
4 changes: 3 additions & 1 deletion nav2_collision_monitor/src/polygon.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -578,7 +578,9 @@ Polygon::dynamicParametersCallback(
for (auto parameter : parameters) {
const auto & param_type = parameter.get_type();
const auto & param_name = parameter.get_name();

if(param_name.find(polygon_name_ + ".") != 0) {
continue;
}
if (param_type == rcl_interfaces::msg::ParameterType::PARAMETER_BOOL) {
if (param_name == polygon_name_ + "." + "enabled") {
enabled_ = parameter.as_bool();
Expand Down
4 changes: 3 additions & 1 deletion nav2_collision_monitor/src/source.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -121,7 +121,9 @@ Source::dynamicParametersCallback(
for (auto parameter : parameters) {
const auto & param_type = parameter.get_type();
const auto & param_name = parameter.get_name();

if(param_name.find(source_name_ + ".") != 0) {
continue;
}
if (param_type == rcl_interfaces::msg::ParameterType::PARAMETER_BOOL) {
if (param_name == source_name_ + "." + "enabled") {
enabled_ = parameter.as_bool();
Expand Down
11 changes: 7 additions & 4 deletions nav2_controller/plugins/pose_progress_checker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -79,11 +79,14 @@ PoseProgressChecker::dynamicParametersCallback(std::vector<rclcpp::Parameter> pa
{
rcl_interfaces::msg::SetParametersResult result;
for (auto parameter : parameters) {
const auto & type = parameter.get_type();
const auto & name = parameter.get_name();
const auto & param_type = parameter.get_type();
const auto & param_name = parameter.get_name();
if (param_name.find(plugin_name_ + ".") != 0) {
continue;
}

if (type == ParameterType::PARAMETER_DOUBLE) {
if (name == plugin_name_ + ".required_movement_angle") {
if (param_type == ParameterType::PARAMETER_DOUBLE) {
if (param_name == plugin_name_ + ".required_movement_angle") {
required_movement_angle_ = parameter.as_double();
}
}
Expand Down
18 changes: 10 additions & 8 deletions nav2_controller/plugins/simple_goal_checker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -145,18 +145,20 @@ SimpleGoalChecker::dynamicParametersCallback(std::vector<rclcpp::Parameter> para
{
rcl_interfaces::msg::SetParametersResult result;
for (auto & parameter : parameters) {
const auto & type = parameter.get_type();
const auto & name = parameter.get_name();

if (type == ParameterType::PARAMETER_DOUBLE) {
if (name == plugin_name_ + ".xy_goal_tolerance") {
const auto & param_type = parameter.get_type();
const auto & param_name = parameter.get_name();
if (param_name.find(plugin_name_ + ".") != 0) {
continue;
}
if (param_type == ParameterType::PARAMETER_DOUBLE) {
if (param_name == plugin_name_ + ".xy_goal_tolerance") {
xy_goal_tolerance_ = parameter.as_double();
xy_goal_tolerance_sq_ = xy_goal_tolerance_ * xy_goal_tolerance_;
} else if (name == plugin_name_ + ".yaw_goal_tolerance") {
} else if (param_name == plugin_name_ + ".yaw_goal_tolerance") {
yaw_goal_tolerance_ = parameter.as_double();
}
} else if (type == ParameterType::PARAMETER_BOOL) {
if (name == plugin_name_ + ".stateful") {
} else if (param_type == ParameterType::PARAMETER_BOOL) {
if (param_name == plugin_name_ + ".stateful") {
stateful_ = parameter.as_bool();
}
}
Expand Down
13 changes: 8 additions & 5 deletions nav2_controller/plugins/simple_progress_checker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -98,13 +98,16 @@ SimpleProgressChecker::dynamicParametersCallback(std::vector<rclcpp::Parameter>
{
rcl_interfaces::msg::SetParametersResult result;
for (auto parameter : parameters) {
const auto & type = parameter.get_type();
const auto & name = parameter.get_name();
const auto & param_type = parameter.get_type();
const auto & param_name = parameter.get_name();
if (param_name.find(plugin_name_ + ".") != 0) {
continue;
}

if (type == ParameterType::PARAMETER_DOUBLE) {
if (name == plugin_name_ + ".required_movement_radius") {
if (param_type == ParameterType::PARAMETER_DOUBLE) {
if (param_name == plugin_name_ + ".required_movement_radius") {
radius_ = parameter.as_double();
} else if (name == plugin_name_ + ".movement_time_allowance") {
} else if (param_name == plugin_name_ + ".movement_time_allowance") {
time_allowance_ = rclcpp::Duration::from_seconds(parameter.as_double());
}
}
Expand Down
13 changes: 8 additions & 5 deletions nav2_controller/plugins/stopped_goal_checker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -119,13 +119,16 @@ StoppedGoalChecker::dynamicParametersCallback(std::vector<rclcpp::Parameter> par
{
rcl_interfaces::msg::SetParametersResult result;
for (auto parameter : parameters) {
const auto & type = parameter.get_type();
const auto & name = parameter.get_name();
const auto & param_type = parameter.get_type();
const auto & param_name = parameter.get_name();
if (param_name.find(plugin_name_ + ".") != 0) {
continue;
}

if (type == ParameterType::PARAMETER_DOUBLE) {
if (name == plugin_name_ + ".rot_stopped_velocity") {
if (param_type == ParameterType::PARAMETER_DOUBLE) {
if (param_name == plugin_name_ + ".rot_stopped_velocity") {
rot_stopped_velocity_ = parameter.as_double();
} else if (name == plugin_name_ + ".trans_stopped_velocity") {
} else if (param_name == plugin_name_ + ".trans_stopped_velocity") {
trans_stopped_velocity_ = parameter.as_double();
}
}
Expand Down
18 changes: 8 additions & 10 deletions nav2_controller/src/controller_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -840,12 +840,12 @@ ControllerServer::dynamicParametersCallback(std::vector<rclcpp::Parameter> param
rcl_interfaces::msg::SetParametersResult result;

for (auto parameter : parameters) {
const auto & type = parameter.get_type();
const auto & name = parameter.get_name();
const auto & param_type = parameter.get_type();
const auto & param_name = parameter.get_name();

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

Expand All @@ -859,16 +859,14 @@ ControllerServer::dynamicParametersCallback(std::vector<rclcpp::Parameter> param
return result;
}

if (type == ParameterType::PARAMETER_DOUBLE) {
if (name == "controller_frequency") {
controller_frequency_ = parameter.as_double();
} else if (name == "min_x_velocity_threshold") {
if (param_type == ParameterType::PARAMETER_DOUBLE) {
if (param_name == "min_x_velocity_threshold") {
min_x_velocity_threshold_ = parameter.as_double();
} else if (name == "min_y_velocity_threshold") {
} else if (param_name == "min_y_velocity_threshold") {
min_y_velocity_threshold_ = parameter.as_double();
} else if (name == "min_theta_velocity_threshold") {
} else if (param_name == "min_theta_velocity_threshold") {
min_theta_velocity_threshold_ = parameter.as_double();
} else if (name == "failure_tolerance") {
} else if (param_name == "failure_tolerance") {
failure_tolerance_ = parameter.as_double();
}
}
Expand Down
4 changes: 1 addition & 3 deletions nav2_controller/test/test_dynamic_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -62,8 +62,7 @@ TEST(WPTest, test_dynamic_parameters)
controller->get_node_services_interface());

auto results = rec_param->set_parameters_atomically(
{rclcpp::Parameter("controller_frequency", 100.0),
rclcpp::Parameter("min_x_velocity_threshold", 100.0),
{rclcpp::Parameter("min_x_velocity_threshold", 100.0),
rclcpp::Parameter("min_y_velocity_threshold", 100.0),
rclcpp::Parameter("min_theta_velocity_threshold", 100.0),
rclcpp::Parameter("failure_tolerance", 5.0)});
Expand All @@ -72,7 +71,6 @@ TEST(WPTest, test_dynamic_parameters)
controller->get_node_base_interface(),
results);

EXPECT_EQ(controller->get_parameter("controller_frequency").as_double(), 100.0);
EXPECT_EQ(controller->get_parameter("min_x_velocity_threshold").as_double(), 100.0);
EXPECT_EQ(controller->get_parameter("min_y_velocity_threshold").as_double(), 100.0);
EXPECT_EQ(controller->get_parameter("min_theta_velocity_threshold").as_double(), 100.0);
Expand Down
3 changes: 3 additions & 0 deletions nav2_costmap_2d/plugins/inflation_layer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -444,6 +444,9 @@ InflationLayer::dynamicParametersCallback(
for (auto parameter : parameters) {
const auto & param_type = parameter.get_type();
const auto & param_name = parameter.get_name();
if (param_name.find(name_ + ".") != 0) {
continue;
}

if (param_type == ParameterType::PARAMETER_DOUBLE) {
if (param_name == name_ + "." + "inflation_radius" &&
Expand Down
3 changes: 3 additions & 0 deletions nav2_costmap_2d/plugins/obstacle_layer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -326,6 +326,9 @@ ObstacleLayer::dynamicParametersCallback(
for (auto parameter : parameters) {
const auto & param_type = parameter.get_type();
const auto & param_name = parameter.get_name();
if (param_name.find(name_ + ".") != 0) {
continue;
}

if (param_type == ParameterType::PARAMETER_DOUBLE) {
if (param_name == name_ + "." + "min_obstacle_height") {
Expand Down
3 changes: 3 additions & 0 deletions nav2_costmap_2d/plugins/plugin_container_layer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -214,6 +214,9 @@ rcl_interfaces::msg::SetParametersResult PluginContainerLayer::dynamicParameters
for (auto parameter : parameters) {
const auto & param_type = parameter.get_type();
const auto & param_name = parameter.get_name();
if (param_name.find(name_ + ".") != 0) {
continue;
}

if (param_type == ParameterType::PARAMETER_INTEGER) {
if (param_name == name_ + "." + "combination_method") {
Expand Down
3 changes: 3 additions & 0 deletions nav2_costmap_2d/plugins/static_layer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -485,6 +485,9 @@ StaticLayer::dynamicParametersCallback(
for (auto parameter : parameters) {
const auto & param_type = parameter.get_type();
const auto & param_name = parameter.get_name();
if (param_name.find(name_ + ".") != 0) {
continue;
}

if (param_name == name_ + "." + "map_subscribe_transient_local" ||
param_name == name_ + "." + "map_topic" ||
Expand Down
3 changes: 3 additions & 0 deletions nav2_costmap_2d/plugins/voxel_layer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -496,6 +496,9 @@ VoxelLayer::dynamicParametersCallback(
for (auto parameter : parameters) {
const auto & param_type = parameter.get_type();
const auto & param_name = parameter.get_name();
if (param_name.find(name_ + ".") != 0) {
continue;
}

if (param_type == ParameterType::PARAMETER_DOUBLE) {
if (param_name == name_ + "." + "max_obstacle_height") {
Expand Down
36 changes: 20 additions & 16 deletions nav2_costmap_2d/src/costmap_2d_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -723,42 +723,46 @@ Costmap2DROS::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameter
std::lock_guard<std::mutex> lock_reinit(_dynamic_parameter_mutex);

for (auto parameter : parameters) {
const auto & type = parameter.get_type();
const auto & name = parameter.get_name();
const auto & param_type = parameter.get_type();
const auto & param_name = parameter.get_name();
if (param_name.find('.') != std::string::npos) {
continue;
}


if (type == ParameterType::PARAMETER_DOUBLE) {
if (name == "robot_radius") {
if (param_type == ParameterType::PARAMETER_DOUBLE) {
if (param_name == "robot_radius") {
robot_radius_ = parameter.as_double();
// Set the footprint
if (use_radius_) {
setRobotFootprint(makeFootprintFromRadius(robot_radius_));
}
} else if (name == "footprint_padding") {
} else if (param_name == "footprint_padding") {
footprint_padding_ = parameter.as_double();
padded_footprint_ = unpadded_footprint_;
padFootprint(padded_footprint_, footprint_padding_);
layered_costmap_->setFootprint(padded_footprint_);
} else if (name == "transform_tolerance") {
} else if (param_name == "transform_tolerance") {
transform_tolerance_ = parameter.as_double();
} else if (name == "publish_frequency") {
} else if (param_name == "publish_frequency") {
map_publish_frequency_ = parameter.as_double();
if (map_publish_frequency_ > 0) {
publish_cycle_ = rclcpp::Duration::from_seconds(1 / map_publish_frequency_);
} else {
publish_cycle_ = rclcpp::Duration(-1s);
}
} else if (name == "resolution") {
} else if (param_name == "resolution") {
resize_map = true;
resolution_ = parameter.as_double();
} else if (name == "origin_x") {
} else if (param_name == "origin_x") {
resize_map = true;
origin_x_ = parameter.as_double();
} else if (name == "origin_y") {
} else if (param_name == "origin_y") {
resize_map = true;
origin_y_ = parameter.as_double();
}
} else if (type == ParameterType::PARAMETER_INTEGER) {
if (name == "width") {
} else if (param_type == ParameterType::PARAMETER_INTEGER) {
if (param_name == "width") {
if (parameter.as_int() > 0) {
resize_map = true;
map_width_meters_ = parameter.as_int();
Expand All @@ -769,7 +773,7 @@ Costmap2DROS::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameter
result.successful = false;
return result;
}
} else if (name == "height") {
} else if (param_name == "height") {
if (parameter.as_int() > 0) {
resize_map = true;
map_height_meters_ = parameter.as_int();
Expand All @@ -781,14 +785,14 @@ Costmap2DROS::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameter
return result;
}
}
} else if (type == ParameterType::PARAMETER_STRING) {
if (name == "footprint") {
} else if (param_type == ParameterType::PARAMETER_STRING) {
if (param_name == "footprint") {
footprint_ = parameter.as_string();
std::vector<geometry_msgs::msg::Point> new_footprint;
if (makeFootprintFromString(footprint_, new_footprint)) {
setRobotFootprint(new_footprint);
}
} else if (name == "robot_base_frame") {
} else if (param_name == "robot_base_frame") {
// First, make sure that the transform between the robot base frame
// and the global frame is available
std::string tf_error;
Expand Down
36 changes: 19 additions & 17 deletions nav2_docking/opennav_docking/src/controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -241,35 +241,37 @@ Controller::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)

rcl_interfaces::msg::SetParametersResult result;
for (auto parameter : parameters) {
const auto & type = parameter.get_type();
const auto & name = parameter.get_name();

if (type == rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE) {
if (name == "controller.k_phi") {
const auto & param_type = parameter.get_type();
const auto & param_name = parameter.get_name();
if (param_name.find("controller.") != 0) {
continue;
}
if (param_type == rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE) {
if (param_name == "controller.k_phi") {
k_phi_ = parameter.as_double();
} else if (name == "controller.k_delta") {
} else if (param_name == "controller.k_delta") {
k_delta_ = parameter.as_double();
} else if (name == "controller.beta") {
} else if (param_name == "controller.beta") {
beta_ = parameter.as_double();
} else if (name == "controller.lambda") {
} else if (param_name == "controller.lambda") {
lambda_ = parameter.as_double();
} else if (name == "controller.v_linear_min") {
} else if (param_name == "controller.v_linear_min") {
v_linear_min_ = parameter.as_double();
} else if (name == "controller.v_linear_max") {
} else if (param_name == "controller.v_linear_max") {
v_linear_max_ = parameter.as_double();
} else if (name == "controller.v_angular_max") {
} else if (param_name == "controller.v_angular_max") {
v_angular_max_ = parameter.as_double();
} else if (name == "controller.slowdown_radius") {
} else if (param_name == "controller.slowdown_radius") {
slowdown_radius_ = parameter.as_double();
} else if (name == "controller.rotate_to_heading_angular_vel") {
} else if (param_name == "controller.rotate_to_heading_angular_vel") {
rotate_to_heading_angular_vel_ = parameter.as_double();
} else if (name == "controller.rotate_to_heading_max_angular_accel") {
} else if (param_name == "controller.rotate_to_heading_max_angular_accel") {
rotate_to_heading_max_angular_accel_ = parameter.as_double();
} else if (name == "controller.projection_time") {
} else if (param_name == "controller.projection_time") {
projection_time_ = parameter.as_double();
} else if (name == "controller.simulation_time_step") {
} else if (param_name == "controller.simulation_time_step") {
simulation_time_step_ = parameter.as_double();
} else if (name == "controller.dock_collision_threshold") {
} else if (param_name == "controller.dock_collision_threshold") {
dock_collision_threshold_ = parameter.as_double();
}

Expand Down
Loading
Loading