Skip to content

Commit

Permalink
removing RPP's use_interpolation param: always on (ros-navigation#3933)
Browse files Browse the repository at this point in the history
Signed-off-by: gg <[email protected]>
  • Loading branch information
SteveMacenski authored and jwallace42 committed Jan 3, 2024
1 parent 9782262 commit 5912913
Show file tree
Hide file tree
Showing 5 changed files with 1 addition and 29 deletions.
2 changes: 0 additions & 2 deletions nav2_regulated_pure_pursuit_controller/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -90,7 +90,6 @@ Note: The maximum allowed time to collision is thresholded by the lookahead poin
| `rotate_to_heading_min_angle` | The difference in the path orientation and the starting robot orientation to trigger a rotate in place, if `use_rotate_to_heading` is enabled. |
| `max_angular_accel` | Maximum allowable angular acceleration while rotating to heading, if enabled |
| `max_robot_pose_search_dist` | Maximum integrated distance along the path to bound the search for the closest pose to the robot. This is set by default to the maximum costmap extent, so it shouldn't be set manually unless there are loops within the local costmap. |
| `use_interpolation` | Enables interpolation between poses on the path for lookahead point selection. Helps sparse paths to avoid inducing discontinuous commanded velocities. Set this to false for a potential performance boost, at the expense of smooth control. |

Example fully-described XML with default parameter values:

Expand Down Expand Up @@ -138,7 +137,6 @@ controller_server:
rotate_to_heading_min_angle: 0.785
max_angular_accel: 3.2
max_robot_pose_search_dist: 10.0
use_interpolation: false
cost_scaling_dist: 0.3
cost_scaling_gain: 1.0
inflation_cost_scaling_factor: 3.0
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,6 @@ struct Parameters
double rotate_to_heading_min_angle;
bool allow_reversing;
double max_robot_pose_search_dist;
bool use_interpolation;
bool use_collision_detection;
double transform_tolerance;
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -90,9 +90,6 @@ ParameterHandler::ParameterHandler(
declare_parameter_if_not_declared(
node, plugin_name_ + ".max_robot_pose_search_dist",
rclcpp::ParameterValue(costmap_size_x / 2.0));
declare_parameter_if_not_declared(
node, plugin_name_ + ".use_interpolation",
rclcpp::ParameterValue(true));
declare_parameter_if_not_declared(
node, plugin_name_ + ".use_collision_detection",
rclcpp::ParameterValue(true));
Expand Down Expand Up @@ -162,9 +159,6 @@ ParameterHandler::ParameterHandler(
params_.max_robot_pose_search_dist = std::numeric_limits<double>::max();
}

node->get_parameter(
plugin_name_ + ".use_interpolation",
params_.use_interpolation);
node->get_parameter(
plugin_name_ + ".use_collision_detection",
params_.use_collision_detection);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -325,7 +325,7 @@ geometry_msgs::msg::PoseStamped RegulatedPurePursuitController::getLookAheadPoin
// If the no pose is not far enough, take the last pose
if (goal_pose_it == transformed_plan.poses.end()) {
goal_pose_it = std::prev(transformed_plan.poses.end());
} else if (params_->use_interpolation && goal_pose_it != transformed_plan.poses.begin()) {
} else if (goal_pose_it != transformed_plan.poses.begin()) {
// Find the point on the line segment between the two poses
// that is exactly the lookahead distance away from the robot pose (the origin)
// This can be found with a closed form for the intersection of a segment and a circle
Expand Down
19 changes: 0 additions & 19 deletions nav2_regulated_pure_pursuit_controller/test/test_regulated_pp.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -379,26 +379,7 @@ TEST(RegulatedPurePursuitTest, lookaheadAPI)
auto pt = ctrl->getLookAheadPointWrapper(dist, path);
EXPECT_EQ(pt.pose.position.x, 1.0);

// test getting next closest point without interpolation
node->set_parameter(
rclcpp::Parameter(
name + ".use_interpolation",
rclcpp::ParameterValue(false)));
ctrl->configure(node, name, tf, costmap);
dist = 3.8;
pt = ctrl->getLookAheadPointWrapper(dist, path);
EXPECT_EQ(pt.pose.position.x, 4.0);

// test end of path
dist = 100.0;
pt = ctrl->getLookAheadPointWrapper(dist, path);
EXPECT_EQ(pt.pose.position.x, 9.0);

// test interpolation
node->set_parameter(
rclcpp::Parameter(
name + ".use_interpolation",
rclcpp::ParameterValue(true)));
ctrl->configure(node, name, tf, costmap);
dist = 3.8;
pt = ctrl->getLookAheadPointWrapper(dist, path);
Expand Down

0 comments on commit 5912913

Please sign in to comment.