Skip to content

Commit

Permalink
nav2_dwb_controller: add shorten_distance parameter
Browse files Browse the repository at this point in the history
Until now, the prune_distance was used as distance threshold to shorten
the upcoming path when shorten_transformed_plan was enabled. However,
the prune and shortening mechanisms are de-correlated mechanisms. One
could wish to use a different shortening distance for upcoming points,
than the prune distance used for passed points. For this reason, a new
parameter "shorten_distance" was added.
  • Loading branch information
DylanDeCoeyer-Quimesis committed Jan 18, 2023
1 parent e77c139 commit d437111
Show file tree
Hide file tree
Showing 3 changed files with 11 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -201,6 +201,7 @@ class DWBLocalPlanner : public nav2_core::Controller
bool debug_trajectory_details_;
rclcpp::Duration transform_tolerance_{0, 0};
bool shorten_transformed_plan_;
double shorten_distance_;

/**
* @brief try to resolve a possibly shortened critic name with the default namespaces and the suffix "Critic"
Expand Down
14 changes: 9 additions & 5 deletions nav2_dwb_controller/dwb_core/src/dwb_local_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -89,6 +89,9 @@ void DWBLocalPlanner::configure(
rclcpp::ParameterValue(true));
declare_parameter_if_not_declared(
node, dwb_plugin_name_ + ".prune_distance",
rclcpp::ParameterValue(1.0));
declare_parameter_if_not_declared(
node, dwb_plugin_name_ + ".shorten_distance",
rclcpp::ParameterValue(2.0));
declare_parameter_if_not_declared(
node, dwb_plugin_name_ + ".debug_trajectory_details",
Expand All @@ -115,6 +118,7 @@ void DWBLocalPlanner::configure(

node->get_parameter(dwb_plugin_name_ + ".prune_plan", prune_plan_);
node->get_parameter(dwb_plugin_name_ + ".prune_distance", prune_distance_);
node->get_parameter(dwb_plugin_name_ + ".shorten_distance", shorten_distance_);
node->get_parameter(dwb_plugin_name_ + ".debug_trajectory_details", debug_trajectory_details_);
node->get_parameter(dwb_plugin_name_ + ".trajectory_generator_name", traj_generator_name);
node->get_parameter(
Expand Down Expand Up @@ -474,7 +478,6 @@ DWBLocalPlanner::transformGlobalPlan(
double dist_threshold = std::max(costmap->getSizeInCellsX(), costmap->getSizeInCellsY()) *
costmap->getResolution() / 2.0;


// If prune_plan is enabled (it is by default) then we want to restrict the
// plan to distances within that range as well.
double prune_dist = prune_distance_;
Expand All @@ -489,12 +492,13 @@ DWBLocalPlanner::transformGlobalPlan(
transform_start_threshold = dist_threshold;
}

// Set the maximum distance we'll include points after the part of the part of
// the plan near the robot (the end of the plan). This determines the amount
// of the plan passed on to the critics
// Set the maximum distance we'll include points after the part of the plan
// near the robot (the end of the plan). This determines the amount of the
// plan passed on to the critics
double transform_end_threshold;
double shorten_dist = shorten_distance_;
if (shorten_transformed_plan_) {
transform_end_threshold = std::min(dist_threshold, prune_dist);
transform_end_threshold = std::min(dist_threshold, shorten_dist);
} else {
transform_end_threshold = dist_threshold;
}
Expand Down
1 change: 1 addition & 0 deletions nav2_system_tests/src/costmap_filters/keepout_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -119,6 +119,7 @@ controller_server:
plugin: "dwb_core::DWBLocalPlanner"
debug_trajectory_details: True
prune_distance: 1.0
shorten_distance: 2.0
min_vel_x: 0.0
min_vel_y: 0.0
max_vel_x: 0.26
Expand Down

0 comments on commit d437111

Please sign in to comment.